Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

replace much boost usage with C++11 equivalents #104

Merged
merged 4 commits into from
Mar 24, 2016
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions CMakeModules/CompilerSettings.cmake
Original file line number Diff line number Diff line change
@@ -1,3 +1,6 @@
# force C++11 mode
add_definitions(-std=c++11)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This causes zillions of warnings on Windows -- that should only be added for gcc & clang.


if(CMAKE_COMPILER_IS_GNUCXX)
add_definitions(-W -Wall -g -Wextra -Wno-missing-field-initializers -Wno-unused-parameter)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think you could just move the -std=c++11 here also.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

👍

endif(CMAKE_COMPILER_IS_GNUCXX)
Expand Down
6 changes: 3 additions & 3 deletions include/fcl/BV/RSS.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,10 @@
#ifndef FCL_RSS_H
#define FCL_RSS_H


#include <math.h>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nitpick: I would prefer to use <cmath> since this is a C++ standard library header while <math.h> is a header defined by the C standard library.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

👍 for #include <cmath>. Shouldn't use any C headers.

#include "fcl/math/vec_3f.h"
#include "fcl/math/matrix_3f.h"
#include <boost/math/constants/constants.hpp>


namespace fcl
{
Expand Down Expand Up @@ -111,7 +111,7 @@ class RSS
/// @brief Volume of the RSS
inline FCL_REAL volume() const
{
return (l[0] * l[1] * 2 * r + 4 * boost::math::constants::pi<FCL_REAL>() * r * r * r);
return (l[0] * l[1] * 2 * r + 4 * M_PI * r * r * r);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Two problems with M_PI:

  • it is a macro and hence untyped; needs to have type FCL_REAL
  • it is non-standard (it is a Posix feature, not a C++11 one)

Since "pi" is the only boost math constant FCL used, I think the simplest thing would be to define an fcl::kPi or whatever that could be defined in a common header with something like

constexpr FCL_REAL kPi=FCL_REAL(/*lots of digits of pi copied from a reliable source*/);

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

M_PI caused compilation failures in Visual Studio 2015.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

M_PI works with visual studio if you define _USE_MATH_DEFINES before including cmath

#ifndef _USE_MATH_DEFINES
# define _USE_MATH_DEFINES
#endif

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

M_PI works with visual studio if you define _USE_MATH_DEFINES

Thanks -- I know about that but it's a non-standard hack so I think Mark's fcl::constants::pi idea is better.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

sounds good

}

/// @brief Size of the RSS (used in BV_Splitter to order two RSSs)
Expand Down
6 changes: 3 additions & 3 deletions include/fcl/BVH/BVH_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
#include "fcl/BVH/BV_splitter.h"
#include "fcl/BVH/BV_fitter.h"
#include <vector>
#include <boost/shared_ptr.hpp>
#include <memory>
#include <boost/noncopyable.hpp>

namespace fcl
Expand Down Expand Up @@ -268,10 +268,10 @@ class BVHModel : public CollisionGeometry,
BVHBuildState build_state;

/// @brief Split rule to split one BV node into two children
boost::shared_ptr<BVSplitterBase<BV> > bv_splitter;
std::shared_ptr<BVSplitterBase<BV> > bv_splitter;

/// @brief Fitting rule to fit a BV node to a set of geometry primitives
boost::shared_ptr<BVFitterBase<BV> > bv_fitter;
std::shared_ptr<BVFitterBase<BV> > bv_fitter;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is a change to the public API, should we bump the major version number?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

As far as I know, we might don't need to bump the major version number because FCL is still in 0.y.z.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

good point, we should at least bump the minor version then



private:
Expand Down
27 changes: 13 additions & 14 deletions include/fcl/articulated_model/joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,7 @@
#include <vector>
#include <map>
#include <limits>
#include <boost/shared_ptr.hpp>
#include <boost/weak_ptr.hpp>
#include <memory>

namespace fcl
{
Expand All @@ -61,7 +60,7 @@ class Joint
{
public:

Joint(const boost::shared_ptr<Link>& link_parent, const boost::shared_ptr<Link>& link_child,
Joint(const std::shared_ptr<Link>& link_parent, const std::shared_ptr<Link>& link_child,
const Transform3f& transform_to_parent,
const std::string& name);

Expand All @@ -76,14 +75,14 @@ class Joint

virtual std::size_t getNumDofs() const = 0;

boost::shared_ptr<JointConfig> getJointConfig() const;
void setJointConfig(const boost::shared_ptr<JointConfig>& joint_cfg);
std::shared_ptr<JointConfig> getJointConfig() const;
void setJointConfig(const std::shared_ptr<JointConfig>& joint_cfg);

boost::shared_ptr<Link> getParentLink() const;
boost::shared_ptr<Link> getChildLink() const;
std::shared_ptr<Link> getParentLink() const;
std::shared_ptr<Link> getChildLink() const;

void setParentLink(const boost::shared_ptr<Link>& link);
void setChildLink(const boost::shared_ptr<Link>& link);
void setParentLink(const std::shared_ptr<Link>& link);
void setChildLink(const std::shared_ptr<Link>& link);

JointType getJointType() const;

Expand All @@ -93,13 +92,13 @@ class Joint
protected:

/// links to parent and child are only for connection, so weak_ptr to avoid cyclic dependency
boost::weak_ptr<Link> link_parent_, link_child_;
std::weak_ptr<Link> link_parent_, link_child_;

JointType type_;

std::string name_;

boost::shared_ptr<JointConfig> joint_cfg_;
std::shared_ptr<JointConfig> joint_cfg_;

Transform3f transform_to_parent_;
};
Expand All @@ -108,7 +107,7 @@ class Joint
class PrismaticJoint : public Joint
{
public:
PrismaticJoint(const boost::shared_ptr<Link>& link_parent, const boost::shared_ptr<Link>& link_child,
PrismaticJoint(const std::shared_ptr<Link>& link_parent, const std::shared_ptr<Link>& link_child,
const Transform3f& transform_to_parent,
const std::string& name,
const Vec3f& axis);
Expand All @@ -128,7 +127,7 @@ class PrismaticJoint : public Joint
class RevoluteJoint : public Joint
{
public:
RevoluteJoint(const boost::shared_ptr<Link>& link_parent, const boost::shared_ptr<Link>& link_child,
RevoluteJoint(const std::shared_ptr<Link>& link_parent, const std::shared_ptr<Link>& link_child,
const Transform3f& transform_to_parent,
const std::string& name,
const Vec3f& axis);
Expand All @@ -150,7 +149,7 @@ class RevoluteJoint : public Joint
class BallEulerJoint : public Joint
{
public:
BallEulerJoint(const boost::shared_ptr<Link>& link_parent, const boost::shared_ptr<Link>& link_child,
BallEulerJoint(const std::shared_ptr<Link>& link_parent, const std::shared_ptr<Link>& link_child,
const Transform3f& transform_to_parent,
const std::string& name);

Expand Down
9 changes: 4 additions & 5 deletions include/fcl/articulated_model/joint_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,7 @@
#define FCL_ARTICULATED_MODEL_JOINT_CONFIG_H

#include "fcl/data_types.h"
#include <boost/shared_ptr.hpp>
#include <boost/weak_ptr.hpp>
#include <memory>
#include <vector>

namespace fcl
Expand All @@ -55,7 +54,7 @@ class JointConfig

JointConfig(const JointConfig& joint_cfg);

JointConfig(const boost::shared_ptr<Joint>& joint,
JointConfig(const std::shared_ptr<Joint>& joint,
FCL_REAL default_value = 0,
FCL_REAL default_value_min = 0,
FCL_REAL default_value_max = 0);
Expand Down Expand Up @@ -84,10 +83,10 @@ class JointConfig

FCL_REAL& getLimitMax(std::size_t i);

boost::shared_ptr<Joint> getJoint() const;
std::shared_ptr<Joint> getJoint() const;

private:
boost::weak_ptr<Joint> joint_;
std::weak_ptr<Joint> joint_;

std::vector<FCL_REAL> values_;
std::vector<FCL_REAL> limits_min_;
Expand Down
14 changes: 7 additions & 7 deletions include/fcl/articulated_model/link.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
#include "fcl/data_types.h"
#include "fcl/collision_object.h"

#include <boost/shared_ptr.hpp>
#include <memory>
#include <vector>

namespace fcl
Expand All @@ -58,11 +58,11 @@ class Link

void setName(const std::string& name);

void addChildJoint(const boost::shared_ptr<Joint>& joint);
void addChildJoint(const std::shared_ptr<Joint>& joint);

void setParentJoint(const boost::shared_ptr<Joint>& joint);
void setParentJoint(const std::shared_ptr<Joint>& joint);

void addObject(const boost::shared_ptr<CollisionObject>& object);
void addObject(const std::shared_ptr<CollisionObject>& object);

std::size_t getNumChildJoints() const;

Expand All @@ -71,11 +71,11 @@ class Link
protected:
std::string name_;

std::vector<boost::shared_ptr<CollisionObject> > objects_;
std::vector<std::shared_ptr<CollisionObject> > objects_;

std::vector<boost::shared_ptr<Joint> > children_joints_;
std::vector<std::shared_ptr<Joint> > children_joints_;

boost::shared_ptr<Joint> parent_joint_;
std::shared_ptr<Joint> parent_joint_;
};

}
Expand Down
22 changes: 11 additions & 11 deletions include/fcl/articulated_model/model.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#include "fcl/articulated_model/link.h"

#include "fcl/data_types.h"
#include <boost/shared_ptr.hpp>
#include <memory>

#include <map>
#include <stdexcept>
Expand All @@ -64,9 +64,9 @@ class Model

const std::string& getName() const;

void addLink(const boost::shared_ptr<Link>& link);
void addLink(const std::shared_ptr<Link>& link);

void addJoint(const boost::shared_ptr<Joint>& joint);
void addJoint(const std::shared_ptr<Joint>& joint);

void initRoot(const std::map<std::string, std::string>& link_parent_tree);

Expand All @@ -78,16 +78,16 @@ class Model

std::size_t getNumJoints() const;

boost::shared_ptr<Link> getRoot() const;
boost::shared_ptr<Link> getLink(const std::string& name) const;
boost::shared_ptr<Joint> getJoint(const std::string& name) const;
std::shared_ptr<Link> getRoot() const;
std::shared_ptr<Link> getLink(const std::string& name) const;
std::shared_ptr<Joint> getJoint(const std::string& name) const;

std::vector<boost::shared_ptr<Link> > getLinks() const;
std::vector<boost::shared_ptr<Joint> > getJoints() const;
std::vector<std::shared_ptr<Link> > getLinks() const;
std::vector<std::shared_ptr<Joint> > getJoints() const;
protected:
boost::shared_ptr<Link> root_link_;
std::map<std::string, boost::shared_ptr<Link> > links_;
std::map<std::string, boost::shared_ptr<Joint> > joints_;
std::shared_ptr<Link> root_link_;
std::map<std::string, std::shared_ptr<Link> > links_;
std::map<std::string, std::shared_ptr<Joint> > joints_;

std::string name_;

Expand Down
9 changes: 4 additions & 5 deletions include/fcl/articulated_model/model_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,7 @@
#include "fcl/articulated_model/joint_config.h"
#include <string>
#include <map>
#include <boost/weak_ptr.hpp>
#include <boost/shared_ptr.hpp>
#include <memory>

namespace fcl
{
Expand All @@ -55,13 +54,13 @@ class ModelConfig

ModelConfig(const ModelConfig& model_cfg);

ModelConfig(std::map<std::string, boost::shared_ptr<Joint> > joints_map);
ModelConfig(std::map<std::string, std::shared_ptr<Joint> > joints_map);

JointConfig getJointConfigByJointName(const std::string& joint_name) const;
JointConfig& getJointConfigByJointName(const std::string& joint_name);

JointConfig getJointConfigByJoint(boost::shared_ptr<Joint> joint) const;
JointConfig& getJointConfigByJoint(boost::shared_ptr<Joint> joint);
JointConfig getJointConfigByJoint(std::shared_ptr<Joint> joint) const;
JointConfig& getJointConfigByJoint(std::shared_ptr<Joint> joint);

std::map<std::string, JointConfig> getJointCfgsMap() const
{ return joint_cfgs_map_; }
Expand Down
10 changes: 5 additions & 5 deletions include/fcl/broadphase/broadphase_dynamic_AABB_tree.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,8 @@
#include "fcl/broadphase/hierarchy_tree.h"
#include "fcl/BV/BV.h"
#include "fcl/shape/geometric_shapes_utility.h"
#include <boost/unordered_map.hpp>
#include <boost/bind.hpp>
#include <unordered_map>
#include <functional>
#include <limits>


Expand All @@ -55,7 +55,7 @@ class DynamicAABBTreeCollisionManager : public BroadPhaseCollisionManager
{
public:
typedef NodeBase<AABB> DynamicAABBNode;
typedef boost::unordered_map<CollisionObject*, DynamicAABBNode*> DynamicAABBTable;
typedef std::unordered_map<CollisionObject*, DynamicAABBNode*> DynamicAABBTable;

int max_tree_nonbalanced_level;
int tree_incremental_balance_pass;
Expand Down Expand Up @@ -114,7 +114,7 @@ class DynamicAABBTreeCollisionManager : public BroadPhaseCollisionManager
void getObjects(std::vector<CollisionObject*>& objs) const
{
objs.resize(this->size());
std::transform(table.begin(), table.end(), objs.begin(), boost::bind(&DynamicAABBTable::value_type::first, _1));
std::transform(table.begin(), table.end(), objs.begin(), std::bind(&DynamicAABBTable::value_type::first, std::placeholders::_1));
}

/// @brief perform collision test between one object and all the objects belonging to the manager
Expand Down Expand Up @@ -152,7 +152,7 @@ class DynamicAABBTreeCollisionManager : public BroadPhaseCollisionManager

private:
HierarchyTree<AABB> dtree;
boost::unordered_map<CollisionObject*, DynamicAABBNode*> table;
std::unordered_map<CollisionObject*, DynamicAABBNode*> table;

bool setup_;

Expand Down
10 changes: 5 additions & 5 deletions include/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,8 @@
#include "fcl/broadphase/hierarchy_tree.h"
#include "fcl/BV/BV.h"
#include "fcl/shape/geometric_shapes_utility.h"
#include <boost/unordered_map.hpp>
#include <boost/bind.hpp>
#include <unordered_map>
#include <functional>
#include <limits>


Expand All @@ -54,7 +54,7 @@ class DynamicAABBTreeCollisionManager_Array : public BroadPhaseCollisionManager
{
public:
typedef implementation_array::NodeBase<AABB> DynamicAABBNode;
typedef boost::unordered_map<CollisionObject*, size_t> DynamicAABBTable;
typedef std::unordered_map<CollisionObject*, size_t> DynamicAABBTable;

int max_tree_nonbalanced_level;
int tree_incremental_balance_pass;
Expand Down Expand Up @@ -112,7 +112,7 @@ class DynamicAABBTreeCollisionManager_Array : public BroadPhaseCollisionManager
void getObjects(std::vector<CollisionObject*>& objs) const
{
objs.resize(this->size());
std::transform(table.begin(), table.end(), objs.begin(), boost::bind(&DynamicAABBTable::value_type::first, _1));
std::transform(table.begin(), table.end(), objs.begin(), std::bind(&DynamicAABBTable::value_type::first, std::placeholders::_1));
}

/// @brief perform collision test between one object and all the objects belonging to the manager
Expand Down Expand Up @@ -150,7 +150,7 @@ class DynamicAABBTreeCollisionManager_Array : public BroadPhaseCollisionManager

private:
implementation_array::HierarchyTree<AABB> dtree;
boost::unordered_map<CollisionObject*, size_t> table;
std::unordered_map<CollisionObject*, size_t> table;

bool setup_;

Expand Down
8 changes: 7 additions & 1 deletion include/fcl/broadphase/broadphase_interval_tree.h
Original file line number Diff line number Diff line change
Expand Up @@ -109,9 +109,10 @@ class IntervalTreeCollisionManager : public BroadPhaseCollisionManager
/// @brief the number of objects managed by the manager
inline size_t size() const { return endpoints[0].size() / 2; }

protected:


protected:

/// @brief SAP end point
struct EndPoint
{
Expand All @@ -123,6 +124,11 @@ class IntervalTreeCollisionManager : public BroadPhaseCollisionManager

/// @brief tag for whether it is a lower bound or higher bound of an interval, 0 for lo, and 1 for hi
char minmax;

bool operator<(const EndPoint &p) const
{
return value < p.value;
}
};

/// @brief Extention interval tree's interval to SAP interval, adding more information
Expand Down
4 changes: 2 additions & 2 deletions include/fcl/broadphase/hash.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#include <set>
#include <vector>
#include <list>
#include <boost/unordered_map.hpp>
#include <unordered_map>

namespace fcl
{
Expand Down Expand Up @@ -123,7 +123,7 @@ class SimpleHashTable


template<typename U, typename V>
class unordered_map_hash_table : public boost::unordered_map<U, V> {};
class unordered_map_hash_table : public std::unordered_map<U, V> {};

/// @brief A hash table implemented using unordered_map
template<typename Key, typename Data, typename HashFnc, template<typename, typename> class TableT = unordered_map_hash_table>
Expand Down
Loading