19 #ifndef HPP_MANIPULATION_PATH_PLANNER_END_EFFECTOR_TRAJECTORY_HH
20 # define HPP_MANIPULATION_PATH_PLANNER_END_EFFECTOR_TRAJECTORY_HH
25 # include <pinocchio/spatial/se3.hpp>
27 # include <hpp/pinocchio/frame.hh>
28 # include <hpp/core/path-planner.hh>
31 namespace manipulation {
32 namespace pathPlanner {
40 return impl_solve (target);
76 {
return nRandomConfig_; }
86 {
return nDiscreteSteps_; }
100 return feasibilityOnly_;
105 ikSolverInit_ = solver;
120 void init (
const EndEffectorTrajectoryWkPtr_t& weak);
126 EndEffectorTrajectoryWkPtr_t weak_;
134 bool feasibilityOnly_;
Definition: end-effector-trajectory.hh:52
void nDiscreteSteps(int n)
Definition: end-effector-trajectory.hh:88
void tryConnectInitAndGoals()
void ikSolverInitialization(IkSolverInitializationPtr_t solver)
Definition: end-effector-trajectory.hh:103
void init(const EndEffectorTrajectoryWkPtr_t &weak)
Store weak pointer to itself.
static EndEffectorTrajectoryPtr_t createWithRoadmap(const core::ProblemConstPtr_t &problem, const core::RoadmapPtr_t &roadmap)
virtual void startSolve()
EndEffectorTrajectory(const core::ProblemConstPtr_t &problem, const core::RoadmapPtr_t &roadmap)
bool checkFeasibilityOnly() const
Definition: end-effector-trajectory.hh:98
int nRandomConfig() const
Definition: end-effector-trajectory.hh:75
void checkFeasibilityOnly(bool enable)
int nDiscreteSteps() const
Number of steps to generate goal config (successive projections).
Definition: end-effector-trajectory.hh:85
EndEffectorTrajectory(const core::ProblemConstPtr_t &problem)
static EndEffectorTrajectoryPtr_t create(const core::ProblemConstPtr_t &problem)
virtual void oneStep()
One step of the algorithm.
void nRandomConfig(int n)
Definition: end-effector-trajectory.hh:78
Definition: end-effector-trajectory.hh:34
virtual Configurations_t impl_solve(vectorIn_t target)=0
Configurations_t solve(vectorIn_t target)
Definition: end-effector-trajectory.hh:38
std::vector< Configuration_t > Configurations_t
Definition: end-effector-trajectory.hh:36
#define HPP_MANIPULATION_DLLAPI
Definition: config.hh:64
HPP_PREDEF_CLASS(EndEffectorTrajectory)
shared_ptr< EndEffectorTrajectory > EndEffectorTrajectoryPtr_t
Definition: end-effector-trajectory.hh:49
shared_ptr< IkSolverInitialization > IkSolverInitializationPtr_t
Definition: end-effector-trajectory.hh:46
shared_ptr< Roadmap > RoadmapPtr_t
Definition: fwd.hh:58
pinocchio::Configuration_t Configuration_t
Definition: fwd.hh:37
shared_ptr< const Problem > ProblemConstPtr_t
Definition: fwd.hh:56
core::vectorIn_t vectorIn_t
Definition: fwd.hh:86