29#ifndef HPP_MANIPULATION_STEERING_METHOD_END_EFFECTOR_TRAJECTORY_HH
30#define HPP_MANIPULATION_STEERING_METHOD_END_EFFECTOR_TRAJECTORY_HH
32#include <hpp/core/steering-method.hh>
37namespace manipulation {
38namespace steeringMethod {
73 :
public core::SteeringMethod {
156 eeTraj_(other.eeTraj_),
157 timeRange_(other.timeRange_),
158 constraint_(other.constraint_) {}
Definition: end-effector-trajectory.hh:73
static EndEffectorTrajectoryPtr_t create(const core::ProblemConstPtr_t &problem)
Definition: end-effector-trajectory.hh:77
EndEffectorTrajectory(const core::ProblemConstPtr_t &problem)
Definition: end-effector-trajectory.hh:151
const constraints::ImplicitPtr_t & trajectoryConstraint()
Definition: end-effector-trajectory.hh:119
const DifferentiableFunctionPtr_t & trajectory() const
Definition: end-effector-trajectory.hh:134
PathPtr_t impl_compute(ConfigurationIn_t q1, ConfigurationIn_t q2) const
PathPtr_t projectedPath(vectorIn_t times, matrixIn_t configs) const
core::interval_t interval_t
Definition: end-effector-trajectory.hh:75
void trajectoryConstraint(const constraints::ImplicitPtr_t &ic)
Set the constraint whose right hand side will vary.
EndEffectorTrajectory(const EndEffectorTrajectory &other)
Definition: end-effector-trajectory.hh:154
static PathPtr_t makePiecewiseLinearTrajectory(matrixIn_t points, vectorIn_t weights)
const interval_t & timeRange() const
Definition: end-effector-trajectory.hh:136
void trajectory(const PathPtr_t &eeTraj, bool se3Output)
void trajectory(const DifferentiableFunctionPtr_t &eeTraj, const interval_t &timeRange)
core::SteeringMethodPtr_t copy() const
Definition: end-effector-trajectory.hh:138
#define HPP_MANIPULATION_DLLAPI
Definition: config.hh:88
shared_ptr< EndEffectorTrajectory > EndEffectorTrajectoryPtr_t
Definition: fwd.hh:115
HPP_PREDEF_CLASS(EndEffectorTrajectory)
core::DifferentiableFunctionPtr_t DifferentiableFunctionPtr_t
Definition: fwd.hh:139
shared_ptr< ConstraintSet > ConstraintSetPtr_t
Definition: fwd.hh:138
core::matrixIn_t matrixIn_t
Definition: fwd.hh:147
shared_ptr< const Problem > ProblemConstPtr_t
Definition: fwd.hh:66
constraints::ImplicitPtr_t ImplicitPtr_t
Definition: fwd.hh:131
pinocchio::ConfigurationIn_t ConfigurationIn_t
Definition: fwd.hh:49
core::vectorIn_t vectorIn_t
Definition: fwd.hh:93
shared_ptr< SteeringMethod > SteeringMethodPtr_t
Definition: fwd.hh:112