From fd56073349585a71f3e5bf1d4509f7eba3a673a4 Mon Sep 17 00:00:00 2001 From: Joseph Mirabel <jmirabel@laas.fr> Date: Wed, 16 Dec 2020 18:59:28 +0100 Subject: [PATCH] Reduce dependency to boost. --- include/hpp/manipulation/fwd.hh | 46 ++--- .../hpp/manipulation/graph-path-validation.hh | 8 +- include/hpp/manipulation/graph/fwd.hh | 24 +-- include/hpp/manipulation/graph/graph.hh | 2 +- include/hpp/manipulation/graph/helper.hh | 12 +- include/hpp/manipulation/graph/state.hh | 10 +- include/hpp/manipulation/graph/statistics.hh | 2 +- .../enforce-transition-semantic.hh | 2 +- .../path-optimization/random-shortcut.hh | 2 +- .../spline-gradient-based.hh | 2 +- .../path-planner/end-effector-trajectory.hh | 4 +- include/hpp/manipulation/serialization.hh | 2 +- .../end-effector-trajectory.hh | 2 +- .../hpp/manipulation/steering-method/fwd.hh | 4 +- src/connected-component.cc | 2 +- src/graph/edge.cc | 4 +- src/graph/helper.cc | 161 +++++++++--------- src/handle.cc | 5 +- src/manipulation-planner.cc | 36 ++-- src/path-planner/end-effector-trajectory.cc | 4 +- src/problem-solver.cc | 32 ++-- src/problem.cc | 2 +- .../cross-state-optimization.cc | 2 - 23 files changed, 181 insertions(+), 189 deletions(-) diff --git a/include/hpp/manipulation/fwd.hh b/include/hpp/manipulation/fwd.hh index 35e0ade..c7164d7 100644 --- a/include/hpp/manipulation/fwd.hh +++ b/include/hpp/manipulation/fwd.hh @@ -26,8 +26,8 @@ namespace hpp { namespace manipulation { HPP_PREDEF_CLASS (Device); - typedef boost::shared_ptr <Device> DevicePtr_t; - typedef boost::shared_ptr <const Device> DeviceConstPtr_t; + typedef shared_ptr <Device> DevicePtr_t; + typedef shared_ptr <const Device> DeviceConstPtr_t; typedef pinocchio::Joint Joint; typedef pinocchio::JointPtr_t JointPtr_t; typedef pinocchio::JointIndex JointIndex; @@ -43,33 +43,33 @@ namespace hpp { typedef pinocchio::LiegroupSpace LiegroupSpace; typedef pinocchio::LiegroupSpacePtr_t LiegroupSpacePtr_t; HPP_PREDEF_CLASS (AxialHandle); - typedef boost::shared_ptr <AxialHandle> AxialHandlePtr_t; + typedef shared_ptr <AxialHandle> AxialHandlePtr_t; HPP_PREDEF_CLASS (Handle); - typedef boost::shared_ptr <Handle> HandlePtr_t; + typedef shared_ptr <Handle> HandlePtr_t; HPP_PREDEF_CLASS (Object); - typedef boost::shared_ptr <Object> ObjectPtr_t; - typedef boost::shared_ptr <const Object> ObjectConstPtr_t; + typedef shared_ptr <Object> ObjectPtr_t; + typedef shared_ptr <const Object> ObjectConstPtr_t; HPP_PREDEF_CLASS (ProblemSolver); typedef ProblemSolver* ProblemSolverPtr_t; HPP_PREDEF_CLASS (Problem); - typedef boost::shared_ptr <Problem> ProblemPtr_t; - typedef boost::shared_ptr <const Problem> ProblemConstPtr_t; + typedef shared_ptr <Problem> ProblemPtr_t; + typedef shared_ptr <const Problem> ProblemConstPtr_t; HPP_PREDEF_CLASS (Roadmap); - typedef boost::shared_ptr <Roadmap> RoadmapPtr_t; + typedef shared_ptr <Roadmap> RoadmapPtr_t; HPP_PREDEF_CLASS (RoadmapNode); typedef RoadmapNode* RoadmapNodePtr_t; typedef std::vector<RoadmapNodePtr_t> RoadmapNodes_t; HPP_PREDEF_CLASS (ConnectedComponent); - typedef boost::shared_ptr<ConnectedComponent> ConnectedComponentPtr_t; + typedef shared_ptr<ConnectedComponent> ConnectedComponentPtr_t; HPP_PREDEF_CLASS (LeafConnectedComp); - typedef boost::shared_ptr<LeafConnectedComp> LeafConnectedCompPtr_t; - typedef boost::shared_ptr<const LeafConnectedComp> + typedef shared_ptr<LeafConnectedComp> LeafConnectedCompPtr_t; + typedef shared_ptr<const LeafConnectedComp> LeafConnectedCompConstPtr_t; typedef std::set<LeafConnectedCompPtr_t> LeafConnectedComps_t; HPP_PREDEF_CLASS (WeighedLeafConnectedComp); - typedef boost::shared_ptr<WeighedLeafConnectedComp> WeighedLeafConnectedCompPtr_t; + typedef shared_ptr<WeighedLeafConnectedComp> WeighedLeafConnectedCompPtr_t; HPP_PREDEF_CLASS (WeighedDistance); - typedef boost::shared_ptr<WeighedDistance> WeighedDistancePtr_t; + typedef shared_ptr<WeighedDistance> WeighedDistancePtr_t; typedef constraints::RelativeOrientation RelativeOrientation; typedef constraints::RelativePosition RelativePosition; typedef constraints::RelativeOrientationPtr_t RelativeOrientationPtr_t; @@ -84,17 +84,17 @@ namespace hpp { typedef core::vectorIn_t vectorIn_t; typedef core::vectorOut_t vectorOut_t; HPP_PREDEF_CLASS (ManipulationPlanner); - typedef boost::shared_ptr < ManipulationPlanner > ManipulationPlannerPtr_t; + typedef shared_ptr < ManipulationPlanner > ManipulationPlannerPtr_t; HPP_PREDEF_CLASS (GraphPathValidation); - typedef boost::shared_ptr < GraphPathValidation > GraphPathValidationPtr_t; + typedef shared_ptr < GraphPathValidation > GraphPathValidationPtr_t; HPP_PREDEF_CLASS (SteeringMethod); - typedef boost::shared_ptr < SteeringMethod > SteeringMethodPtr_t; + typedef shared_ptr < SteeringMethod > SteeringMethodPtr_t; typedef core::PathOptimizer PathOptimizer; typedef core::PathOptimizerPtr_t PathOptimizerPtr_t; HPP_PREDEF_CLASS (GraphOptimizer); - typedef boost::shared_ptr < GraphOptimizer > GraphOptimizerPtr_t; + typedef shared_ptr < GraphOptimizer > GraphOptimizerPtr_t; HPP_PREDEF_CLASS (GraphNodeOptimizer); - typedef boost::shared_ptr < GraphNodeOptimizer > GraphNodeOptimizerPtr_t; + typedef shared_ptr < GraphNodeOptimizer > GraphNodeOptimizerPtr_t; typedef core::PathProjectorPtr_t PathProjectorPtr_t; typedef std::vector <pinocchio::DevicePtr_t> Devices_t; @@ -110,7 +110,7 @@ namespace hpp { typedef core::ConfigProjector ConfigProjector; typedef core::ConfigProjectorPtr_t ConfigProjectorPtr_t; HPP_PREDEF_CLASS (ConstraintSet); - typedef boost::shared_ptr <ConstraintSet> ConstraintSetPtr_t; + typedef shared_ptr <ConstraintSet> ConstraintSetPtr_t; typedef core::DifferentiableFunctionPtr_t DifferentiableFunctionPtr_t; typedef core::ConfigurationShooter ConfigurationShooter; typedef core::ConfigurationShooterPtr_t ConfigurationShooterPtr_t; @@ -134,14 +134,14 @@ namespace hpp { namespace pathOptimization { HPP_PREDEF_CLASS (SmallSteps); - typedef boost::shared_ptr < SmallSteps > SmallStepsPtr_t; + typedef shared_ptr < SmallSteps > SmallStepsPtr_t; HPP_PREDEF_CLASS (Keypoints); - typedef boost::shared_ptr < Keypoints > KeypointsPtr_t; + typedef shared_ptr < Keypoints > KeypointsPtr_t; } // namespace pathOptimization namespace problemTarget { HPP_PREDEF_CLASS (State); - typedef boost::shared_ptr < State > StatePtr_t; + typedef shared_ptr < State > StatePtr_t; } // namespace problemTarget } // namespace manipulation } // namespace hpp diff --git a/include/hpp/manipulation/graph-path-validation.hh b/include/hpp/manipulation/graph-path-validation.hh index 9bfe494..ef36ad7 100644 --- a/include/hpp/manipulation/graph-path-validation.hh +++ b/include/hpp/manipulation/graph-path-validation.hh @@ -105,7 +105,7 @@ namespace hpp { /// hpp::core::ObstacleUserInterface::addObstacle in case of success. void addObstacle (const hpp::core::CollisionObjectConstPtr_t& object) { - boost::shared_ptr<core::ObstacleUserInterface> oui = + shared_ptr<core::ObstacleUserInterface> oui = HPP_DYNAMIC_PTR_CAST(core::ObstacleUserInterface, pathValidation_); if (oui) oui->addObstacle (object); } @@ -119,7 +119,7 @@ namespace hpp { void removeObstacleFromJoint (const JointPtr_t& joint, const pinocchio::CollisionObjectConstPtr_t& obstacle) { - boost::shared_ptr<core::ObstacleUserInterface> oui = + shared_ptr<core::ObstacleUserInterface> oui = HPP_DYNAMIC_PTR_CAST(core::ObstacleUserInterface, pathValidation_); if (oui) oui->removeObstacleFromJoint (joint, obstacle); } @@ -132,7 +132,7 @@ namespace hpp { /// success. void filterCollisionPairs (const core::RelativeMotion::matrix_type& relMotion) { - boost::shared_ptr<core::ObstacleUserInterface> oui = + shared_ptr<core::ObstacleUserInterface> oui = HPP_DYNAMIC_PTR_CAST(core::ObstacleUserInterface, pathValidation_); if (oui) oui->filterCollisionPairs (relMotion); } @@ -145,7 +145,7 @@ namespace hpp { /// success. void setSecurityMargins(const matrix_t& securityMargins) { - boost::shared_ptr<core::ObstacleUserInterface> oui = + shared_ptr<core::ObstacleUserInterface> oui = HPP_DYNAMIC_PTR_CAST(core::ObstacleUserInterface, pathValidation_); if (oui) oui->setSecurityMargins(securityMargins); } diff --git a/include/hpp/manipulation/graph/fwd.hh b/include/hpp/manipulation/graph/fwd.hh index 5806bde..ff6cdd5 100644 --- a/include/hpp/manipulation/graph/fwd.hh +++ b/include/hpp/manipulation/graph/fwd.hh @@ -32,15 +32,15 @@ namespace hpp { HPP_PREDEF_CLASS (StateSelector); HPP_PREDEF_CLASS (GraphComponent); HPP_PREDEF_CLASS (GuidedStateSelector); - typedef boost::shared_ptr < Graph > GraphPtr_t; - typedef boost::shared_ptr < State > StatePtr_t; - typedef boost::shared_ptr < Edge > EdgePtr_t; - typedef boost::shared_ptr < WaypointEdge > WaypointEdgePtr_t; - typedef boost::shared_ptr < LevelSetEdge > LevelSetEdgePtr_t; - typedef boost::shared_ptr < StateSelector > StateSelectorPtr_t; - typedef boost::shared_ptr < GuidedStateSelector > + typedef shared_ptr < Graph > GraphPtr_t; + typedef shared_ptr < State > StatePtr_t; + typedef shared_ptr < Edge > EdgePtr_t; + typedef shared_ptr < WaypointEdge > WaypointEdgePtr_t; + typedef shared_ptr < LevelSetEdge > LevelSetEdgePtr_t; + typedef shared_ptr < StateSelector > StateSelectorPtr_t; + typedef shared_ptr < GuidedStateSelector > GuidedStateSelectorPtr_t; - typedef boost::shared_ptr < GraphComponent > GraphComponentPtr_t; + typedef shared_ptr < GraphComponent > GraphComponentPtr_t; typedef std::vector < GraphComponentWkPtr_t > GraphComponents_t; typedef std::vector < StatePtr_t > States_t; typedef std::vector < EdgePtr_t > Edges_t; @@ -56,13 +56,13 @@ namespace hpp { class Histogram; class StateHistogram; class LeafHistogram; - typedef boost::shared_ptr <Histogram> HistogramPtr_t; - typedef boost::shared_ptr <StateHistogram> StateHistogramPtr_t; - typedef boost::shared_ptr <LeafHistogram> LeafHistogramPtr_t; + typedef shared_ptr <Histogram> HistogramPtr_t; + typedef shared_ptr <StateHistogram> StateHistogramPtr_t; + typedef shared_ptr <LeafHistogram> LeafHistogramPtr_t; typedef std::list < HistogramPtr_t > Histograms_t; class Validation; - typedef boost::shared_ptr < Validation > ValidationPtr_t; + typedef shared_ptr < Validation > ValidationPtr_t; } // namespace graph } // namespace manipulation } // namespace hpp diff --git a/include/hpp/manipulation/graph/graph.hh b/include/hpp/manipulation/graph/graph.hh index ade3266..8bd7099 100644 --- a/include/hpp/manipulation/graph/graph.hh +++ b/include/hpp/manipulation/graph/graph.hh @@ -17,7 +17,7 @@ #ifndef HPP_MANIPULATION_GRAPH_GRAPH_HH # define HPP_MANIPULATION_GRAPH_GRAPH_HH -# include <boost/tuple/tuple.hpp> +# include <tuple> # include "hpp/manipulation/config.hh" # include "hpp/manipulation/constraint-set.hh" # include "hpp/manipulation/fwd.hh" diff --git a/include/hpp/manipulation/graph/helper.hh b/include/hpp/manipulation/graph/helper.hh index 381c57f..339024f 100644 --- a/include/hpp/manipulation/graph/helper.hh +++ b/include/hpp/manipulation/graph/helper.hh @@ -20,7 +20,7 @@ # include <string> # include <algorithm> -# include <boost/tuple/tuple.hpp> +# include <tuple> # include "hpp/manipulation/config.hh" # include "hpp/manipulation/fwd.hh" @@ -165,10 +165,10 @@ namespace hpp { const LockedJoints_t objectLocks, FoliatedManifold& place, FoliatedManifold& preplace); - typedef boost::tuple <ImplicitPtr_t, - ImplicitPtr_t, - LockedJoints_t> - PlacementConstraint_t; + typedef std::tuple <ImplicitPtr_t, + ImplicitPtr_t, + LockedJoints_t> + PlacementConstraint_t; typedef std::vector <HandlePtr_t> Handles_t; typedef std::vector <GripperPtr_t> Grippers_t; /// Tuple representing an object as follows: @@ -176,7 +176,7 @@ namespace hpp { /// \li Handles_t list of handles of the object /// \li std::size_t the index of this tuple in Objects_t. /// \note the index must be unique, as object equallity is checked using this index. - typedef boost::tuple <PlacementConstraint_t, Handles_t, std::size_t> Object_t; + typedef std::tuple <PlacementConstraint_t, Handles_t, std::size_t> Object_t; typedef std::vector <Object_t> Objects_t; /// Fill a Graph diff --git a/include/hpp/manipulation/graph/state.hh b/include/hpp/manipulation/graph/state.hh index 916326c..01fc664 100644 --- a/include/hpp/manipulation/graph/state.hh +++ b/include/hpp/manipulation/graph/state.hh @@ -17,7 +17,7 @@ #ifndef HPP_MANIPULATION_GRAPH_STATE_HH # define HPP_MANIPULATION_GRAPH_STATE_HH -# include <boost/function.hpp> +#include <functional> #include <hpp/core/constraint-set.hh> #include <hpp/core/config-projector.hh> @@ -44,10 +44,10 @@ namespace hpp { class HPP_MANIPULATION_DLLAPI State : public GraphComponent { public: - typedef boost::function < EdgePtr_t - (const std::string&, - const GraphWkPtr_t&, - const StateWkPtr_t&, const StateWkPtr_t&) > + typedef std::function < EdgePtr_t + (const std::string&, + const GraphWkPtr_t&, + const StateWkPtr_t&, const StateWkPtr_t&) > EdgeFactory; /// Destructor ~State (); diff --git a/include/hpp/manipulation/graph/statistics.hh b/include/hpp/manipulation/graph/statistics.hh index 6c3a8ba..13aaffb 100644 --- a/include/hpp/manipulation/graph/statistics.hh +++ b/include/hpp/manipulation/graph/statistics.hh @@ -198,7 +198,7 @@ namespace hpp { graph::GraphPtr_t graph_; }; typedef StateHistogram NodeHistogram HPP_MANIPULATION_DEPRECATED; - typedef boost::shared_ptr <StateHistogram> NodeHistogramPtr_t; + typedef shared_ptr <StateHistogram> NodeHistogramPtr_t; } // namespace graph } // namespace manipulation } // namespace hpp diff --git a/include/hpp/manipulation/path-optimization/enforce-transition-semantic.hh b/include/hpp/manipulation/path-optimization/enforce-transition-semantic.hh index f50da1b..570e0d6 100644 --- a/include/hpp/manipulation/path-optimization/enforce-transition-semantic.hh +++ b/include/hpp/manipulation/path-optimization/enforce-transition-semantic.hh @@ -34,7 +34,7 @@ namespace hpp { { public: typedef hpp::core::PathVectorPtr_t PathVectorPtr_t; - typedef boost::shared_ptr<EnforceTransitionSemantic> Ptr_t; + typedef shared_ptr<EnforceTransitionSemantic> Ptr_t; static Ptr_t create (const core::ProblemConstPtr_t& problem) { ProblemConstPtr_t p (HPP_DYNAMIC_PTR_CAST(const Problem, problem)); diff --git a/include/hpp/manipulation/path-optimization/random-shortcut.hh b/include/hpp/manipulation/path-optimization/random-shortcut.hh index b95767f..45e1088 100644 --- a/include/hpp/manipulation/path-optimization/random-shortcut.hh +++ b/include/hpp/manipulation/path-optimization/random-shortcut.hh @@ -28,7 +28,7 @@ namespace hpp { /// \{ namespace pathOptimization { HPP_PREDEF_CLASS (RandomShortcut); - typedef boost::shared_ptr<RandomShortcut> RandomShortcutPtr_t; + typedef shared_ptr<RandomShortcut> RandomShortcutPtr_t; class HPP_MANIPULATION_DLLAPI RandomShortcut : public core::pathOptimization::RandomShortcut diff --git a/include/hpp/manipulation/path-optimization/spline-gradient-based.hh b/include/hpp/manipulation/path-optimization/spline-gradient-based.hh index 6af8561..6be91d5 100644 --- a/include/hpp/manipulation/path-optimization/spline-gradient-based.hh +++ b/include/hpp/manipulation/path-optimization/spline-gradient-based.hh @@ -38,7 +38,7 @@ namespace hpp { }; typedef core::pathOptimization::SplineGradientBased<PolynomeBasis, SplineOrder> Parent_t; - typedef boost::shared_ptr<SplineGradientBased> Ptr_t; + typedef shared_ptr<SplineGradientBased> Ptr_t; using typename Parent_t::Spline; using typename Parent_t::SplinePtr_t; diff --git a/include/hpp/manipulation/path-planner/end-effector-trajectory.hh b/include/hpp/manipulation/path-planner/end-effector-trajectory.hh index 133601a..c4f2a24 100644 --- a/include/hpp/manipulation/path-planner/end-effector-trajectory.hh +++ b/include/hpp/manipulation/path-planner/end-effector-trajectory.hh @@ -43,10 +43,10 @@ namespace hpp { protected: virtual Configurations_t impl_solve (vectorIn_t target) = 0; }; - typedef boost::shared_ptr<IkSolverInitialization> IkSolverInitializationPtr_t; + typedef shared_ptr<IkSolverInitialization> IkSolverInitializationPtr_t; HPP_PREDEF_CLASS (EndEffectorTrajectory); - typedef boost::shared_ptr<EndEffectorTrajectory> EndEffectorTrajectoryPtr_t; + typedef shared_ptr<EndEffectorTrajectory> EndEffectorTrajectoryPtr_t; class HPP_MANIPULATION_DLLAPI EndEffectorTrajectory : public core::PathPlanner { diff --git a/include/hpp/manipulation/serialization.hh b/include/hpp/manipulation/serialization.hh index cfb1835..568562d 100644 --- a/include/hpp/manipulation/serialization.hh +++ b/include/hpp/manipulation/serialization.hh @@ -44,7 +44,7 @@ manipulation::graph::GraphPtr_t getGraphFromArchive(Archive& ar, const std::stri } template<class Archive, class GraphCompT> -inline void serializeGraphComponent(Archive & ar, boost::shared_ptr<GraphCompT>& c, const unsigned int version) +inline void serializeGraphComponent(Archive & ar, shared_ptr<GraphCompT>& c, const unsigned int version) { (void) version; diff --git a/include/hpp/manipulation/steering-method/end-effector-trajectory.hh b/include/hpp/manipulation/steering-method/end-effector-trajectory.hh index 542b8f9..73b3052 100644 --- a/include/hpp/manipulation/steering-method/end-effector-trajectory.hh +++ b/include/hpp/manipulation/steering-method/end-effector-trajectory.hh @@ -28,7 +28,7 @@ namespace hpp { /// \{ namespace steeringMethod { HPP_PREDEF_CLASS (EndEffectorTrajectory); - typedef boost::shared_ptr < EndEffectorTrajectory > EndEffectorTrajectoryPtr_t; + typedef shared_ptr < EndEffectorTrajectory > EndEffectorTrajectoryPtr_t; using core::PathPtr_t; diff --git a/include/hpp/manipulation/steering-method/fwd.hh b/include/hpp/manipulation/steering-method/fwd.hh index 467557d..e3b6626 100644 --- a/include/hpp/manipulation/steering-method/fwd.hh +++ b/include/hpp/manipulation/steering-method/fwd.hh @@ -27,9 +27,9 @@ namespace hpp { namespace manipulation { namespace steeringMethod { HPP_PREDEF_CLASS (Graph); - typedef boost::shared_ptr < Graph > GraphPtr_t; + typedef shared_ptr < Graph > GraphPtr_t; HPP_PREDEF_CLASS (CrossStateOptimization); - typedef boost::shared_ptr < CrossStateOptimization > CrossStateOptimizationPtr_t; + typedef shared_ptr < CrossStateOptimization > CrossStateOptimizationPtr_t; } // namespace steeringMethod } // namespace manipulation } // namespace hpp diff --git a/src/connected-component.cc b/src/connected-component.cc index ce7e0fd..bf12490 100644 --- a/src/connected-component.cc +++ b/src/connected-component.cc @@ -59,7 +59,7 @@ namespace hpp { void ConnectedComponent::merge (const core::ConnectedComponentPtr_t& otherCC) { core::ConnectedComponent::merge(otherCC); - const ConnectedComponentPtr_t other = boost::static_pointer_cast <ConnectedComponent> (otherCC); + const ConnectedComponentPtr_t other = static_pointer_cast <ConnectedComponent> (otherCC); /// take all graph states in other->graphStateMap_ and put them in this->graphStateMap_ /// if they already exist in this->graphStateMap_, append roadmap nodes from other graph state /// to graph state in this. diff --git a/src/graph/edge.cc b/src/graph/edge.cc index e026a1d..6012044 100644 --- a/src/graph/edge.cc +++ b/src/graph/edge.cc @@ -63,7 +63,7 @@ namespace hpp { void Edge::relativeMotion(const RelativeMotion::matrix_type & m) { if(!isInit_) throw std::logic_error("The graph must be initialized before changing the relative motion matrix."); - boost::shared_ptr<core::ObstacleUserInterface> oui = + shared_ptr<core::ObstacleUserInterface> oui = HPP_DYNAMIC_PTR_CAST(core::ObstacleUserInterface, pathValidation_); if (oui) oui->filterCollisionPairs(m); relMotion_ = m; @@ -334,7 +334,7 @@ namespace hpp { // TODO this path validation will not contain obstacles added after // its creation. pathValidation_ = problem->pathValidationFactory (); - boost::shared_ptr<core::ObstacleUserInterface> oui = + shared_ptr<core::ObstacleUserInterface> oui = HPP_DYNAMIC_PTR_CAST(core::ObstacleUserInterface, pathValidation_); if (oui) { relMotion_ = RelativeMotion::matrix (g->robot()); diff --git a/src/graph/helper.cc b/src/graph/helper.cc index ecd245b..3c1ae35 100644 --- a/src/graph/helper.cc +++ b/src/graph/helper.cc @@ -19,10 +19,10 @@ #include <tr1/unordered_map> #include <tr1/unordered_set> -#include <boost/array.hpp> +#include <iterator> +#include <array> + #include <boost/regex.hpp> -#include <boost/foreach.hpp> -#include <boost/assign/list_of.hpp> #include <pinocchio/multibody/model.hpp> @@ -121,8 +121,8 @@ namespace hpp { static const std::size_t Nedges = 1 + nbWaypoints; // static const std::size_t iNpregrasp = pregrasp?1 + 1:nbWaypoints; // static const std::size_t iNpreplace = pregrasp?1 + 1:nbWaypoints; - typedef boost::array <StatePtr_t, Nstates> StateArray; - typedef boost::array <EdgePtr_t, Nedges> EdgeArray; + typedef std::array <StatePtr_t, Nstates> StateArray; + typedef std::array <EdgePtr_t, Nedges> EdgeArray; static inline const StatePtr_t& Npregrasp (const StateArray& n) { assert (pregrasp); return n[1]; } static inline const StatePtr_t& Nintersec (const StateArray& n) { assert (intersec); return n[1 + (pregrasp?1:0)]; } @@ -145,7 +145,7 @@ namespace hpp { const size_type& w) { if (Nedges > 1) { - WaypointEdgePtr_t we = boost::static_pointer_cast <WaypointEdge> + WaypointEdgePtr_t we = static_pointer_cast <WaypointEdge> (from->linkTo (name, to, w, WaypointEdge::create)); we->nbWaypoints (nbWaypoints); return we; @@ -179,7 +179,7 @@ namespace hpp { { if (Nedges > 1) { const std::size_t T = (pregrasp?1:0) + (intersec?1:0); - WaypointEdgePtr_t we = boost::static_pointer_cast <WaypointEdge> + WaypointEdgePtr_t we = static_pointer_cast <WaypointEdge> (n.front()->linkTo (name + "_ls", n.back(), w, WaypointEdge::create)); we->nbWaypoints (nbWaypoints); @@ -193,7 +193,7 @@ namespace hpp { } else { assert (gCase == (GraspOnly | NoPlace) && "Cannot implement a LevelSetEdge for grasping"); - gls = boost::static_pointer_cast <LevelSetEdge> + gls = static_pointer_cast <LevelSetEdge> (n.front()->linkTo (name + "_ls", n.back(), w, LevelSetEdge::create)); return gls; @@ -206,7 +206,7 @@ namespace hpp { { if (Nedges > 1) { const std::size_t T = (pregrasp?1:0) + (intersec?1:0); - WaypointEdgePtr_t we = boost::static_pointer_cast <WaypointEdge> + WaypointEdgePtr_t we = static_pointer_cast <WaypointEdge> (n.back()->linkTo (name + "_ls", n.front(), w, WaypointEdge::create)); we->nbWaypoints (nbWaypoints); @@ -223,7 +223,7 @@ namespace hpp { } else { assert (gCase == (NoGrasp | PlaceOnly) && "Cannot implement a LevelSetEdge for placement"); - pls = boost::static_pointer_cast <LevelSetEdge> + pls = static_pointer_cast <LevelSetEdge> (n.back()->linkTo (name + "_ls", n.front(), w, LevelSetEdge::create)); return pls; @@ -231,7 +231,7 @@ namespace hpp { } template <typename EdgeType> - static inline boost::shared_ptr<EdgeType> linkWaypoint ( + static inline shared_ptr<EdgeType> linkWaypoint ( const StateArray& states, const std::size_t& iF, const std::size_t& iT, const std::string& prefix, @@ -240,7 +240,7 @@ namespace hpp { std::stringstream ss; ss << prefix << "_" << iF << iT; if (suffix.length () > 0) ss << "_" << suffix; - return boost::static_pointer_cast <EdgeType> + return static_pointer_cast <EdgeType> (states[iF]->linkTo (ss.str(), states[iT], -1, EdgeType::create)); } @@ -376,7 +376,7 @@ namespace hpp { if (levelSetPlace) weBackLs = T::makeLSEplace (name, n, eB, 10*wBack, pls); - Edges_t ret = boost::assign::list_of (weForw)(weBack); + Edges_t ret { weForw, weBack }; if (levelSetPlace) { if (!place.foliated ()) { @@ -517,9 +517,7 @@ namespace hpp { typedef std::vector <index_t> IndexV_t; typedef std::list <index_t> IndexL_t; typedef std::pair <index_t, index_t> Grasp_t; - typedef boost::tuple <StatePtr_t, - FoliatedManifold> - StateAndManifold_t; + typedef std::tuple <StatePtr_t, FoliatedManifold> StateAndManifold_t; //typedef std::vector <index_t, index_t> GraspV_t; /// GraspV_t corresponds to a unique ID of a permutation. /// - its size is the number of grippers, @@ -565,7 +563,7 @@ namespace hpp { } }; std::tr1::unordered_set<edgeid_type, edgeid_hash> edges; - std::vector< boost::array<ImplicitPtr_t,3> > graspCs; + std::vector< std::array<ImplicitPtr_t,3> > graspCs; index_t nG, nOH; GraspV_t dims; const Grippers_t& gs; @@ -578,11 +576,10 @@ namespace hpp { ps (problem), graph (g), nG (grippers.size ()), nOH (0), gs (grippers), ohs (objects), defaultAcceptationPolicy (CompiledRule::Refuse) { - BOOST_FOREACH (const Object_t& o, objects) { - nOH += o.get<1>().size(); - BOOST_FOREACH (const HandlePtr_t& h, o.get<1>()) { + for (const Object_t& o : objects) { + nOH += std::get<1>(o).size(); + for (const HandlePtr_t& h : std::get<1>(o)) handleNames.push_back(h->name()); - } } handleNames.push_back(""); dims.resize (nG); @@ -647,10 +644,10 @@ namespace hpp { edges.insert(edgeid_type(stateid(g1), stateid(g2))); } - inline boost::array<ImplicitPtr_t,3>& graspConstraint ( + inline std::array<ImplicitPtr_t,3>& graspConstraint ( const index_t& iG, const index_t& iOH) { - boost::array<ImplicitPtr_t,3>& gcs = + std::array<ImplicitPtr_t,3>& gcs = graspCs [iG * nOH + iOH]; if (!gcs[0]) { hppDout (info, "Create grasps constraints for (" @@ -674,18 +671,18 @@ namespace hpp { const Object_t& object (const index_t& iOH) const { index_t iH = iOH; - BOOST_FOREACH (const Object_t& o, ohs) { - if (iH < o.get<1>().size()) return o; - iH -= o.get<1>().size(); + for (const Object_t& o : ohs) { + if (iH < std::get<1>(o).size()) return o; + iH -= std::get<1>(o).size(); } throw std::out_of_range ("Handle index"); } const HandlePtr_t& handle (const index_t& iOH) const { index_t iH = iOH; - BOOST_FOREACH (const Object_t& o, ohs) { - if (iH < o.get<1>().size()) return o.get<1>()[iH]; - iH -= o.get<1>().size(); + for (const Object_t& o : ohs) { + if (iH < std::get<1>(o).size()) return std::get<1>(o)[iH]; + iH -= std::get<1>(o).size(); } throw std::out_of_range ("Handle index"); } @@ -694,7 +691,7 @@ namespace hpp { bool objectCanBePlaced (const Object_t& o) const { // If the object has no joint, then it cannot be placed. - return (o.get<0>().get<2>().size() > 0); + return (std::get<2>(std::get<0>(o)).size() > 0); } /// Check is an object is grasped by the GraspV_t @@ -704,7 +701,7 @@ namespace hpp { assert (idxOH.size () == nG); for (std::size_t i = 0; i < idxOH.size (); ++i) if (idxOH[i] < nOH) // This grippers grasps an object - if (o.get<2>() == object(idxOH[i]).get<2>()) + if (std::get<2>(o) == std::get<2>(object(idxOH[i]))) return true; return false; } @@ -753,7 +750,7 @@ namespace hpp { void graspManifold (const index_t& iG, const index_t& iOH, FoliatedManifold& grasp, FoliatedManifold& pregrasp) { - boost::array<ImplicitPtr_t,3>& gcs + std::array<ImplicitPtr_t,3>& gcs = graspConstraint (iG, iOH); grasp.nc.nc.push_back (gcs[0]); grasp.nc.pdof.push_back (segments_t ()); @@ -791,9 +788,9 @@ namespace hpp { const int priority) { StateAndManifold_t& nam = r (g); - if (!nam.get<0>()) { + if (!std::get<0>(nam)) { hppDout (info, "Creating state " << r.name (g)); - nam.get<0>() = r.graph->stateSelector ()->createState + std::get<0>(nam) = r.graph->stateSelector ()->createState (r.name (g), false, priority); // Loop over the grippers and create grasping constraints if required FoliatedManifold unused; @@ -801,32 +798,34 @@ namespace hpp { for (index_t i = 0; i < r.nG; ++i) { if (g[i] < r.nOH) { idxsOH.insert (g[i]); - r.graspManifold (i, g[i], nam.get<1>(), unused); + r.graspManifold (i, g[i], std::get<1>(nam), unused); } } index_t iOH = 0; - BOOST_FOREACH (const Object_t& o, r.ohs) { + for (const Object_t& o : r.ohs) { if (!r.objectCanBePlaced(o)) continue; bool oIsGrasped = false; // TODO: use the fact that the set is sorted. - // BOOST_FOREACH (const HandlePtr_t& h, o.get<1>()) - for (index_t i = 0; i < o.get<1>().size(); ++i) { + // for (const HandlePtr_t& h : std::get<0>(o)) + for (index_t i = 0; i < std::get<1>(o).size(); ++i) { if (idxsOH.erase (iOH) == 1) oIsGrasped = true; ++iOH; } - if (!oIsGrasped) - relaxedPlacementManifold (o.get<0>().get<0>(), - o.get<0>().get<1>(), - o.get<0>().get<2>(), - nam.get<1>(), unused); + if (!oIsGrasped) { + const auto& pc (std::get<0>(o)); + relaxedPlacementManifold (std::get<0>(pc), + std::get<1>(pc), + std::get<2>(pc), + std::get<1>(nam), unused); + } } - nam.get<1>().addToState (nam.get<0>()); + std::get<1>(nam).addToState (std::get<0>(nam)); createLoopEdge (r.nameLoopEdge (g), - nam.get<0>(), 0, + std::get<0>(nam), 0, false, - // TODO nam.get<1>().foliated(), - nam.get<1>()); + // TODO std::get<1>(nam).foliated(), + std::get<1>(nam)); } return nam; } @@ -856,9 +855,10 @@ namespace hpp { submanifold; r.graspManifold (iG, gTo[iG], grasp, pregrasp); if (!noPlace) { - relaxedPlacementManifold (o.get<0>().get<0>(), - o.get<0>().get<1>(), - o.get<0>().get<2>(), + const auto& pc (std::get<0>(o)); + relaxedPlacementManifold (std::get<0>(pc), + std::get<1>(pc), + std::get<2>(pc), place, preplace); } std::pair<std::string, std::string> names = @@ -873,30 +873,32 @@ namespace hpp { } } index_t iOH = 0; - BOOST_FOREACH (const Object_t& o, r.ohs) { + for (const Object_t& o : r.ohs) { if (!r.objectCanBePlaced(o)) continue; bool oIsGrasped = false; const index_t iOHstart = iOH; - for (; iOH < iOHstart + o.get<1>().size(); ++iOH) { + for (; iOH < iOHstart + std::get<1>(o).size(); ++iOH) { if (iOH == gTo [iG]) { oIsGrasped = true; - iOH = iOHstart + o.get<1>().size(); + iOH = iOHstart + std::get<1>(o).size(); break; } if (idxsOH.erase (iOH) == 1) oIsGrasped = true; } - if (!oIsGrasped) - relaxedPlacementManifold (o.get<0>().get<0>(), - o.get<0>().get<1>(), - o.get<0>().get<2>(), + if (!oIsGrasped) { + const auto& pc (std::get<0>(o)); + relaxedPlacementManifold (std::get<0>(pc), + std::get<1>(pc), + std::get<2>(pc), submanifold, unused); + } } } if (pregrasp.empty ()) { if (noPlace) createEdges <GraspOnly | NoPlace> ( names.first , names.second, - from.get<0> () , to.get<0>(), + std::get<0>(from) , std::get<0>(to), 1 , 1, grasp , pregrasp, place , preplace, @@ -905,7 +907,7 @@ namespace hpp { else if (preplace.empty ()) createEdges <GraspOnly | PlaceOnly> ( names.first , names.second, - from.get<0> () , to.get<0>(), + std::get<0>(from) , std::get<0>(to), 1 , 1, grasp , pregrasp, place , preplace, @@ -916,7 +918,7 @@ namespace hpp { /* createEdges <GraspOnly | WithPrePlace> ( names.first , names.second, - from.get<0> () , to.get<0>(), + std::get<0>(from) , std::get<0>(to), 1 , 1, grasp , pregrasp, place , preplace, @@ -927,7 +929,7 @@ namespace hpp { if (noPlace) createEdges <WithPreGrasp | NoPlace> ( names.first , names.second, - from.get<0> () , to.get<0>(), + std::get<0>(from) , std::get<0>(to), 1 , 1, grasp , pregrasp, place , preplace, @@ -936,7 +938,7 @@ namespace hpp { else if (preplace.empty ()) createEdges <WithPreGrasp | PlaceOnly> ( names.first , names.second, - from.get<0> () , to.get<0>(), + std::get<0>(from) , std::get<0>(to), 1 , 1, grasp , pregrasp, place , preplace, @@ -945,7 +947,7 @@ namespace hpp { else createEdges <WithPreGrasp | WithPrePlace> ( names.first , names.second, - from.get<0> () , to.get<0>(), + std::get<0>(from) , std::get<0>(to), 1 , 1, grasp , pregrasp, place , preplace, @@ -969,7 +971,7 @@ namespace hpp { for (IndexV_t::const_iterator itx_g = idx_g.begin (); itx_g != idx_g.end (); ++itx_g) { // Copy all element except itx_g - std::copy (boost::next (itx_g), idx_g.end (), + std::copy (std::next (itx_g), idx_g.end (), std::copy (idx_g.begin (), itx_g, nIdx_g.begin ()) ); for (IndexV_t::const_iterator itx_oh = idx_oh.begin (); @@ -985,7 +987,7 @@ namespace hpp { makeEdge (r, grasps, nGrasps, *itx_g, depth); // Copy all element except itx_oh - std::copy (boost::next (itx_oh), idx_oh.end (), + std::copy (std::next (itx_oh), idx_oh.end (), std::copy (idx_oh.begin (), itx_oh, nIdx_oh.begin ()) ); // Do all the possible combination below this new grasp @@ -1037,7 +1039,7 @@ namespace hpp { const pinocchio::Model& model = robot.model(); Grippers_t grippers (griNames.size()); index_t i = 0; - BOOST_FOREACH (const std::string& gn, griNames) { + for (const std::string& gn : griNames) { grippers[i] = robot.grippers.get (gn); ++i; } @@ -1045,12 +1047,12 @@ namespace hpp { i = 0; const value_type margin = 1e-3; bool prePlace = (prePlaceWidth > 0); - BOOST_FOREACH (const ObjectDef_t& od, objs) { + for (const ObjectDef_t& od : objs) { // Create handles - objects[i].get<2> () = i; - objects[i].get<1> ().resize (od.handles.size()); - Handles_t::iterator it = objects[i].get<1> ().begin(); - BOOST_FOREACH (const std::string hn, od.handles) { + std::get<2>(objects[i]) = i; + std::get<1>(objects[i]).resize (od.handles.size()); + Handles_t::iterator it = std::get<1>(objects[i]).begin(); + for (const std::string hn : od.handles) { *it = robot.handles.get (hn); ++it; } @@ -1064,30 +1066,27 @@ namespace hpp { // else if contact surfaces are defined and selected // create default placement constraint using the ProblemSolver // methods createPlacementConstraint and createPrePlacementConstraint + auto& pc (std::get<0>(objects[i])); if (ps->numericalConstraints.has(placeN)) { - objects[i].get<0> ().get<0> () = - ps->numericalConstraints.get (placeN); + std::get<0>(pc) = ps->numericalConstraints.get (placeN); if (ps->numericalConstraints.has(preplaceN)) { - objects[i].get<0> ().get<1> () = - ps->numericalConstraints.get (preplaceN); + std::get<1>(pc) = ps->numericalConstraints.get (preplaceN); } } else if (!envNames.empty() && !od.shapes.empty ()) { ps->createPlacementConstraint (placeN, od.shapes, envNames, margin); - objects[i].get<0> ().get<0> () = - ps->numericalConstraints.get (placeN); + std::get<0>(pc) = ps->numericalConstraints.get (placeN); if (prePlace) { ps->createPrePlacementConstraint (preplaceN, od.shapes, envNames, margin, prePlaceWidth); - objects[i].get<0> ().get<1> () = - ps->numericalConstraints.get (preplaceN); + std::get<1>(pc) = ps->numericalConstraints.get (preplaceN); } } // Create object lock // Loop over all frames of object, detect joint and create locked // joint. assert (robot.robotFrames (od.name).size () != 0); - BOOST_FOREACH (const FrameIndex& f, robot.robotFrames (od.name)) { + for (const FrameIndex& f : robot.robotFrames (od.name)) { if (model.frames[f].type != ::pinocchio::JOINT) continue; const JointIndex j = model.frames[f].parent; JointPtr_t oj (Joint::create (ps->robot(), j)); @@ -1097,7 +1096,7 @@ namespace hpp { oj->configSize ()), space); LockedJointPtr_t lj = core::LockedJoint::create (oj, lge); ps->numericalConstraints.add ("lock_" + oj->name (), lj); - objects[i].get<0> ().get<2> ().push_back (lj); + std::get<2>(pc).push_back (lj); } ++i; } diff --git a/src/handle.cc b/src/handle.cc index fe5c917..945e584 100644 --- a/src/handle.cc +++ b/src/handle.cc @@ -19,8 +19,6 @@ #include <hpp/manipulation/handle.hh> -#include <boost/assign/list_of.hpp> - #include <pinocchio/multibody/joint/joint-generic.hpp> #include <hpp/util/debug.hh> @@ -149,7 +147,7 @@ namespace hpp { core::DevicePtr_t r = robot(); if (is6Dmask(mask_)) { return Implicit::create ( - boost::shared_ptr <ZeroDiffFunc> (new ZeroDiffFunc ( + shared_ptr <ZeroDiffFunc> (new ZeroDiffFunc ( r->configSize(), r->numberDof (), n)), ComparisonTypes_t()); } else { std::vector<bool> Cmask = complementMask(mask_); @@ -164,7 +162,6 @@ namespace hpp { ImplicitPtr_t Handle::createGraspAndComplement (const GripperPtr_t& gripper, std::string n) const { - using boost::assign::list_of; using core::ExplicitRelativeTransformation; if (n.empty()) { n = gripper->name() + "_holds_" + name(); diff --git a/src/manipulation-planner.cc b/src/manipulation-planner.cc index 33f432d..212c584 100644 --- a/src/manipulation-planner.cc +++ b/src/manipulation-planner.cc @@ -16,8 +16,8 @@ #include "hpp/manipulation/manipulation-planner.hh" -#include <boost/tuple/tuple.hpp> -#include <boost/assign/list_of.hpp> +#include <tuple> +#include <iterator> #include <hpp/util/pointer.hh> #include <hpp/util/timer.hh> @@ -99,15 +99,16 @@ namespace hpp { } const std::vector<ManipulationPlanner::Reason> - ManipulationPlanner::reasons_ = boost::assign::list_of - (SuccessBin::createReason ("--Path could not be fully projected")) // PATH_PROJECTION_SHORTER = 0, - (SuccessBin::createReason ("--Path could not be fully validated")) // PATH_VALIDATION_SHORTER = 1, - (SuccessBin::createReason ("--Reached destination node")) // REACHED_DESTINATION_NODE = 2, - (SuccessBin::createReason ("Failure")) // FAILURE = 3, - (SuccessBin::createReason ("--Projection of configuration on edge leaf")) // PROJECTION = 4, - (SuccessBin::createReason ("--SteeringMethod")) // STEERING_METHOD = 5, - (SuccessBin::createReason ("--Path validation returned length 0")) // PATH_VALIDATION_ZERO = 6, - (SuccessBin::createReason ("--Path could not be projected at all")); // PATH_PROJECTION_ZERO = 7 + ManipulationPlanner::reasons_ = { + SuccessBin::createReason("--Path could not be fully projected"), // PATH_PROJECTION_SHORTER = 0, + SuccessBin::createReason("--Path could not be fully validated"), // PATH_VALIDATION_SHORTER = 1, + SuccessBin::createReason("--Reached destination node"), // REACHED_DESTINATION_NODE = 2, + SuccessBin::createReason("Failure"), // FAILURE = 3, + SuccessBin::createReason("--Projection of configuration on edge leaf"), // PROJECTION = 4, + SuccessBin::createReason("--SteeringMethod"), // STEERING_METHOD = 5, + SuccessBin::createReason("--Path validation returned length 0"), // PATH_VALIDATION_ZERO = 6, + SuccessBin::createReason("--Path could not be projected at all"), // PATH_PROJECTION_ZERO = 7 + }; ManipulationPlannerPtr_t ManipulationPlanner::create (const core::ProblemConstPtr_t& problem, @@ -168,7 +169,7 @@ namespace hpp { core::Nodes_t newNodes; core::PathPtr_t path; - typedef boost::tuple <core::NodePtr_t, ConfigurationPtr_t, core::PathPtr_t> + typedef std::tuple <core::NodePtr_t, ConfigurationPtr_t, core::PathPtr_t> DelayedEdge_t; typedef std::vector <DelayedEdge_t> DelayedEdges_t; DelayedEdges_t delayedEdges; @@ -208,11 +209,10 @@ namespace hpp { HPP_START_TIMECOUNTER(delayedEdges); // Insert delayed edges - for (DelayedEdges_t::const_iterator itEdge = delayedEdges.begin (); - itEdge != delayedEdges.end (); ++itEdge) { - const core::NodePtr_t& near = itEdge-> get <0> (); - const ConfigurationPtr_t& q_new = itEdge-> get <1> (); - const core::PathPtr_t& validPath = itEdge-> get <2> (); + for (const auto& edge : delayedEdges) { + const core::NodePtr_t& near = std::get<0>(edge); + const ConfigurationPtr_t& q_new = std::get<1>(edge); + const core::PathPtr_t& validPath = std::get<2>(edge); core::NodePtr_t newNode = roadmap ()->addNode (q_new); roadmap ()->addEdge (near, newNode, validPath); roadmap ()->addEdge (newNode, near, validPath->reverse()); @@ -437,7 +437,7 @@ namespace hpp { const Configuration_t& q1 (*(*itn1)->configuration ()); graph::StatePtr_t s1 = getState (graph, *itn1); - for (core::Nodes_t::const_iterator itn2 = boost::next (itn1); + for (core::Nodes_t::const_iterator itn2 = std::next (itn1); itn2 != nodes.end (); ++itn2) { if ((*itn1)->connectedComponent () == (*itn2)->connectedComponent ()) continue; diff --git a/src/path-planner/end-effector-trajectory.cc b/src/path-planner/end-effector-trajectory.cc index a898f5f..7a486aa 100644 --- a/src/path-planner/end-effector-trajectory.cc +++ b/src/path-planner/end-effector-trajectory.cc @@ -208,10 +208,10 @@ namespace hpp { continue; } - roadmap()->initNode (boost::make_shared<Configuration_t>(steps.col(0))); + roadmap()->initNode (make_shared<Configuration_t>(steps.col(0))); core::NodePtr_t init = roadmap()-> initNode (); core::NodePtr_t goal = roadmap()->addGoalNode ( - boost::make_shared<Configuration_t>(steps.col(nDiscreteSteps_))); + make_shared<Configuration_t>(steps.col(nDiscreteSteps_))); roadmap()->addEdge (init, goal, path); success = true; if (feasibilityOnly_) break; diff --git a/src/problem-solver.cc b/src/problem-solver.cc index fadf04c..86df217 100644 --- a/src/problem-solver.cc +++ b/src/problem-solver.cc @@ -17,8 +17,6 @@ #include "hpp/manipulation/problem-solver.hh" -#include <boost/bind.hpp> - #include <hpp/util/pointer.hh> #include <hpp/util/debug.hh> @@ -93,7 +91,7 @@ namespace hpp { core::SteeringMethodPtr_t createSMWithGuess (const core::ProblemConstPtr_t& problem) { - boost::shared_ptr<ParentSM_t> sm = ParentSM_t::create (problem); + shared_ptr<ParentSM_t> sm = ParentSM_t::create (problem); sm->innerSteeringMethod (ChildSM_t::createWithGuess (problem)); return sm; } @@ -272,27 +270,27 @@ namespace hpp { (Constraint_t::createConstraintAndComplement (name, robot_, floorSurfaces, objectSurfaces, margin)); - addNumericalConstraint(boost::get<0>(constraints)->function().name(), - boost::get<0>(constraints)); - addNumericalConstraint(boost::get<1>(constraints)->function().name(), - boost::get<1>(constraints)); - addNumericalConstraint(boost::get<2>(constraints)->function().name(), - boost::get<2>(constraints)); + addNumericalConstraint(std::get<0>(constraints)->function().name(), + std::get<0>(constraints)); + addNumericalConstraint(std::get<1>(constraints)->function().name(), + std::get<1>(constraints)); + addNumericalConstraint(std::get<2>(constraints)->function().name(), + std::get<2>(constraints)); // Set security margin to contact constraint assert(HPP_DYNAMIC_PTR_CAST(constraints::ConvexShapeContact, - boost::get<0>(constraints)->functionPtr())); + std::get<0>(constraints)->functionPtr())); constraints::ConvexShapeContactPtr_t contactFunction (HPP_STATIC_PTR_CAST(constraints::ConvexShapeContact, - boost::get<0>(constraints)->functionPtr())); + std::get<0>(constraints)->functionPtr())); contactFunction->setNormalMargin(margin); constraintsAndComplements.push_back ( - ConstraintAndComplement_t (boost::get<0>(constraints), - boost::get<1>(constraints), - boost::get<2>(constraints))); + ConstraintAndComplement_t (std::get<0>(constraints), + std::get<1>(constraints), + std::get<2>(constraints))); if (constraintGraph ()) - constraintGraph ()->registerConstraints(boost::get<0>(constraints), - boost::get<1>(constraints), - boost::get<2>(constraints)); + constraintGraph ()->registerConstraints(std::get<0>(constraints), + std::get<1>(constraints), + std::get<2>(constraints)); } void ProblemSolver::createPrePlacementConstraint diff --git a/src/problem.cc b/src/problem.cc index 1a3cf39..a0cdc35 100644 --- a/src/problem.cc +++ b/src/problem.cc @@ -75,7 +75,7 @@ namespace hpp { { PathValidationPtr_t pv (pvFactory_ (robot(), pvTol_)); - boost::shared_ptr<core::ObstacleUserInterface> oui = + shared_ptr<core::ObstacleUserInterface> oui = HPP_DYNAMIC_PTR_CAST(core::ObstacleUserInterface, pv); if (oui) { const core::ObjectStdVector_t& obstacles (collisionObstacles ()); diff --git a/src/steering-method/cross-state-optimization.cc b/src/steering-method/cross-state-optimization.cc index e6b3d2e..3d43520 100644 --- a/src/steering-method/cross-state-optimization.cc +++ b/src/steering-method/cross-state-optimization.cc @@ -21,8 +21,6 @@ #include <queue> #include <vector> -#include <boost/bind.hpp> - #include <hpp/util/exception-factory.hh> #include <pinocchio/multibody/model.hpp> -- GitLab