hpp-manipulation  4.9.0
Classes for manipulation planning.
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:
Collaboration diagram for hpp::manipulation::steeringMethod::EndEffectorTrajectory:

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)
 
void trajectory (const DifferentiableFunctionPtr_t &eeTraj, const interval_t &timeRange)
 
const DifferentiableFunctionPtr_ttrajectory () const
 
const interval_ttimeRange () const
 
core::SteeringMethodPtr_t copy () const
 
PathPtr_t projectedPath (vectorIn_t times, matrixIn_t configs) 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
 
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)
 
static PathPtr_t makePiecewiseLinearTrajectory (matrixIn_t points, vectorIn_t weights)
 

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)
 
 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

◆ interval_t

Constructor & Destructor Documentation

◆ EndEffectorTrajectory() [1/2]

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

◆ EndEffectorTrajectory() [2/2]

hpp::manipulation::steeringMethod::EndEffectorTrajectory::EndEffectorTrajectory ( const EndEffectorTrajectory other)
inlineprotected

Member Function Documentation

◆ copy()

core::SteeringMethodPtr_t hpp::manipulation::steeringMethod::EndEffectorTrajectory::copy ( ) const
inlinevirtual

◆ create()

static EndEffectorTrajectoryPtr_t hpp::manipulation::steeringMethod::EndEffectorTrajectory::create ( const core::Problem problem)
inlinestatic

◆ impl_compute()

PathPtr_t hpp::manipulation::steeringMethod::EndEffectorTrajectory::impl_compute ( ConfigurationIn_t  q1,
ConfigurationIn_t  q2 
) const
protectedvirtual

◆ makePiecewiseLinearTrajectory()

static PathPtr_t hpp::manipulation::steeringMethod::EndEffectorTrajectory::makePiecewiseLinearTrajectory ( matrixIn_t  points,
vectorIn_t  weights 
)
static

Build a trajectory in SE(3).

Parameters
pointsa Nx7 matrix whose rows corresponds to a pose.
weightsa 6D vector, weights to be applied when computing the distance between two SE3 points.

◆ projectedPath()

PathPtr_t hpp::manipulation::steeringMethod::EndEffectorTrajectory::projectedPath ( vectorIn_t  times,
matrixIn_t  configs 
) const

Computes an core::InterpolatedPath from the provided interpolation points.

Parameters
timesthe time of each configuration
configseach column correspond to a configuration

◆ timeRange()

const interval_t& hpp::manipulation::steeringMethod::EndEffectorTrajectory::timeRange ( ) const
inline

◆ trajectory() [1/3]

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.

◆ trajectory() [2/3]

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.

◆ trajectory() [3/3]

const DifferentiableFunctionPtr_t& hpp::manipulation::steeringMethod::EndEffectorTrajectory::trajectory ( ) const
inline

◆ trajectoryConstraint() [1/2]

void hpp::manipulation::steeringMethod::EndEffectorTrajectory::trajectoryConstraint ( const constraints::ImplicitPtr_t ic)

Set the constraint whose right hand side will vary.

◆ trajectoryConstraint() [2/2]

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

The documentation for this class was generated from the following file: