#include <trajectory_interface/quintic_spline_segment.h>
#include <trajectory_interface/pos_vel_acc_state.h>
#include <cartesian_trajectory_interpolation/cartesian_state.h>
Go to the source code of this file.
Classes | |
class | ros_controllers_cartesian::CartesianTrajectorySegment |
Cartesian segment between two trajectory waypoints. More... | |
Namespaces | |
ros_controllers_cartesian | |
Typedefs | |
using | ros_controllers_cartesian::QuinticSplineSegment = trajectory_interface::QuinticSplineSegment< double > |
7-dimensional quintic spline segment More... | |
Functions | |
CartesianTrajectorySegment::SplineState | ros_controllers_cartesian::convert (const CartesianState &state) |
Convert a CartesianState into a ros_controllers_cartesian::SplineState. More... | |
CartesianState | ros_controllers_cartesian::convert (const CartesianTrajectorySegment::SplineState &state) |
Convert a ros_controllers_cartesian::SplineState into a CartesianState. More... | |
std::ostream & | ros_controllers_cartesian::operator<< (std::ostream &os, const CartesianTrajectorySegment::SplineState &state) |
Stream operator for testing and debugging. More... | |
Definition in file cartesian_trajectory_segment.h.