Build piecewise straight paths for a robot end-effector
To use this steering method, the user needs to provide
- a constraint with value in \(SE(3)\). An easy way to create such a constraint is to use method hpp::manipulation::Handle::createGrasp. The constraint is passed to the steering method using method trajectoryConstraint .
- the time-varying right hand side of this constraint along the path the user wants to create in the form of a hpp::core::Path instance with values in \(SE(3)\). For that, makePiecewiseLinearTrajectory method may be useful.
- 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.
static PathPtr_t hpp::manipulation::steeringMethod::EndEffectorTrajectory::makePiecewiseLinearTrajectory |
( |
matrixIn_t |
points, |
|
|
vectorIn_t |
weights |
|
) |
| |
|
static |
Build a trajectory in SE(3).
- Parameters
-
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*}