hpp-manipulation  6.0.0
Classes for manipulation planning.
hpp::manipulation::steeringMethod::EndEffectorTrajectory Class Reference

#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_t & trajectoryConstraint ()
 
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
 

Static Public Member Functions

static EndEffectorTrajectoryPtr_t create (const core::ProblemConstPtr_t &problem)
 
static PathPtr_t makePiecewiseLinearTrajectory (matrixIn_t points, vectorIn_t weights)
 

Protected Member Functions

 EndEffectorTrajectory (const core::ProblemConstPtr_t &problem)
 
 EndEffectorTrajectory (const EndEffectorTrajectory &other)
 
PathPtr_t impl_compute (ConfigurationIn_t q1, ConfigurationIn_t q2) const
 

Detailed Description

Build piecewise straight paths for a robot end-effector

To use this steering method, the user needs to provide

Warning
the constraint should also be inserted in the set of constraints of the steering method.

Once the steering method has been initialized, it can be called between two configurations q1 and q2. The interval of definition \([0,T]\) of the output path is the same as the one of the path provided as the right hand side of the constraint. Note that q1 and q2 should satisfy the constraint at times 0 and \(T\) respectively. The output path is a linear interpolation between q1 and q2 projected on the steering method constraints.

Member Typedef Documentation

◆ interval_t

Constructor & Destructor Documentation

◆ EndEffectorTrajectory() [1/2]

hpp::manipulation::steeringMethod::EndEffectorTrajectory::EndEffectorTrajectory ( const core::ProblemConstPtr_t &  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
inline

◆ create()

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

◆ impl_compute()

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

◆ 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 poses.
weightsa 6D vector, weights to be applied when computing the distance between two SE3 points.

The trajectory \(T\) is defined as follows. Let \(N\) be the number of lines of matrix points, \(p_i\) be the i-th line of points and let \(W\) be the diagonal matrix with the coefficients of weights:

\[ W = \left(\begin{array}{cccccc} w_1 & 0 & 0 & 0 & 0 & 0\\ 0 & w_2 & 0 & 0 & 0 & 0\\ 0 & 0 & w_3 & 0 & 0 & 0\\ 0 & 0 & 0 & w_4 & 0 & 0\\ 0 & 0 & 0 & 0 & w_5 & 0\\ 0 & 0 & 0 & 0 & 0 & w_6\\ \end{array}\right) \]

\begin{eqnarray*} f(t) = \mathbf{p}_i \oplus \frac{t-t_i}{t_{i+1}-t_i} (\mathbf{p}_{i+1}-\mathbf{p}_i) && \mbox{ for } t \in [t_i,t_{i+1}] \end{eqnarray*}

where \(t_0 = 0\) and

\begin{eqnarray*} t_{i+1}-t_i = \|W(\mathbf{p}_{i+1}-\mathbf{p}_i)\| && \mbox{for } i \mbox{ such that } 1 \leq i \leq N-1 \end{eqnarray*}

◆ 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]

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

◆ 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]

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.

◆ trajectoryConstraint() [1/2]

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

◆ trajectoryConstraint() [2/2]

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

Set the constraint whose right hand side will vary.


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