hpp::manipulation::steeringMethod::EndEffectorTrajectory Class Reference

Build StraightPath constrained by a varying right hand side constraint. More...

#include <hpp/manipulation/steering-method/end-effector-trajectory.hh>

Inheritance diagram for hpp::manipulation::steeringMethod::EndEffectorTrajectory:
[legend]
Collaboration diagram for hpp::manipulation::steeringMethod::EndEffectorTrajectory:
[legend]

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_ttrajectoryConstraint ()
 
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_ttrajectory () const
 
const interval_ttimeRange () const
 
core::SteeringMethodPtr_t copy () const
 
- Public Member Functions inherited from hpp::core::SteeringMethod
PathPtr_t operator() (ConfigurationIn_t q1, ConfigurationIn_t q2) const
 
PathPtr_t steer (ConfigurationIn_t q1, ConfigurationIn_t q2) const
 
virtual ~SteeringMethod ()
 
const Problemproblem () const
 
void constraints (const ConstraintSetPtr_t &constraints)
 
const ConstraintSetPtr_tconstraints () const
 
void constraints (const ConstraintSetPtr_t &constraints)
 
const ConstraintSetPtr_tconstraints () 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
 
- Protected Member Functions inherited from hpp::core::SteeringMethod
 SteeringMethod (const Problem &problem)
 
 SteeringMethod (const SteeringMethod &other)
 
void init (SteeringMethodWkPtr_t weak)
 

Additional Inherited Members

- Protected Attributes inherited from hpp::core::SteeringMethod
const Problemproblem_
 

Detailed Description

Build StraightPath constrained by a varying right hand side constraint.

Member Typedef Documentation

Constructor & Destructor Documentation

hpp::manipulation::steeringMethod::EndEffectorTrajectory::EndEffectorTrajectory ( const core::Problem problem)
inlineprotected
hpp::manipulation::steeringMethod::EndEffectorTrajectory::EndEffectorTrajectory ( const EndEffectorTrajectory other)
inlineprotected

References impl_compute().

Member Function Documentation

core::SteeringMethodPtr_t hpp::manipulation::steeringMethod::EndEffectorTrajectory::copy ( ) const
inlinevirtual
static EndEffectorTrajectoryPtr_t hpp::manipulation::steeringMethod::EndEffectorTrajectory::create ( const core::Problem problem)
inlinestatic
PathPtr_t hpp::manipulation::steeringMethod::EndEffectorTrajectory::impl_compute ( ConfigurationIn_t  q1,
ConfigurationIn_t  q2 
) const
protectedvirtual
const interval_t& hpp::manipulation::steeringMethod::EndEffectorTrajectory::timeRange ( ) const
inline
void hpp::manipulation::steeringMethod::EndEffectorTrajectory::trajectory ( const PathPtr_t eeTraj,
bool  se3Output 
)

Set the right hand side of the function from a path.

Parameters
se3Outputset 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.

Parameters
eeTraja function whose input space is of dimension 1.
timeRangethe input range of eeTraj.
const DifferentiableFunctionPtr_t& hpp::manipulation::steeringMethod::EndEffectorTrajectory::trajectory ( ) const
inline
void hpp::manipulation::steeringMethod::EndEffectorTrajectory::trajectoryConstraint ( const constraints::ImplicitPtr_t ic)

Set the constraint whose right hand side will vary.

const constraints::ImplicitPtr_t& hpp::manipulation::steeringMethod::EndEffectorTrajectory::trajectoryConstraint ( )
inline