Skip to content

Commit

Permalink
Merge pull request #105 from mamoll/master
Browse files Browse the repository at this point in the history
Remove more boost usage and replace with C++11 equivalents.
  • Loading branch information
sherm1 committed Mar 25, 2016
2 parents a22c65d + 3f924f6 commit 0eeb075
Show file tree
Hide file tree
Showing 25 changed files with 90 additions and 119 deletions.
4 changes: 1 addition & 3 deletions include/fcl/BVH/BVH_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,15 +45,13 @@
#include "fcl/BVH/BV_fitter.h"
#include <vector>
#include <memory>
#include <boost/noncopyable.hpp>

namespace fcl
{

/// @brief A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as a degraded version of mesh)
template<typename BV>
class BVHModel : public CollisionGeometry,
private boost::noncopyable
class BVHModel : public CollisionGeometry
{

public:
Expand Down
1 change: 0 additions & 1 deletion include/fcl/broadphase/interval_tree.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,6 @@ namespace fcl

/// @brief Interval trees implemented using red-black-trees as described in
/// the book Introduction_To_Algorithms_ by Cormen, Leisserson, and Rivest.
/// Can be replaced in part by boost::icl::interval_set, which is only supported after boost 1.46 and does not support delete node routine.
struct SimpleInterval
{
public:
Expand Down
4 changes: 2 additions & 2 deletions include/fcl/ccd/interpolation/interpolation_factory.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,15 +44,15 @@
#include <map>

#include <memory>
#include <boost/function.hpp>
#include <functional>

namespace fcl
{

class InterpolationFactory
{
public:
typedef boost::function<std::shared_ptr<Interpolation>(FCL_REAL, FCL_REAL)> CreateFunction;
typedef std::function<std::shared_ptr<Interpolation>(FCL_REAL, FCL_REAL)> CreateFunction;

public:
void registerClass(const InterpolationType type, const CreateFunction create_function);
Expand Down
10 changes: 5 additions & 5 deletions include/fcl/data_types.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,16 +39,16 @@
#define FCL_DATA_TYPES_H

#include <cstddef>
#include <boost/cstdint.hpp>
#include <cstdint>

namespace fcl
{

typedef double FCL_REAL;
typedef boost::uint64_t FCL_INT64;
typedef boost::int64_t FCL_UINT64;
typedef boost::uint32_t FCL_UINT32;
typedef boost::int32_t FCL_INT32;
typedef std::uint_fast64_t FCL_INT64;
typedef std::int_fast64_t FCL_UINT64;
typedef std::uint_fast32_t FCL_UINT32;
typedef std::int_fast32_t FCL_INT32;

/// @brief Triangle with 3 indices for points
class Triangle
Expand Down
1 change: 0 additions & 1 deletion include/fcl/intersect.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@
#define FCL_INTERSECT_H

#include "fcl/math/transform.h"
#include <boost/math/special_functions/erf.hpp>

namespace fcl
{
Expand Down
2 changes: 1 addition & 1 deletion include/fcl/knn/greedy_kcenters.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class GreedyKCenters
{
public:
/// @brief The definition of a distance function
typedef boost::function<double(const _T&, const _T&)> DistanceFunction;
typedef std::function<double(const _T&, const _T&)> DistanceFunction;

GreedyKCenters(void)
{
Expand Down
3 changes: 1 addition & 2 deletions include/fcl/knn/nearest_neighbors.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@

#include <vector>
#include <functional>
#include <boost/function.hpp>

namespace fcl
{
Expand All @@ -51,7 +50,7 @@ class NearestNeighbors
public:

/// @brief The definition of a distance function
typedef boost::function<double(const _T&, const _T&)> DistanceFunction;
typedef std::function<double(const _T&, const _T&)> DistanceFunction;

NearestNeighbors(void)
{
Expand Down
10 changes: 5 additions & 5 deletions include/fcl/knn/nearest_neighbors_GNAT.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#include "fcl/knn/nearest_neighbors.h"
#include "fcl/knn/greedy_kcenters.h"
#include "fcl/exception.h"
#include <boost/unordered_set.hpp>
#include <unordered_set>
#include <queue>
#include <algorithm>

Expand Down Expand Up @@ -239,7 +239,7 @@ class NearestNeighborsGNAT : public NearestNeighbors<_T>
if (!gnat.removed_.empty())
{
out << "Elements marked for removal:\n";
for (typename boost::unordered_set<const _T*>::const_iterator it = gnat.removed_.begin();
for (typename std::unordered_set<const _T*>::const_iterator it = gnat.removed_.begin();
it != gnat.removed_.end(); it++)
out << **it << '\t';
out << std::endl;
Expand All @@ -252,12 +252,12 @@ class NearestNeighborsGNAT : public NearestNeighbors<_T>
void integrityCheck()
{
std::vector<_T> lst;
boost::unordered_set<const _T*> tmp;
std::unordered_set<const _T*> tmp;
// get all elements, including those marked for removal
removed_.swap(tmp);
list(lst);
// check if every element marked for removal is also in the tree
for (typename boost::unordered_set<const _T*>::iterator it=tmp.begin(); it!=tmp.end(); it++)
for (typename std::unordered_set<const _T*>::iterator it=tmp.begin(); it!=tmp.end(); it++)
{
unsigned int i;
for (i=0; i<lst.size(); ++i)
Expand Down Expand Up @@ -689,7 +689,7 @@ class NearestNeighborsGNAT : public NearestNeighbors<_T>
/// \brief The data structure used to split data into subtrees.
GreedyKCenters<_T> pivotSelector_;
/// \brief Cache of removed elements.
boost::unordered_set<const _T*> removed_;
std::unordered_set<const _T*> removed_;
};
}

Expand Down
49 changes: 22 additions & 27 deletions include/fcl/math/sampling.h
Original file line number Diff line number Diff line change
@@ -1,11 +1,8 @@
#ifndef FCL_MATH_SAMPLING_H
#define FCL_MATH_SAMPLING_H

#include <boost/random/mersenne_twister.hpp>
#include <boost/random/uniform_real.hpp>
#include <boost/random/normal_distribution.hpp>
#include <boost/random/variate_generator.hpp>
#include <boost/assign/list_of.hpp>
#include <random>
#include <cassert>
#include "fcl/math/constants.h"
#include "fcl/math/vec_nf.h"
#include "fcl/math/transform.h"
Expand All @@ -30,14 +27,14 @@ class RNG
/// @brief Generate a random real between 0 and 1
double uniform01()
{
return uni_();
return uniDist_(generator_);
}

/// @brief Generate a random real within given bounds: [\e lower_bound, \e upper_bound)
double uniformReal(double lower_bound, double upper_bound)
{
assert(lower_bound <= upper_bound);
return (upper_bound - lower_bound) * uni_() + lower_bound;
return (upper_bound - lower_bound) * uniDist_(generator_) + lower_bound;
}

/// @brief Generate a random integer within given bounds: [\e lower_bound, \e upper_bound]
Expand All @@ -50,19 +47,19 @@ class RNG
/// @brief Generate a random boolean
bool uniformBool()
{
return uni_() <= 0.5;
return uniDist_(generator_) <= 0.5;
}

/// @brief Generate a random real using a normal distribution with mean 0 and variance 1
double gaussian01()
{
return normal_();
return normalDist_(generator_);
}

/// @brief Generate a random real using a normal distribution with given mean and variance
double gaussian(double mean, double stddev)
{
return normal_() * stddev + mean;
return normalDist_(generator_) * stddev + mean;
}

/// @brief Generate a random real using a half-normal distribution. The value is within specified bounds [\e r_min, \e r_max], but with a bias towards \e r_max. The function is implemended using a Gaussian distribution with mean at \e r_max - \e r_min. The distribution is 'folded' around \e r_max axis towards \e r_min. The variance of the distribution is (\e r_max - \e r_min) / \e focus. The higher the focus, the more probable it is that generated numbers are close to \e r_max.
Expand All @@ -84,18 +81,16 @@ class RNG
void ball(double r_min, double r_max, double& x, double& y, double& z);

/// @brief Set the seed for random number generation. Use this function to ensure the same sequence of random numbers is generated.
static void setSeed(boost::uint32_t seed);
static void setSeed(std::uint_fast32_t seed);

/// @brief Get the seed used for random number generation. Passing the returned value to setSeed() at a subsequent execution of the code will ensure deterministic (repeatable) behaviour. Useful for debugging.
static boost::uint32_t getSeed();
static std::uint_fast32_t getSeed();

private:

boost::mt19937 generator_;
boost::uniform_real<> uniDist_;
boost::normal_distribution<> normalDist_;
boost::variate_generator<boost::mt19937&, boost::uniform_real<> > uni_;
boost::variate_generator<boost::mt19937&, boost::normal_distribution<> > normal_;
std::mt19937 generator_;
std::uniform_real_distribution<> uniDist_;
std::normal_distribution<> normalDist_;

};

Expand Down Expand Up @@ -160,8 +155,8 @@ class SamplerSE2 : public SamplerBase
{}

SamplerSE2(FCL_REAL x_min, FCL_REAL x_max,
FCL_REAL y_min, FCL_REAL y_max) : lower_bound(boost::assign::list_of<FCL_REAL>(x_min)(y_min).convert_to_container<std::vector<FCL_REAL> >()),
upper_bound(boost::assign::list_of<FCL_REAL>(x_max)(y_max).convert_to_container<std::vector<FCL_REAL> >())
FCL_REAL y_min, FCL_REAL y_max) : lower_bound(std::vector<FCL_REAL>({x_min, y_min})),
upper_bound(std::vector<FCL_REAL>({x_max, y_max}))

{}

Expand Down Expand Up @@ -248,8 +243,8 @@ class SamplerSE3Euler : public SamplerBase
{}

SamplerSE3Euler(const Vec3f& lower_bound_,
const Vec3f& upper_bound_) : lower_bound(boost::assign::list_of<FCL_REAL>(lower_bound_[0])(lower_bound_[1])(lower_bound_[2]).convert_to_container<std::vector<FCL_REAL> >()),
upper_bound(boost::assign::list_of<FCL_REAL>(upper_bound_[0])(upper_bound_[1])(upper_bound_[2]).convert_to_container<std::vector<FCL_REAL> >())
const Vec3f& upper_bound_) : lower_bound(std::vector<FCL_REAL>({lower_bound_[0], lower_bound_[1], lower_bound_[2]})),
upper_bound(std::vector<FCL_REAL>({upper_bound_[0], upper_bound_[1], upper_bound_[2]}))
{}

void setBound(const Vecnf<3>& lower_bound_,
Expand All @@ -263,8 +258,8 @@ class SamplerSE3Euler : public SamplerBase
void setBound(const Vec3f& lower_bound_,
const Vec3f& upper_bound_)
{
lower_bound = Vecnf<3>(boost::assign::list_of<FCL_REAL>(lower_bound_[0])(lower_bound_[1])(lower_bound_[2]).convert_to_container<std::vector<FCL_REAL> >());
upper_bound = Vecnf<3>(boost::assign::list_of<FCL_REAL>(upper_bound_[0])(upper_bound_[1])(upper_bound_[2]).convert_to_container<std::vector<FCL_REAL> >());
lower_bound = Vecnf<3>(std::vector<FCL_REAL>({lower_bound_[0], lower_bound_[1], lower_bound_[2]}));
upper_bound = Vecnf<3>(std::vector<FCL_REAL>({upper_bound_[0], upper_bound_[1], upper_bound_[2]}));
}

void getBound(Vecnf<3>& lower_bound_,
Expand Down Expand Up @@ -319,8 +314,8 @@ class SamplerSE3Quat : public SamplerBase
{}

SamplerSE3Quat(const Vec3f& lower_bound_,
const Vec3f& upper_bound_) : lower_bound(boost::assign::list_of<FCL_REAL>(lower_bound_[0])(lower_bound_[1])(lower_bound_[2]).convert_to_container<std::vector<FCL_REAL> >()),
upper_bound(boost::assign::list_of<FCL_REAL>(upper_bound_[0])(upper_bound_[1])(upper_bound_[2]).convert_to_container<std::vector<FCL_REAL> >())
const Vec3f& upper_bound_) : lower_bound(std::vector<FCL_REAL>({lower_bound_[0], lower_bound_[1], lower_bound_[2]})),
upper_bound(std::vector<FCL_REAL>({upper_bound_[0], upper_bound_[1], upper_bound_[2]}))
{}


Expand All @@ -335,8 +330,8 @@ class SamplerSE3Quat : public SamplerBase
void setBound(const Vec3f& lower_bound_,
const Vec3f& upper_bound_)
{
lower_bound = Vecnf<3>(boost::assign::list_of<FCL_REAL>(lower_bound_[0])(lower_bound_[1])(lower_bound_[2]).convert_to_container<std::vector<FCL_REAL> >());
upper_bound = Vecnf<3>(boost::assign::list_of<FCL_REAL>(upper_bound_[0])(upper_bound_[1])(upper_bound_[2]).convert_to_container<std::vector<FCL_REAL> >());
lower_bound = Vecnf<3>(std::vector<FCL_REAL>({lower_bound_[0], lower_bound_[1], lower_bound_[2]}));
upper_bound = Vecnf<3>(std::vector<FCL_REAL>({upper_bound_[0], upper_bound_[1], upper_bound_[2]}));
}


Expand Down
4 changes: 2 additions & 2 deletions include/fcl/math/transform.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#define FCL_TRANSFORM_H

#include "fcl/math/matrix_3f.h"
#include <boost/thread/mutex.hpp>
#include <mutex>

namespace fcl
{
Expand Down Expand Up @@ -182,7 +182,7 @@ static inline std::ostream& operator << (std::ostream& o, const Quaternion3f& q)
/// @brief Simple transform class used locally by InterpMotion
class Transform3f
{
boost::mutex lock_;
std::mutex lock_;

/// @brief Whether matrix cache is set
mutable bool matrix_set;
Expand Down
1 change: 0 additions & 1 deletion include/fcl/math/vec_nf.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
#include <iostream>
#include <limits>
#include <vector>
#include <boost/array.hpp>
#include <cstdarg>
#include "fcl/data_types.h"

Expand Down
8 changes: 4 additions & 4 deletions include/fcl/octree.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@


#include <memory>
#include <boost/array.hpp>
#include <array>

#include <octomap/octomap.h>
#include "fcl/BV/AABB.h"
Expand Down Expand Up @@ -134,9 +134,9 @@ class OcTree : public CollisionGeometry

/// @brief transform the octree into a bunch of boxes; uncertainty information is kept in the boxes. However, we
/// only keep the occupied boxes (i.e., the boxes whose occupied probability is higher enough).
inline std::vector<boost::array<FCL_REAL, 6> > toBoxes() const
inline std::vector<std::array<FCL_REAL, 6> > toBoxes() const
{
std::vector<boost::array<FCL_REAL, 6> > boxes;
std::vector<std::array<FCL_REAL, 6> > boxes;
boxes.reserve(tree->size() / 2);
for(octomap::OcTree::iterator it = tree->begin(tree->getTreeDepth()), end = tree->end();
it != end;
Expand All @@ -152,7 +152,7 @@ class OcTree : public CollisionGeometry
FCL_REAL c = (*it).getOccupancy();
FCL_REAL t = tree->getOccupancyThres();

boost::array<FCL_REAL, 6> box = {{x, y, z, size, c, t}};
std::array<FCL_REAL, 6> box = {{x, y, z, size, c, t}};
boxes.push_back(box);
}
}
Expand Down
20 changes: 11 additions & 9 deletions include/fcl/profile.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,7 @@
#include <iostream>
#include <thread>
#include <mutex>
#include <boost/noncopyable.hpp>
#include <boost/date_time/posix_time/posix_time.hpp>
#include <chrono>

namespace fcl
{
Expand All @@ -71,29 +70,29 @@ namespace time
{

/// @brief Representation of a point in time
typedef boost::posix_time::ptime point;
typedef std::chrono::system_clock::time_point point;

/// @brief Representation of a time duration
typedef boost::posix_time::time_duration duration;
typedef std::chrono::system_clock::duration duration;

/// @brief Get the current time point
inline point now(void)
{
return boost::posix_time::microsec_clock::universal_time();
return std::chrono::system_clock::now();
}

/// @brief Return the time duration representing a given number of seconds
inline duration seconds(double sec)
{
long s = (long)sec;
long us = (long)((sec - s) * 1000000);
return boost::posix_time::seconds(s) + boost::posix_time::microseconds(us);
return std::chrono::seconds(s) + std::chrono::microseconds(us);
}

/// @brief Return the number of seconds that a time duration represents
inline double seconds(const duration &d)
{
return (double)d.total_microseconds() / 1000000.0;
return std::chrono::duration<double>(d).count();
}

}
Expand All @@ -106,9 +105,12 @@ namespace tools
/// external profiling tools in that it allows the user to count
/// time spent in various bits of code (sub-function granularity)
/// or count how many times certain pieces of code are executed.
class Profiler : private boost::noncopyable
class Profiler
{
public:
// non-copyable
Profiler(const Profiler&) = delete;
Profiler& operator=(const Profiler&) = delete;

/// @brief This instance will call Profiler::begin() when constructed and Profiler::end() when it goes out of scope.
class ScopedBlock
Expand Down Expand Up @@ -267,7 +269,7 @@ class Profiler : private boost::noncopyable
/// @brief Information about time spent in a section of the code
struct TimeInfo
{
TimeInfo(void) : total(0, 0, 0, 0), shortest(boost::posix_time::pos_infin), longest(boost::posix_time::neg_infin), parts(0)
TimeInfo(void) : total(time::seconds(0.)), shortest(time::duration::max()), longest(time::duration::min()), parts(0)
{
}

Expand Down
Loading

0 comments on commit 0eeb075

Please sign in to comment.