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>
39namespace manipulation {
40namespace pathPlanner {
60 const core::ProblemConstPtr_t& problem);
65 const core::ProblemConstPtr_t& problem,
66 const core::RoadmapPtr_t& roadmap);
100 ikSolverInit_ = solver;
113 const core::RoadmapPtr_t& roadmap);
115 void init(
const EndEffectorTrajectoryWkPtr_t& weak);
118 std::vector<core::Configuration_t> configurations(
119 const core::Configuration_t& q_init);
122 EndEffectorTrajectoryWkPtr_t weak_;
130 bool feasibilityOnly_;
Definition: end-effector-trajectory.hh:55
void nDiscreteSteps(int n)
Definition: end-effector-trajectory.hh:88
void tryConnectInitAndGoals()
void ikSolverInitialization(IkSolverInitializationPtr_t solver)
Definition: end-effector-trajectory.hh:99
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:97
int nRandomConfig() const
Definition: end-effector-trajectory.hh:78
void checkFeasibilityOnly(bool enable)
int nDiscreteSteps() const
Number of steps to generate goal config (successive projections).
Definition: end-effector-trajectory.hh:86
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:80
Definition: end-effector-trajectory.hh:41
virtual Configurations_t impl_solve(vectorIn_t target)=0
Configurations_t solve(vectorIn_t target)
Definition: end-effector-trajectory.hh:45
std::vector< Configuration_t > Configurations_t
Definition: end-effector-trajectory.hh:43
#define HPP_MANIPULATION_DLLAPI
Definition: config.hh:64
HPP_PREDEF_CLASS(EndEffectorTrajectory)
shared_ptr< EndEffectorTrajectory > EndEffectorTrajectoryPtr_t
Definition: end-effector-trajectory.hh:53
shared_ptr< IkSolverInitialization > IkSolverInitializationPtr_t
Definition: end-effector-trajectory.hh:50
core::vectorIn_t vectorIn_t
Definition: fwd.hh:94