Classes | Typedefs | Functions
ros_controllers_cartesian Namespace Reference

Classes

struct  CartesianState
 Cartesian state with pose, velocity and acceleration. More...
 
class  CartesianTrajectory
 A class for Cartesian trajectory representation and interpolation. More...
 
class  CartesianTrajectorySegment
 Cartesian segment between two trajectory waypoints. More...
 

Typedefs

using QuinticSplineSegment = trajectory_interface::QuinticSplineSegment< double >
 7-dimensional quintic spline segment More...
 
using SplineState = CartesianTrajectorySegment::SplineState
 
using Time = CartesianTrajectorySegment::Time
 

Functions

CartesianTrajectorySegment::SplineState convert (const CartesianState &state)
 Convert a CartesianState into a ros_controllers_cartesian::SplineState. More...
 
CartesianState convert (const CartesianTrajectorySegment::SplineState &state)
 Convert a ros_controllers_cartesian::SplineState into a CartesianState. More...
 
std::ostream & operator<< (std::ostream &os, const CartesianTrajectorySegment::SplineState &state)
 Stream operator for testing and debugging. More...
 
std::ostream & operator<< (std::ostream &out, const CartesianState &state)
 

Typedef Documentation

◆ QuinticSplineSegment

7-dimensional quintic spline segment

This two-point segment is uniquely defined by its start and end ros_controllers_cartesian::SplineState.

Definition at line 41 of file cartesian_trajectory_segment.h.

◆ SplineState

Definition at line 39 of file cartesian_trajectory_segment.cpp.

◆ Time

Definition at line 38 of file cartesian_trajectory_segment.cpp.

Function Documentation

◆ convert() [1/2]

SplineState ros_controllers_cartesian::convert ( const CartesianState state)

Convert a CartesianState into a ros_controllers_cartesian::SplineState.

The computation of quaternion velocities and accelerations from Cartesian angular velocities and accelerations is based on this blog post and on this article.

Note
SplineState has the velocities and accelerations given in the body-local reference frame that is implicitly defined by state's pose.
By default, all-zero velocities and accelerations are interpreted as intended boundary conditions. If used together with Cartesian trajectory execution, this will yield smooth stops in the trajectory's waypoints (= cubic interpolation with zero velocity/acceleration boundary conditions). If users want linear interpolation, they should mark the velocities/accelerations as unspecified by setting at least one of the field values to NaN, e.g. state.v.x() = std::nan("0");
Parameters
stateThe CartesianState to convert
Returns
The content of state in ros_controllers_cartesian::SplineState notation

Definition at line 67 of file cartesian_trajectory_segment.cpp.

◆ convert() [2/2]

CartesianState ros_controllers_cartesian::convert ( const CartesianTrajectorySegment::SplineState state)

Convert a ros_controllers_cartesian::SplineState into a CartesianState.

The computation of Cartesian angular velocities and accelerations from quaternion velocities and accelerations is based on this blog post. and on this article.

Parameters
stateThe SplineState to convert
Returns
The content of state in CartesianState notation

Definition at line 123 of file cartesian_trajectory_segment.cpp.

◆ operator<<() [1/2]

std::ostream & ros_controllers_cartesian::operator<< ( std::ostream &  os,
const CartesianTrajectorySegment::SplineState state 
)

Stream operator for testing and debugging.

Parameters
osThe output stream
stateThe SplineState
Returns
Reference to the stream for chaining

Definition at line 180 of file cartesian_trajectory_segment.cpp.

◆ operator<<() [2/2]

std::ostream& ros_controllers_cartesian::operator<< ( std::ostream &  out,
const CartesianState state 
)
Parameters
osThe output stream
stateThe CartesianState
Returns
Reference to the stream for chaining

Definition at line 113 of file cartesian_state.cpp.



cartesian_trajectory_interpolation
Author(s):
autogenerated on Tue Oct 15 2024 02:09:14