29 #ifndef HPP_MANIPULATION_PATH_PLANNER_END_EFFECTOR_TRAJECTORY_HH
30 #define HPP_MANIPULATION_PATH_PLANNER_END_EFFECTOR_TRAJECTORY_HH
32 #include <hpp/core/path-planner.hh>
35 #include <hpp/pinocchio/frame.hh>
36 #include <pinocchio/spatial/se3.hpp>
39 namespace manipulation {
40 namespace pathPlanner {
140 ikSolverInit_ = solver;
155 void init(
const EndEffectorTrajectoryWkPtr_t& weak);
158 std::vector<core::Configuration_t> configurations(
162 EndEffectorTrajectoryWkPtr_t weak_;
170 bool feasibilityOnly_;
Definition: end-effector-trajectory.hh:95
Definition: end-effector-trajectory.hh:41
#define HPP_MANIPULATION_DLLAPI
Definition: config.hh:88
void nDiscreteSteps(int n)
Definition: end-effector-trajectory.hh:128
void tryConnectInitAndGoals()
void ikSolverInitialization(IkSolverInitializationPtr_t solver)
Definition: end-effector-trajectory.hh:139
virtual Configurations_t impl_solve(vectorIn_t target)=0
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)
Configurations_t solve(vectorIn_t target)
Definition: end-effector-trajectory.hh:45
virtual void startSolve()
EndEffectorTrajectory(const core::ProblemConstPtr_t &problem, const core::RoadmapPtr_t &roadmap)
bool checkFeasibilityOnly() const
Definition: end-effector-trajectory.hh:137
std::vector< Configuration_t > Configurations_t
Definition: end-effector-trajectory.hh:43
int nRandomConfig() const
Definition: end-effector-trajectory.hh:118
void checkFeasibilityOnly(bool enable)
int nDiscreteSteps() const
Number of steps to generate goal config (successive projections).
Definition: end-effector-trajectory.hh:126
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:120
shared_ptr< EndEffectorTrajectory > EndEffectorTrajectoryPtr_t
Definition: fwd.hh:99
HPP_PREDEF_CLASS(EndEffectorTrajectory)
shared_ptr< IkSolverInitialization > IkSolverInitializationPtr_t
Definition: end-effector-trajectory.hh:50
shared_ptr< Roadmap > RoadmapPtr_t
Definition: fwd.hh:68
pinocchio::Configuration_t Configuration_t
Definition: fwd.hh:48
shared_ptr< const Problem > ProblemConstPtr_t
Definition: fwd.hh:66
core::vectorIn_t vectorIn_t
Definition: fwd.hh:93