Skip to content
Snippets Groups Projects
Commit 1c06ef09 authored by pre-commit-ci[bot]'s avatar pre-commit-ci[bot]
Browse files

[pre-commit.ci] auto fixes from pre-commit.com hooks

for more information, see https://pre-commit.ci
parent 7e647d85
No related branches found
No related tags found
No related merge requests found
Pipeline #28874 passed
...@@ -96,23 +96,23 @@ typedef core::vectorOut_t vectorOut_t; ...@@ -96,23 +96,23 @@ typedef core::vectorOut_t vectorOut_t;
HPP_PREDEF_CLASS(ManipulationPlanner); HPP_PREDEF_CLASS(ManipulationPlanner);
typedef shared_ptr<ManipulationPlanner> ManipulationPlannerPtr_t; typedef shared_ptr<ManipulationPlanner> ManipulationPlannerPtr_t;
namespace pathPlanner { namespace pathPlanner {
HPP_PREDEF_CLASS(EndEffectorTrajectory); HPP_PREDEF_CLASS(EndEffectorTrajectory);
typedef shared_ptr<EndEffectorTrajectory> EndEffectorTrajectoryPtr_t; typedef shared_ptr<EndEffectorTrajectory> EndEffectorTrajectoryPtr_t;
HPP_PREDEF_CLASS (StatesPathFinder); HPP_PREDEF_CLASS(StatesPathFinder);
typedef shared_ptr < StatesPathFinder > StatesPathFinderPtr_t; typedef shared_ptr<StatesPathFinder> StatesPathFinderPtr_t;
HPP_PREDEF_CLASS (InStatePath); HPP_PREDEF_CLASS(InStatePath);
typedef shared_ptr < InStatePath > InStatePathPtr_t; typedef shared_ptr<InStatePath> InStatePathPtr_t;
HPP_PREDEF_CLASS (StateShooter); HPP_PREDEF_CLASS(StateShooter);
typedef shared_ptr < StateShooter > StateShooterPtr_t; typedef shared_ptr<StateShooter> StateShooterPtr_t;
} // namespace pathPlanner } // namespace pathPlanner
HPP_PREDEF_CLASS(GraphPathValidation); HPP_PREDEF_CLASS(GraphPathValidation);
typedef shared_ptr<GraphPathValidation> GraphPathValidationPtr_t; typedef shared_ptr<GraphPathValidation> GraphPathValidationPtr_t;
HPP_PREDEF_CLASS(SteeringMethod); HPP_PREDEF_CLASS(SteeringMethod);
typedef shared_ptr<SteeringMethod> SteeringMethodPtr_t; typedef shared_ptr<SteeringMethod> SteeringMethodPtr_t;
namespace steeringMethod{ namespace steeringMethod {
HPP_PREDEF_CLASS(EndEffectorTrajectory); HPP_PREDEF_CLASS(EndEffectorTrajectory);
typedef shared_ptr<EndEffectorTrajectory> EndEffectorTrajectoryPtr_t; typedef shared_ptr<EndEffectorTrajectory> EndEffectorTrajectoryPtr_t;
} } // namespace steeringMethod
typedef core::PathOptimizer PathOptimizer; typedef core::PathOptimizer PathOptimizer;
typedef core::PathOptimizerPtr_t PathOptimizerPtr_t; typedef core::PathOptimizerPtr_t PathOptimizerPtr_t;
HPP_PREDEF_CLASS(GraphOptimizer); HPP_PREDEF_CLASS(GraphOptimizer);
......
...@@ -17,119 +17,112 @@ ...@@ -17,119 +17,112 @@
// hpp-manipulation. If not, see <http://www.gnu.org/licenses/>. // hpp-manipulation. If not, see <http://www.gnu.org/licenses/>.
#ifndef HPP_MANIPULATION_PATH_PLANNER_IN_STATE_PATH_HH #ifndef HPP_MANIPULATION_PATH_PLANNER_IN_STATE_PATH_HH
# define HPP_MANIPULATION_PATH_PLANNER_IN_STATE_PATH_HH #define HPP_MANIPULATION_PATH_PLANNER_IN_STATE_PATH_HH
# include <hpp/core/path-planner.hh> #include <hpp/core/collision-validation.hh>
# include <hpp/core/config-projector.hh> #include <hpp/core/config-projector.hh>
# include <hpp/core/collision-validation.hh> #include <hpp/core/joint-bound-validation.hh>
# include <hpp/core/joint-bound-validation.hh> #include <hpp/core/path-planner.hh>
#include <hpp/manipulation/config.hh>
# include <hpp/manipulation/config.hh> #include <hpp/manipulation/fwd.hh>
# include <hpp/manipulation/fwd.hh> #include <hpp/manipulation/problem.hh>
# include <hpp/manipulation/problem.hh> #include <hpp/manipulation/steering-method/graph.hh>
# include <hpp/manipulation/steering-method/graph.hh>
namespace hpp { namespace hpp {
namespace manipulation { namespace manipulation {
namespace pathPlanner { namespace pathPlanner {
/// \addtogroup path_planner /// \addtogroup path_planner
/// \{ /// \{
/// ///
/// Path planner designed to build a path between two configurations /// Path planner designed to build a path between two configurations
/// on the same leaf of a given state graph edge /// on the same leaf of a given state graph edge
class HPP_MANIPULATION_DLLAPI InStatePath : public core::PathPlanner class HPP_MANIPULATION_DLLAPI InStatePath : public core::PathPlanner {
{ public:
public: virtual ~InStatePath() {}
virtual ~InStatePath()
{} static InStatePathPtr_t create(const core::ProblemConstPtr_t& problem);
static InStatePathPtr_t create ( static InStatePathPtr_t createWithRoadmap(
const core::ProblemConstPtr_t& problem); const core::ProblemConstPtr_t& problem,
const core::RoadmapPtr_t& roadmap);
static InStatePathPtr_t createWithRoadmap (
const core::ProblemConstPtr_t& problem, InStatePathPtr_t copy() const;
const core::RoadmapPtr_t& roadmap);
void maxIterPlanner(const unsigned long& maxiter);
InStatePathPtr_t copy () const; void timeOutPlanner(const double& timeout);
void resetRoadmap(const bool& resetroadmap);
void maxIterPlanner(const unsigned long& maxiter); void plannerType(const std::string& plannertype);
void timeOutPlanner(const double& timeout); void addOptimizerType(const std::string& opttype);
void resetRoadmap(const bool& resetroadmap); void resetOptimizerTypes();
void plannerType(const std::string& plannertype);
void addOptimizerType(const std::string& opttype); /// Set the edge along which q_init and q_goal will be linked.
void resetOptimizerTypes(); /// Use setEdge before setInit and setGoal.
void setEdge(const graph::EdgePtr_t& edge);
/// Set the edge along which q_init and q_goal will be linked. void setInit(const ConfigurationPtr_t& q);
/// Use setEdge before setInit and setGoal. void setGoal(const ConfigurationPtr_t& q);
void setEdge (const graph::EdgePtr_t& edge);
void setInit (const ConfigurationPtr_t& q); virtual void oneStep() {}
void setGoal (const ConfigurationPtr_t& q); virtual core::PathVectorPtr_t solve();
virtual void oneStep() const core::RoadmapPtr_t& leafRoadmap() const;
{} void mergeLeafRoadmapWith(const core::RoadmapPtr_t& roadmap) const;
virtual core::PathVectorPtr_t solve();
protected:
const core::RoadmapPtr_t& leafRoadmap() const; InStatePath(const core::ProblemConstPtr_t& problem,
void mergeLeafRoadmapWith(const core::RoadmapPtr_t& roadmap) const; const core::RoadmapPtr_t& roadmap)
: PathPlanner(problem),
protected: problem_(HPP_STATIC_PTR_CAST(const manipulation::Problem, problem)),
InStatePath (const core::ProblemConstPtr_t& problem, leafRoadmap_(roadmap),
const core::RoadmapPtr_t& roadmap) : constraints_(),
PathPlanner(problem), weak_() {
problem_ (HPP_STATIC_PTR_CAST(const manipulation::Problem, problem)), const core::DevicePtr_t& robot = problem_->robot();
leafRoadmap_(roadmap), leafProblem_ = core::Problem::create(robot);
constraints_(), weak_() leafProblem_->setParameter("kPRM*/numberOfNodes",
{ core::Parameter((size_type)2000));
const core::DevicePtr_t& robot = problem_->robot(); leafProblem_->clearConfigValidations();
leafProblem_ = core::Problem::create(robot); leafProblem_->addConfigValidation(core::CollisionValidation::create(robot));
leafProblem_->setParameter leafProblem_->addConfigValidation(
("kPRM*/numberOfNodes", core::Parameter((size_type) 2000)); core::JointBoundValidation::create(robot));
leafProblem_->clearConfigValidations(); for (const core::CollisionObjectPtr_t& obs :
leafProblem_->addConfigValidation(core::CollisionValidation::create(robot)); problem_->collisionObstacles()) {
leafProblem_->addConfigValidation(core::JointBoundValidation::create(robot)); leafProblem_->addObstacle(obs);
for (const core::CollisionObjectPtr_t & obs: problem_->collisionObstacles()) { }
leafProblem_->addObstacle(obs); leafProblem_->pathProjector(problem->pathProjector());
} }
leafProblem_->pathProjector(problem->pathProjector());
} InStatePath(const InStatePath& other)
: PathPlanner(other.problem_),
InStatePath (const InStatePath& other) : problem_(other.problem_),
PathPlanner(other.problem_), leafProblem_(other.leafProblem_),
problem_(other.problem_), leafProblem_(other.leafProblem_), leafRoadmap_(other.leafRoadmap_),
leafRoadmap_ (other.leafRoadmap_), constraints_(other.constraints_),
constraints_(other.constraints_), weak_() {}
weak_ ()
{} void init(InStatePathWkPtr_t weak) { weak_ = weak; }
void init (InStatePathWkPtr_t weak) private:
{ // a pointer to the problem used to create the InStatePath instance
weak_ = weak; ProblemConstPtr_t problem_;
} // a new problem created for this InStatePath instance
core::ProblemPtr_t leafProblem_;
private: core::RoadmapPtr_t leafRoadmap_;
ConstraintSetPtr_t constraints_;
// a pointer to the problem used to create the InStatePath instance
ProblemConstPtr_t problem_; double timeOutPathPlanning_ = 0;
// a new problem created for this InStatePath instance unsigned long maxIterPathPlanning_ = 0;
core::ProblemPtr_t leafProblem_; bool resetRoadmap_ = true;
core::RoadmapPtr_t leafRoadmap_; std::string plannerType_ = "BiRRT*";
ConstraintSetPtr_t constraints_; std::vector<std::string> optimizerTypes_;
double timeOutPathPlanning_ = 0; /// Weak pointer to itself
unsigned long maxIterPathPlanning_ = 0; InStatePathWkPtr_t weak_;
bool resetRoadmap_ = true;
std::string plannerType_ = "BiRRT*"; }; // class InStatePath
std::vector<std::string> optimizerTypes_; /// \}
/// Weak pointer to itself } // namespace pathPlanner
InStatePathWkPtr_t weak_; } // namespace manipulation
} // namespace hpp
}; // class InStatePath
/// \} #endif // HPP_MANIPULATION_STEERING_METHOD_CROSS_STATE_OPTIMIZATION_HH
} // namespace pathPlanner
} // namespace manipulation
} // namespace hpp
#endif // HPP_MANIPULATION_STEERING_METHOD_CROSS_STATE_OPTIMIZATION_HH
This diff is collapsed.
...@@ -77,9 +77,8 @@ class HPP_MANIPULATION_DLLAPI EndEffectorTrajectory ...@@ -77,9 +77,8 @@ class HPP_MANIPULATION_DLLAPI EndEffectorTrajectory
\f] \f]
\f{eqnarray*}{ \f{eqnarray*}{
f(t) = \mathbf{p}_i \oplus \frac{t-t_i}{t_{i+1}-t_i} (\mathbf{p}_{i+1}-\mathbf{p}_i) && f(t) = \mathbf{p}_i \oplus \frac{t-t_i}{t_{i+1}-t_i}
\mbox{ for } t \in [t_i,t_{i+1}] (\mathbf{p}_{i+1}-\mathbf{p}_i) && \mbox{ for } t \in [t_i,t_{i+1}] \f}
\f}
where \f$t_0 = 0\f$ and where \f$t_0 = 0\f$ and
\f{eqnarray*}{ \f{eqnarray*}{
......
This diff is collapsed.
...@@ -62,8 +62,8 @@ ...@@ -62,8 +62,8 @@
#include "hpp/manipulation/path-optimization/enforce-transition-semantic.hh" #include "hpp/manipulation/path-optimization/enforce-transition-semantic.hh"
#include "hpp/manipulation/path-optimization/random-shortcut.hh" #include "hpp/manipulation/path-optimization/random-shortcut.hh"
#include "hpp/manipulation/path-planner/end-effector-trajectory.hh" #include "hpp/manipulation/path-planner/end-effector-trajectory.hh"
#include "hpp/manipulation/path-planner/states-path-finder.hh"
#include "hpp/manipulation/path-planner/in-state-path.hh" #include "hpp/manipulation/path-planner/in-state-path.hh"
#include "hpp/manipulation/path-planner/states-path-finder.hh"
#include "hpp/manipulation/problem-target/state.hh" #include "hpp/manipulation/problem-target/state.hh"
#include "hpp/manipulation/problem.hh" #include "hpp/manipulation/problem.hh"
#include "hpp/manipulation/roadmap.hh" #include "hpp/manipulation/roadmap.hh"
...@@ -125,8 +125,8 @@ ProblemSolver::ProblemSolver() : core::ProblemSolver(), robot_(), problem_() { ...@@ -125,8 +125,8 @@ ProblemSolver::ProblemSolver() : core::ProblemSolver(), robot_(), problem_() {
pathPlanners.add("M-RRT", ManipulationPlanner::create); pathPlanners.add("M-RRT", ManipulationPlanner::create);
pathPlanners.add("EndEffectorTrajectory", pathPlanners.add("EndEffectorTrajectory",
pathPlanner::EndEffectorTrajectory::createWithRoadmap); pathPlanner::EndEffectorTrajectory::createWithRoadmap);
pathPlanners.add ("StatesPathFinder", pathPlanners.add("StatesPathFinder",
pathPlanner::StatesPathFinder::createWithRoadmap); pathPlanner::StatesPathFinder::createWithRoadmap);
pathValidations.add("Graph-Discretized", pathValidations.add("Graph-Discretized",
createDiscretizedCollisionGraphPathValidation); createDiscretizedCollisionGraphPathValidation);
pathValidations.add("Graph-DiscretizedCollision", pathValidations.add("Graph-DiscretizedCollision",
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment