Represents a trajectory for and end effector uses the method effector_spline to create a spline trajectory. Additionally, handles the rotation of the effector as follows: does not rotate during the take off and landing phase, then uses a SLERP algorithm to interpolate the rotation in the quaternion space.
More...
#include <parametric-curves/helpers/effector_spline_rotation.h>
|
template<typename In > |
| effector_spline_rotation (In wayPointsBegin, In wayPointsEnd, quat_ref_const_t &to_quat=quat_t(0, 0, 0, 1), quat_ref_const_t &land_quat=quat_t(0, 0, 0, 1), const Point &lift_normal=Eigen::Vector3d::UnitZ(), const Point &land_normal=Eigen::Vector3d::UnitZ(), const Numeric lift_offset=0.02, const Numeric land_offset=0.02, const Time lift_offset_duration=0.02, const Time land_offset_duration=0.02) |
| Constructor. Given a set of waypoints, and the normal vector of the start and ending positions, automatically create the spline such that: More...
|
|
template<typename In , typename InQuat > |
| effector_spline_rotation (In wayPointsBegin, In wayPointsEnd, InQuat quatWayPointsBegin, InQuat quatWayPointsEnd, const Point &lift_normal=Eigen::Vector3d::UnitZ(), const Point &land_normal=Eigen::Vector3d::UnitZ(), const Numeric lift_offset=0.02, const Numeric land_offset=0.02, const Time lift_offset_duration=0.02, const Time land_offset_duration=0.02) |
| Constructor. Given a set of waypoints, and the normal vector of the start and ending positions, automatically create the spline such that: More...
|
|
| ~effector_spline_rotation () |
|
Numeric | min () const |
|
Numeric | max () const |
|
config_t | operator() (const Numeric t) const |
| Evaluation of the effector position and rotation at time t. More...
|
|
quat_t | interpolate_quat (const Numeric t) const |
|
Represents a trajectory for and end effector uses the method effector_spline to create a spline trajectory. Additionally, handles the rotation of the effector as follows: does not rotate during the take off and landing phase, then uses a SLERP algorithm to interpolate the rotation in the quaternion space.
◆ effector_spline_rotation() [1/2]
template<typename In >
spline::helpers::effector_spline_rotation::effector_spline_rotation |
( |
In |
wayPointsBegin, |
|
|
In |
wayPointsEnd, |
|
|
quat_ref_const_t & |
to_quat = quat_t(0, 0, 0, 1) , |
|
|
quat_ref_const_t & |
land_quat = quat_t(0, 0, 0, 1) , |
|
|
const Point & |
lift_normal = Eigen::Vector3d::UnitZ() , |
|
|
const Point & |
land_normal = Eigen::Vector3d::UnitZ() , |
|
|
const Numeric |
lift_offset = 0.02 , |
|
|
const Numeric |
land_offset = 0.02 , |
|
|
const Time |
lift_offset_duration = 0.02 , |
|
|
const Time |
land_offset_duration = 0.02 |
|
) |
| |
|
inline |
Constructor. Given a set of waypoints, and the normal vector of the start and ending positions, automatically create the spline such that:
- init and end velocities / accelerations are 0.
- the effector lifts and lands exactly in the direction of the specified normals
- Parameters
-
wayPointsBegin | : an iterator pointing to the first element of a waypoint container |
wayPointsEnd | : an iterator pointing to the end of a waypoint container |
to_quat | : 4D vector, quaternion indicating rotation at take off(x, y, z, w) |
land_quat | : 4D vector, quaternion indicating rotation at landing (x, y, z, w) |
lift_normal | : normal to be followed by end effector at take-off |
land_normal | : normal to be followed by end effector at landing |
lift_offset | : length of the straight line along normal at take-off |
land_offset | : length of the straight line along normal at landing |
lift_offset_duration | : time travelled along straight line at take-off |
land_offset_duration | : time travelled along straight line at landing |
◆ effector_spline_rotation() [2/2]
template<typename In , typename InQuat >
spline::helpers::effector_spline_rotation::effector_spline_rotation |
( |
In |
wayPointsBegin, |
|
|
In |
wayPointsEnd, |
|
|
InQuat |
quatWayPointsBegin, |
|
|
InQuat |
quatWayPointsEnd, |
|
|
const Point & |
lift_normal = Eigen::Vector3d::UnitZ() , |
|
|
const Point & |
land_normal = Eigen::Vector3d::UnitZ() , |
|
|
const Numeric |
lift_offset = 0.02 , |
|
|
const Numeric |
land_offset = 0.02 , |
|
|
const Time |
lift_offset_duration = 0.02 , |
|
|
const Time |
land_offset_duration = 0.02 |
|
) |
| |
|
inline |
Constructor. Given a set of waypoints, and the normal vector of the start and ending positions, automatically create the spline such that:
- init and end velocities / accelerations are 0.
- the effector lifts and lands exactly in the direction of the specified normals
- Parameters
-
wayPointsBegin | : an iterator pointing to the first element of a waypoint container |
wayPointsEnd | : an iterator pointing to the end of a waypoint container |
quatWayPointsBegin | : en iterator pointing to the first element of a 4D vector (x, y, z, w) container of quaternions indicating rotation at specific time steps. |
quatWayPointsEnd | : en iterator pointing to the end of a 4D vector (x, y, z, w) container of quaternions indicating rotation at specific time steps. |
lift_normal | : normal to be followed by end effector at take-off |
land_normal | : normal to be followed by end effector at landing |
lift_offset | : length of the straight line along normal at take-off |
land_offset | : length of the straight line along normal at landing |
lift_offset_duration | : time travelled along straight line at take-off |
land_offset_duration | : time travelled along straight line at landing |
◆ ~effector_spline_rotation()
spline::helpers::effector_spline_rotation::~effector_spline_rotation |
( |
| ) |
|
|
inline |
◆ interpolate_quat()
quat_t spline::helpers::effector_spline_rotation::interpolate_quat |
( |
const Numeric |
t | ) |
const |
|
inline |
◆ max()
Numeric spline::helpers::effector_spline_rotation::max |
( |
| ) |
const |
|
inline |
◆ min()
Numeric spline::helpers::effector_spline_rotation::min |
( |
| ) |
const |
|
inline |
◆ operator()()
config_t spline::helpers::effector_spline_rotation::operator() |
( |
const Numeric |
t | ) |
const |
|
inline |
Evaluation of the effector position and rotation at time t.
- Parameters
-
t | : the time when to evaluate the spline |
return | : a 7D vector; The 3 first values are the 3D position, the 4 last the quaternion describing the rotation |
◆ land_quat_
const Eigen::Quaterniond spline::helpers::effector_spline_rotation::land_quat_ |
◆ quat_spline_
◆ spline_
const exact_cubic_t* spline::helpers::effector_spline_rotation::spline_ |
◆ time_land_offset_
const double spline::helpers::effector_spline_rotation::time_land_offset_ |
◆ time_lift_offset_
const double spline::helpers::effector_spline_rotation::time_lift_offset_ |
◆ to_quat_
const Eigen::Quaterniond spline::helpers::effector_spline_rotation::to_quat_ |
The documentation for this class was generated from the following file: