|
hpp-manipulation 6.1.0
Classes for manipulation planning.
|
#include <hpp/manipulation/steering-method/end-effector-trajectory.hh>


Public Types | |
| typedef core::interval_t | interval_t |
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 |
Protected Member Functions inherited from hpp::core::SteeringMethod | |
| SteeringMethod (const ProblemConstPtr_t &problem) | |
| SteeringMethod (const SteeringMethod &other) | |
| void | init (SteeringMethodWkPtr_t weak) |
Build piecewise straight paths for a robot end-effector
To use this steering method, the user needs to provide
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.
|
inlineprotected |
|
inlineprotected |
|
inlinevirtual |
Implements hpp::core::SteeringMethod.
|
inlinestatic |
|
protectedvirtual |
Implements hpp::core::SteeringMethod.
|
static |
Build a trajectory in SE(3).
| points | a Nx7 matrix whose rows corresponds to poses. |
| weights | a 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*}
| PathPtr_t hpp::manipulation::steeringMethod::EndEffectorTrajectory::projectedPath | ( | vectorIn_t | times, |
| matrixIn_t | configs ) const |
Computes an core::InterpolatedPath from the provided interpolation points.
| times | the time of each configuration |
| configs | each column correspond to a configuration |
|
inline |
|
inline |
| 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. |
| 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. |
|
inline |
| void hpp::manipulation::steeringMethod::EndEffectorTrajectory::trajectoryConstraint | ( | const constraints::ImplicitPtr_t & | ic | ) |
Set the constraint whose right hand side will vary.