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) |
| using ros_controllers_cartesian::QuinticSplineSegment = typedef trajectory_interface::QuinticSplineSegment<double> |
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.
Definition at line 39 of file cartesian_trajectory_segment.cpp.
| using ros_controllers_cartesian::Time = typedef CartesianTrajectorySegment::Time |
Definition at line 38 of file cartesian_trajectory_segment.cpp.
| 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.
| state | The CartesianState to convert |
Definition at line 67 of file cartesian_trajectory_segment.cpp.
| 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.
| state | The SplineState to convert |
Definition at line 123 of file cartesian_trajectory_segment.cpp.
| std::ostream & ros_controllers_cartesian::operator<< | ( | std::ostream & | os, |
| const CartesianTrajectorySegment::SplineState & | state | ||
| ) |
Stream operator for testing and debugging.
| os | The output stream |
| state | The SplineState |
Definition at line 180 of file cartesian_trajectory_segment.cpp.
| std::ostream& ros_controllers_cartesian::operator<< | ( | std::ostream & | out, |
| const CartesianState & | state | ||
| ) |
| os | The output stream |
| state | The CartesianState |
Definition at line 113 of file cartesian_state.cpp.