Build StraightPath constrained by a varying right hand side constraint. More...
#include <hpp/manipulation/steering-method/end-effector-trajectory.hh>
Public Types | |
typedef core::interval_t | interval_t |
Public Member Functions | |
void | trajectoryConstraint (const constraints::ImplicitPtr_t &ic) |
Set the constraint whose right hand side will vary. More... | |
const constraints::ImplicitPtr_t & | trajectoryConstraint () |
void | trajectory (const PathPtr_t &eeTraj, bool se3Output) |
Set the right hand side of the function from a path. More... | |
void | trajectory (const DifferentiableFunctionPtr_t &eeTraj, const interval_t &timeRange) |
Set the right hand side of the function from another function. More... | |
const DifferentiableFunctionPtr_t & | trajectory () const |
const interval_t & | timeRange () const |
core::SteeringMethodPtr_t | copy () const |
Static Public Member Functions | |
static EndEffectorTrajectoryPtr_t | create (const core::Problem &problem) |
Protected Member Functions | |
EndEffectorTrajectory (const core::Problem &problem) | |
EndEffectorTrajectory (const EndEffectorTrajectory &other) | |
PathPtr_t | impl_compute (ConfigurationIn_t q1, ConfigurationIn_t q2) const |
Build StraightPath constrained by a varying right hand side constraint.
typedef core::interval_t hpp::manipulation::steeringMethod::EndEffectorTrajectory::interval_t |
|
inlineprotected |
|
inlineprotected |
|
inline |
|
inlinestatic |
|
protected |
|
inline |
void hpp::manipulation::steeringMethod::EndEffectorTrajectory::trajectory | ( | const PathPtr_t & | eeTraj, |
bool | se3Output | ||
) |
Set the right hand side of the function from a path.
se3Output | set to True if the output of path must be understood as SE3. |
void hpp::manipulation::steeringMethod::EndEffectorTrajectory::trajectory | ( | const DifferentiableFunctionPtr_t & | eeTraj, |
const interval_t & | timeRange | ||
) |
Set the right hand side of the function from another function.
eeTraj | a function whose input space is of dimension 1. |
timeRange | the input range of eeTraj. |
|
inline |
void hpp::manipulation::steeringMethod::EndEffectorTrajectory::trajectoryConstraint | ( | const constraints::ImplicitPtr_t & | ic | ) |
Set the constraint whose right hand side will vary.
|
inline |