Skip to content

Commit a22c65d

Browse files
committed
Merge pull request #104 from mamoll/master
replace much boost usage with C++11 equivalents
2 parents 1473632 + 5b82c3b commit a22c65d

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

68 files changed

+385
-333
lines changed

.travis.yml

+11
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,8 @@
1+
sudo: required
2+
dist: trusty
3+
cache:
4+
apt: true
5+
16
language: cpp
27

38
os:
@@ -17,6 +22,12 @@ matrix:
1722
- os: osx
1823
compiler: gcc
1924

25+
addons:
26+
apt:
27+
packages:
28+
- libflann-dev
29+
- libboost-all-dev
30+
2031
install:
2132
# Install dependencies for FCL
2233
- if [ "$TRAVIS_OS_NAME" = "linux" ]; then 'ci/install_linux.sh' ; fi

CMakeLists.txt

+4-1
Original file line numberDiff line numberDiff line change
@@ -104,7 +104,7 @@ endif()
104104
# endif()
105105

106106

107-
find_package(Boost COMPONENTS thread date_time filesystem system unit_test_framework REQUIRED)
107+
find_package(Boost COMPONENTS date_time filesystem system unit_test_framework REQUIRED)
108108
include_directories(${Boost_INCLUDE_DIR})
109109

110110
if(MSVC)
@@ -145,6 +145,9 @@ add_subdirectory(src)
145145

146146
set(pkg_conf_file_in "${CMAKE_CURRENT_SOURCE_DIR}/fcl.pc.in")
147147
set(pkg_conf_file_out "${CMAKE_CURRENT_BINARY_DIR}/fcl.pc")
148+
if(NOT MSVC)
149+
set(PKG_CFLAGS "-std=c++11")
150+
endif()
148151
configure_file("${pkg_conf_file_in}" "${pkg_conf_file_out}" @ONLY)
149152

150153
install(DIRECTORY include/ DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}

CMakeModules/CompilerSettings.cmake

+7-4
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,11 @@
1+
# force C++11 mode
2+
add_definitions()
3+
14
if(CMAKE_COMPILER_IS_GNUCXX)
2-
add_definitions(-W -Wall -g -Wextra -Wno-missing-field-initializers -Wno-unused-parameter)
5+
add_definitions(-std=c++11 -W -Wall -g -Wextra -Wno-missing-field-initializers -Wno-unused-parameter)
36
endif(CMAKE_COMPILER_IS_GNUCXX)
47
if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang")
5-
add_definitions(-W -Wall -Wextra -Wno-missing-field-initializers -Wno-unused-parameter -Wno-delete-non-virtual-dtor -Wno-overloaded-virtual -Wno-unknown-pragmas)
8+
add_definitions(-std=c++11 -W -Wall -Wextra -Wno-missing-field-initializers -Wno-unused-parameter -Wno-delete-non-virtual-dtor -Wno-overloaded-virtual -Wno-unknown-pragmas -Wno-deprecated-register)
69
endif()
710

811
if(MSVC OR MSVC90 OR MSVC10)
@@ -15,7 +18,7 @@ else()
1518
set(IS_ICPC 0)
1619
endif()
1720
if(IS_ICPC)
18-
add_definitions(-wd191 -wd411 -wd654 -wd1125 -wd1292 -wd1565 -wd1628 -wd2196)
21+
add_definitions(-std=c++11 -wd191 -wd411 -wd654 -wd1125 -wd1292 -wd1565 -wd1628 -wd2196)
1922
set(CMAKE_AR "xiar" CACHE STRING "Intel archiver" FORCE)
2023
set(CMAKE_CXX_FLAGS "-pthread" CACHE STRING "Default compile flags" FORCE)
2124
set(CMAKE_CXX_FLAGS_RELEASE "-O3 -DNDEBUG"
@@ -31,7 +34,7 @@ else()
3134
set(IS_XLC 0)
3235
endif()
3336
if(IS_XLC)
34-
add_definitions(-qpic -q64 -qmaxmem=-1)
37+
add_definitions(-std=c++11 -qpic -q64 -qmaxmem=-1)
3538
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -q64")
3639
set(CMAKE_MODULE_LINKER_FLAGS "${CMAKE_MODULE_LINKER_FLAGS} -q64")
3740
endif(IS_XLC)

CMakeModules/FCLVersion.cmake

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
# set the version in a way CMake can use
22
set(FCL_MAJOR_VERSION 0)
3-
set(FCL_MINOR_VERSION 4)
3+
set(FCL_MINOR_VERSION 5)
44
set(FCL_PATCH_VERSION 0)
55
set(FCL_VERSION "${FCL_MAJOR_VERSION}.${FCL_MINOR_VERSION}.${FCL_PATCH_VERSION}")
66

77
# increment this when we have ABI changes
8-
set(FCL_ABI_VERSION 6)
8+
set(FCL_ABI_VERSION 7)

ci/install_linux.sh

-10
Original file line numberDiff line numberDiff line change
@@ -1,18 +1,8 @@
11
sudo add-apt-repository --yes ppa:libccd-debs/ppa
22
sudo apt-get -qq update
33

4-
########################
5-
# Mendatory dependencies
6-
########################
7-
sudo apt-get -qq --yes --force-yes install cmake
8-
sudo apt-get -qq --yes --force-yes install libboost-all-dev
94
sudo apt-get -qq --yes --force-yes install libccd-dev
105

11-
########################
12-
# Optional dependencies
13-
########################
14-
sudo apt-get -qq --yes --force-yes install libflann-dev
15-
166
# Octomap
177
git clone https://github.com/OctoMap/octomap
188
cd octomap

fcl.pc.in

+1-1
Original file line numberDiff line numberDiff line change
@@ -9,4 +9,4 @@ Description: @PKG_DESC@
99
Version: @FCL_VERSION@
1010
Requires: @PKG_EXTERNAL_DEPS@
1111
Libs: -L${libdir} -lfcl
12-
Cflags: -I${includedir}
12+
Cflags: @PKG_CFLAGS@ -I${includedir}

include/fcl/BV/RSS.h

+3-3
Original file line numberDiff line numberDiff line change
@@ -38,10 +38,10 @@
3838
#ifndef FCL_RSS_H
3939
#define FCL_RSS_H
4040

41-
41+
#include "fcl/math/constants.h"
4242
#include "fcl/math/vec_3f.h"
4343
#include "fcl/math/matrix_3f.h"
44-
#include <boost/math/constants/constants.hpp>
44+
4545

4646
namespace fcl
4747
{
@@ -111,7 +111,7 @@ class RSS
111111
/// @brief Volume of the RSS
112112
inline FCL_REAL volume() const
113113
{
114-
return (l[0] * l[1] * 2 * r + 4 * boost::math::constants::pi<FCL_REAL>() * r * r * r);
114+
return (l[0] * l[1] * 2 * r + 4 * constants::pi * r * r * r);
115115
}
116116

117117
/// @brief Size of the RSS (used in BV_Splitter to order two RSSs)

include/fcl/BVH/BVH_model.h

+3-3
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@
4444
#include "fcl/BVH/BV_splitter.h"
4545
#include "fcl/BVH/BV_fitter.h"
4646
#include <vector>
47-
#include <boost/shared_ptr.hpp>
47+
#include <memory>
4848
#include <boost/noncopyable.hpp>
4949

5050
namespace fcl
@@ -268,10 +268,10 @@ class BVHModel : public CollisionGeometry,
268268
BVHBuildState build_state;
269269

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

273273
/// @brief Fitting rule to fit a BV node to a set of geometry primitives
274-
boost::shared_ptr<BVFitterBase<BV> > bv_fitter;
274+
std::shared_ptr<BVFitterBase<BV> > bv_fitter;
275275

276276

277277
private:

include/fcl/articulated_model/joint.h

+13-14
Original file line numberDiff line numberDiff line change
@@ -45,8 +45,7 @@
4545
#include <vector>
4646
#include <map>
4747
#include <limits>
48-
#include <boost/shared_ptr.hpp>
49-
#include <boost/weak_ptr.hpp>
48+
#include <memory>
5049

5150
namespace fcl
5251
{
@@ -61,7 +60,7 @@ class Joint
6160
{
6261
public:
6362

64-
Joint(const boost::shared_ptr<Link>& link_parent, const boost::shared_ptr<Link>& link_child,
63+
Joint(const std::shared_ptr<Link>& link_parent, const std::shared_ptr<Link>& link_child,
6564
const Transform3f& transform_to_parent,
6665
const std::string& name);
6766

@@ -76,14 +75,14 @@ class Joint
7675

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

79-
boost::shared_ptr<JointConfig> getJointConfig() const;
80-
void setJointConfig(const boost::shared_ptr<JointConfig>& joint_cfg);
78+
std::shared_ptr<JointConfig> getJointConfig() const;
79+
void setJointConfig(const std::shared_ptr<JointConfig>& joint_cfg);
8180

82-
boost::shared_ptr<Link> getParentLink() const;
83-
boost::shared_ptr<Link> getChildLink() const;
81+
std::shared_ptr<Link> getParentLink() const;
82+
std::shared_ptr<Link> getChildLink() const;
8483

85-
void setParentLink(const boost::shared_ptr<Link>& link);
86-
void setChildLink(const boost::shared_ptr<Link>& link);
84+
void setParentLink(const std::shared_ptr<Link>& link);
85+
void setChildLink(const std::shared_ptr<Link>& link);
8786

8887
JointType getJointType() const;
8988

@@ -93,13 +92,13 @@ class Joint
9392
protected:
9493

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

9897
JointType type_;
9998

10099
std::string name_;
101100

102-
boost::shared_ptr<JointConfig> joint_cfg_;
101+
std::shared_ptr<JointConfig> joint_cfg_;
103102

104103
Transform3f transform_to_parent_;
105104
};
@@ -108,7 +107,7 @@ class Joint
108107
class PrismaticJoint : public Joint
109108
{
110109
public:
111-
PrismaticJoint(const boost::shared_ptr<Link>& link_parent, const boost::shared_ptr<Link>& link_child,
110+
PrismaticJoint(const std::shared_ptr<Link>& link_parent, const std::shared_ptr<Link>& link_child,
112111
const Transform3f& transform_to_parent,
113112
const std::string& name,
114113
const Vec3f& axis);
@@ -128,7 +127,7 @@ class PrismaticJoint : public Joint
128127
class RevoluteJoint : public Joint
129128
{
130129
public:
131-
RevoluteJoint(const boost::shared_ptr<Link>& link_parent, const boost::shared_ptr<Link>& link_child,
130+
RevoluteJoint(const std::shared_ptr<Link>& link_parent, const std::shared_ptr<Link>& link_child,
132131
const Transform3f& transform_to_parent,
133132
const std::string& name,
134133
const Vec3f& axis);
@@ -150,7 +149,7 @@ class RevoluteJoint : public Joint
150149
class BallEulerJoint : public Joint
151150
{
152151
public:
153-
BallEulerJoint(const boost::shared_ptr<Link>& link_parent, const boost::shared_ptr<Link>& link_child,
152+
BallEulerJoint(const std::shared_ptr<Link>& link_parent, const std::shared_ptr<Link>& link_child,
154153
const Transform3f& transform_to_parent,
155154
const std::string& name);
156155

include/fcl/articulated_model/joint_config.h

+4-5
Original file line numberDiff line numberDiff line change
@@ -39,8 +39,7 @@
3939
#define FCL_ARTICULATED_MODEL_JOINT_CONFIG_H
4040

4141
#include "fcl/data_types.h"
42-
#include <boost/shared_ptr.hpp>
43-
#include <boost/weak_ptr.hpp>
42+
#include <memory>
4443
#include <vector>
4544

4645
namespace fcl
@@ -55,7 +54,7 @@ class JointConfig
5554

5655
JointConfig(const JointConfig& joint_cfg);
5756

58-
JointConfig(const boost::shared_ptr<Joint>& joint,
57+
JointConfig(const std::shared_ptr<Joint>& joint,
5958
FCL_REAL default_value = 0,
6059
FCL_REAL default_value_min = 0,
6160
FCL_REAL default_value_max = 0);
@@ -84,10 +83,10 @@ class JointConfig
8483

8584
FCL_REAL& getLimitMax(std::size_t i);
8685

87-
boost::shared_ptr<Joint> getJoint() const;
86+
std::shared_ptr<Joint> getJoint() const;
8887

8988
private:
90-
boost::weak_ptr<Joint> joint_;
89+
std::weak_ptr<Joint> joint_;
9190

9291
std::vector<FCL_REAL> values_;
9392
std::vector<FCL_REAL> limits_min_;

include/fcl/articulated_model/link.h

+7-7
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@
4141
#include "fcl/data_types.h"
4242
#include "fcl/collision_object.h"
4343

44-
#include <boost/shared_ptr.hpp>
44+
#include <memory>
4545
#include <vector>
4646

4747
namespace fcl
@@ -58,11 +58,11 @@ class Link
5858

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

61-
void addChildJoint(const boost::shared_ptr<Joint>& joint);
61+
void addChildJoint(const std::shared_ptr<Joint>& joint);
6262

63-
void setParentJoint(const boost::shared_ptr<Joint>& joint);
63+
void setParentJoint(const std::shared_ptr<Joint>& joint);
6464

65-
void addObject(const boost::shared_ptr<CollisionObject>& object);
65+
void addObject(const std::shared_ptr<CollisionObject>& object);
6666

6767
std::size_t getNumChildJoints() const;
6868

@@ -71,11 +71,11 @@ class Link
7171
protected:
7272
std::string name_;
7373

74-
std::vector<boost::shared_ptr<CollisionObject> > objects_;
74+
std::vector<std::shared_ptr<CollisionObject> > objects_;
7575

76-
std::vector<boost::shared_ptr<Joint> > children_joints_;
76+
std::vector<std::shared_ptr<Joint> > children_joints_;
7777

78-
boost::shared_ptr<Joint> parent_joint_;
78+
std::shared_ptr<Joint> parent_joint_;
7979
};
8080

8181
}

include/fcl/articulated_model/model.h

+11-11
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@
4242
#include "fcl/articulated_model/link.h"
4343

4444
#include "fcl/data_types.h"
45-
#include <boost/shared_ptr.hpp>
45+
#include <memory>
4646

4747
#include <map>
4848
#include <stdexcept>
@@ -64,9 +64,9 @@ class Model
6464

6565
const std::string& getName() const;
6666

67-
void addLink(const boost::shared_ptr<Link>& link);
67+
void addLink(const std::shared_ptr<Link>& link);
6868

69-
void addJoint(const boost::shared_ptr<Joint>& joint);
69+
void addJoint(const std::shared_ptr<Joint>& joint);
7070

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

@@ -78,16 +78,16 @@ class Model
7878

7979
std::size_t getNumJoints() const;
8080

81-
boost::shared_ptr<Link> getRoot() const;
82-
boost::shared_ptr<Link> getLink(const std::string& name) const;
83-
boost::shared_ptr<Joint> getJoint(const std::string& name) const;
81+
std::shared_ptr<Link> getRoot() const;
82+
std::shared_ptr<Link> getLink(const std::string& name) const;
83+
std::shared_ptr<Joint> getJoint(const std::string& name) const;
8484

85-
std::vector<boost::shared_ptr<Link> > getLinks() const;
86-
std::vector<boost::shared_ptr<Joint> > getJoints() const;
85+
std::vector<std::shared_ptr<Link> > getLinks() const;
86+
std::vector<std::shared_ptr<Joint> > getJoints() const;
8787
protected:
88-
boost::shared_ptr<Link> root_link_;
89-
std::map<std::string, boost::shared_ptr<Link> > links_;
90-
std::map<std::string, boost::shared_ptr<Joint> > joints_;
88+
std::shared_ptr<Link> root_link_;
89+
std::map<std::string, std::shared_ptr<Link> > links_;
90+
std::map<std::string, std::shared_ptr<Joint> > joints_;
9191

9292
std::string name_;
9393

include/fcl/articulated_model/model_config.h

+4-5
Original file line numberDiff line numberDiff line change
@@ -42,8 +42,7 @@
4242
#include "fcl/articulated_model/joint_config.h"
4343
#include <string>
4444
#include <map>
45-
#include <boost/weak_ptr.hpp>
46-
#include <boost/shared_ptr.hpp>
45+
#include <memory>
4746

4847
namespace fcl
4948
{
@@ -55,13 +54,13 @@ class ModelConfig
5554

5655
ModelConfig(const ModelConfig& model_cfg);
5756

58-
ModelConfig(std::map<std::string, boost::shared_ptr<Joint> > joints_map);
57+
ModelConfig(std::map<std::string, std::shared_ptr<Joint> > joints_map);
5958

6059
JointConfig getJointConfigByJointName(const std::string& joint_name) const;
6160
JointConfig& getJointConfigByJointName(const std::string& joint_name);
6261

63-
JointConfig getJointConfigByJoint(boost::shared_ptr<Joint> joint) const;
64-
JointConfig& getJointConfigByJoint(boost::shared_ptr<Joint> joint);
62+
JointConfig getJointConfigByJoint(std::shared_ptr<Joint> joint) const;
63+
JointConfig& getJointConfigByJoint(std::shared_ptr<Joint> joint);
6564

6665
std::map<std::string, JointConfig> getJointCfgsMap() const
6766
{ return joint_cfgs_map_; }

0 commit comments

Comments
 (0)