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