diff --git a/include/geometric_shapes/bodies.h b/include/geometric_shapes/bodies.h index 8285fc7d..fa665744 100644 --- a/include/geometric_shapes/bodies.h +++ b/include/geometric_shapes/bodies.h @@ -37,13 +37,17 @@ #ifndef GEOMETRIC_SHAPES_BODIES_ #define GEOMETRIC_SHAPES_BODIES_ +#if __cplusplus <= 199711L +#error This header requires at least C++11 +#endif + #include "geometric_shapes/shapes.h" #include -#include #include -#include #include #include +#include +#include /** \brief This set of classes allows quickly detecting whether a given point is inside an object or not. This capability is useful when removing @@ -74,10 +78,10 @@ struct BoundingCylinder class Body; /** \brief Shared pointer to a Body */ -typedef boost::shared_ptr BodyPtr; +typedef std::shared_ptr BodyPtr; /** \brief Shared pointer to a const Body */ -typedef boost::shared_ptr BodyConstPtr; +typedef std::shared_ptr BodyConstPtr; /** \brief A body is a shape + its pose. Point inclusion, ray intersection can be tested, volumes and bounding spheres can @@ -456,7 +460,7 @@ class ConvexMesh : public Body }; // shape-dependent data; keep this in one struct so that a cheap pointer copy can be done in cloneAt() - boost::shared_ptr mesh_data_; + std::shared_ptr mesh_data_; // pose/padding/scaling-dependent values & values computed for convenience and fast upcoming computations Eigen::Affine3d i_pose_; @@ -471,7 +475,7 @@ class ConvexMesh : public Body EigenSTL::vector_Vector3d *scaled_vertices_; private: - boost::scoped_ptr scaled_vertices_storage_; + std::unique_ptr scaled_vertices_storage_; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -528,10 +532,10 @@ class BodyVector }; /** \brief Shared pointer to a Body */ -typedef boost::shared_ptr BodyPtr; +typedef std::shared_ptr BodyPtr; /** \brief Shared pointer to a const Body */ -typedef boost::shared_ptr BodyConstPtr; +typedef std::shared_ptr BodyConstPtr; } diff --git a/include/geometric_shapes/shapes.h b/include/geometric_shapes/shapes.h index 3526e964..13d1c272 100644 --- a/include/geometric_shapes/shapes.h +++ b/include/geometric_shapes/shapes.h @@ -44,7 +44,6 @@ #include #include #include -#include #include #include @@ -270,10 +269,10 @@ class OcTree : public Shape /** \brief Shared pointer to a Shape */ -typedef boost::shared_ptr ShapePtr; +typedef std::shared_ptr ShapePtr; /** \brief Shared pointer to a const Shape */ -typedef boost::shared_ptr ShapeConstPtr; +typedef std::shared_ptr ShapeConstPtr; } diff --git a/src/bodies.cpp b/src/bodies.cpp index 700e4f25..f7067924 100644 --- a/src/bodies.cpp +++ b/src/bodies.cpp @@ -149,7 +149,7 @@ void bodies::Sphere::updateInternalData() center_ = pose_.translation(); } -boost::shared_ptr bodies::Sphere::cloneAt(const Eigen::Affine3d &pose, double padding, double scale) const +std::shared_ptr bodies::Sphere::cloneAt(const Eigen::Affine3d &pose, double padding, double scale) const { Sphere *s = new Sphere(); s->radius_ = radius_; @@ -157,7 +157,7 @@ boost::shared_ptr bodies::Sphere::cloneAt(const Eigen::Affine3d &p s->scale_ = scale; s->pose_ = pose; s->updateInternalData(); - return boost::shared_ptr(s); + return std::shared_ptr(s); } double bodies::Sphere::computeVolume() const @@ -323,7 +323,7 @@ bool bodies::Cylinder::samplePointInside(random_numbers::RandomNumberGenerator & return true; } -boost::shared_ptr bodies::Cylinder::cloneAt(const Eigen::Affine3d &pose, double padding, double scale) const +std::shared_ptr bodies::Cylinder::cloneAt(const Eigen::Affine3d &pose, double padding, double scale) const { Cylinder *c = new Cylinder(); c->length_ = length_; @@ -332,7 +332,7 @@ boost::shared_ptr bodies::Cylinder::cloneAt(const Eigen::Affine3d c->scale_ = scale; c->pose_ = pose; c->updateInternalData(); - return boost::shared_ptr(c); + return std::shared_ptr(c); } double bodies::Cylinder::computeVolume() const @@ -521,7 +521,7 @@ void bodies::Box::updateInternalData() corner2_ = center_ + tmp; } -boost::shared_ptr bodies::Box::cloneAt(const Eigen::Affine3d &pose, double padding, double scale) const +std::shared_ptr bodies::Box::cloneAt(const Eigen::Affine3d &pose, double padding, double scale) const { Box *b = new Box(); b->length_ = length_; @@ -531,7 +531,7 @@ boost::shared_ptr bodies::Box::cloneAt(const Eigen::Affine3d &pose b->scale_ = scale; b->pose_ = pose; b->updateInternalData(); - return boost::shared_ptr(b); + return std::shared_ptr(b); } double bodies::Box::computeVolume() const @@ -922,7 +922,7 @@ void bodies::ConvexMesh::updateInternalData() Eigen::Affine3d pose = pose_; pose.translation() = Eigen::Vector3d(pose_ * mesh_data_->box_offset_); - boost::scoped_ptr box_shape(new shapes::Box(mesh_data_->box_size_.x(), mesh_data_->box_size_.y(), mesh_data_->box_size_.z())); + std::unique_ptr box_shape(new shapes::Box(mesh_data_->box_size_.x(), mesh_data_->box_size_.y(), mesh_data_->box_size_.z())); bounding_box_.setDimensions(box_shape.get()); bounding_box_.setPose(pose); bounding_box_.setPadding(padding_); @@ -967,7 +967,7 @@ const EigenSTL::vector_Vector3d& bodies::ConvexMesh::getScaledVertices() const return scaled_vertices_ ? *scaled_vertices_ : getVertices(); } -boost::shared_ptr bodies::ConvexMesh::cloneAt(const Eigen::Affine3d &pose, double padding, double scale) const +std::shared_ptr bodies::ConvexMesh::cloneAt(const Eigen::Affine3d &pose, double padding, double scale) const { ConvexMesh *m = new ConvexMesh(); m->mesh_data_ = mesh_data_; @@ -975,7 +975,7 @@ boost::shared_ptr bodies::ConvexMesh::cloneAt(const Eigen::Affine3 m->scale_ = scale; m->pose_ = pose; m->updateInternalData(); - return boost::shared_ptr(m); + return std::shared_ptr(m); } void bodies::ConvexMesh::computeBoundingSphere(BoundingSphere &sphere) const