Loading...
Searching...
No Matches
ndcurves::helpers::effector_spline_rotation Class Reference

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 <ndcurves/helpers/effector_spline_rotation.h>

Collaboration diagram for ndcurves::helpers::effector_spline_rotation:

Public Member Functions

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:
 
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:
 
virtual ~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.
 
quat_t interpolate_quat (const Numeric t) const
 

Public Attributes

const exact_cubic_tspline_
 
const Eigen::Quaterniond to_quat_
 
const Eigen::Quaterniond land_quat_
 
const double time_lift_offset_
 
const double time_land_offset_
 
const exact_cubic_quat_t quat_spline_
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ effector_spline_rotation() [1/2]

template<typename In >
ndcurves::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 last element 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 >
ndcurves::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 last element 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 last element 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()

virtual ndcurves::helpers::effector_spline_rotation::~effector_spline_rotation ( )
inlinevirtual

Member Function Documentation

◆ interpolate_quat()

quat_t ndcurves::helpers::effector_spline_rotation::interpolate_quat ( const Numeric  t) const
inline

◆ max()

Numeric ndcurves::helpers::effector_spline_rotation::max ( ) const
inline

◆ min()

Numeric ndcurves::helpers::effector_spline_rotation::min ( ) const
inline

◆ operator()()

config_t ndcurves::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.
Returns
A 7D vector where the 3 first values are the 3D position and the 4 last are the quaternion describing the rotation.

Member Data Documentation

◆ land_quat_

const Eigen::Quaterniond ndcurves::helpers::effector_spline_rotation::land_quat_

◆ quat_spline_

const exact_cubic_quat_t ndcurves::helpers::effector_spline_rotation::quat_spline_

◆ spline_

const exact_cubic_t* ndcurves::helpers::effector_spline_rotation::spline_

◆ time_land_offset_

const double ndcurves::helpers::effector_spline_rotation::time_land_offset_

◆ time_lift_offset_

const double ndcurves::helpers::effector_spline_rotation::time_lift_offset_

◆ to_quat_

const Eigen::Quaterniond ndcurves::helpers::effector_spline_rotation::to_quat_

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