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 all commits
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
11 changes: 11 additions & 0 deletions .travis.yml
Original file line number Diff line number Diff line change
@@ -1,3 +1,8 @@
sudo: required
dist: trusty
cache:
apt: true

language: cpp

os:
Expand All @@ -17,6 +22,12 @@ matrix:
- os: osx
compiler: gcc

addons:
apt:
packages:
- libflann-dev
- libboost-all-dev

install:
# Install dependencies for FCL
- if [ "$TRAVIS_OS_NAME" = "linux" ]; then 'ci/install_linux.sh' ; fi
Expand Down
5 changes: 4 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ endif()
# endif()


find_package(Boost COMPONENTS thread date_time filesystem system unit_test_framework REQUIRED)
find_package(Boost COMPONENTS date_time filesystem system unit_test_framework REQUIRED)
include_directories(${Boost_INCLUDE_DIR})

if(MSVC)
Expand Down Expand Up @@ -145,6 +145,9 @@ add_subdirectory(src)

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

install(DIRECTORY include/ DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}
Expand Down
11 changes: 7 additions & 4 deletions CMakeModules/CompilerSettings.cmake
Original file line number Diff line number Diff line change
@@ -1,8 +1,11 @@
# force C++11 mode
add_definitions()

if(CMAKE_COMPILER_IS_GNUCXX)
add_definitions(-W -Wall -g -Wextra -Wno-missing-field-initializers -Wno-unused-parameter)
add_definitions(-std=c++11 -W -Wall -g -Wextra -Wno-missing-field-initializers -Wno-unused-parameter)
endif(CMAKE_COMPILER_IS_GNUCXX)
if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang")
add_definitions(-W -Wall -Wextra -Wno-missing-field-initializers -Wno-unused-parameter -Wno-delete-non-virtual-dtor -Wno-overloaded-virtual -Wno-unknown-pragmas)
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)
endif()

if(MSVC OR MSVC90 OR MSVC10)
Expand All @@ -15,7 +18,7 @@ else()
set(IS_ICPC 0)
endif()
if(IS_ICPC)
add_definitions(-wd191 -wd411 -wd654 -wd1125 -wd1292 -wd1565 -wd1628 -wd2196)
add_definitions(-std=c++11 -wd191 -wd411 -wd654 -wd1125 -wd1292 -wd1565 -wd1628 -wd2196)
set(CMAKE_AR "xiar" CACHE STRING "Intel archiver" FORCE)
set(CMAKE_CXX_FLAGS "-pthread" CACHE STRING "Default compile flags" FORCE)
set(CMAKE_CXX_FLAGS_RELEASE "-O3 -DNDEBUG"
Expand All @@ -31,7 +34,7 @@ else()
set(IS_XLC 0)
endif()
if(IS_XLC)
add_definitions(-qpic -q64 -qmaxmem=-1)
add_definitions(-std=c++11 -qpic -q64 -qmaxmem=-1)
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -q64")
set(CMAKE_MODULE_LINKER_FLAGS "${CMAKE_MODULE_LINKER_FLAGS} -q64")
endif(IS_XLC)
Expand Down
4 changes: 2 additions & 2 deletions CMakeModules/FCLVersion.cmake
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# set the version in a way CMake can use
set(FCL_MAJOR_VERSION 0)
set(FCL_MINOR_VERSION 4)
set(FCL_MINOR_VERSION 5)
set(FCL_PATCH_VERSION 0)
set(FCL_VERSION "${FCL_MAJOR_VERSION}.${FCL_MINOR_VERSION}.${FCL_PATCH_VERSION}")

# increment this when we have ABI changes
set(FCL_ABI_VERSION 6)
set(FCL_ABI_VERSION 7)
10 changes: 0 additions & 10 deletions ci/install_linux.sh
Original file line number Diff line number Diff line change
@@ -1,18 +1,8 @@
sudo add-apt-repository --yes ppa:libccd-debs/ppa
sudo apt-get -qq update

########################
# Mendatory dependencies
########################
sudo apt-get -qq --yes --force-yes install cmake
sudo apt-get -qq --yes --force-yes install libboost-all-dev
sudo apt-get -qq --yes --force-yes install libccd-dev

########################
# Optional dependencies
########################
sudo apt-get -qq --yes --force-yes install libflann-dev

# Octomap
git clone https://github.com/OctoMap/octomap
cd octomap
Expand Down
2 changes: 1 addition & 1 deletion fcl.pc.in
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,4 @@ Description: @PKG_DESC@
Version: @FCL_VERSION@
Requires: @PKG_EXTERNAL_DEPS@
Libs: -L${libdir} -lfcl
Cflags: -I${includedir}
Cflags: @PKG_CFLAGS@ -I${includedir}
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 "fcl/math/constants.h"
#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 * constants::pi * r * r * r);
}

/// @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
Loading