Go to the documentation of this file.
31 #include <cartesian_control_msgs/CartesianTrajectory.h>
70 bool init(
const cartesian_control_msgs::CartesianTrajectory& ros_trajectory);
bool init(const cartesian_control_msgs::CartesianTrajectory &ros_trajectory)
Initialize from ROS message.
Cartesian state with pose, velocity and acceleration.
A class for Cartesian trajectory representation and interpolation.
void sample(const CartesianTrajectorySegment::Time &time, CartesianState &state)
Sample a trajectory at a specified time.
virtual ~CartesianTrajectory()
std::vector< CartesianTrajectorySegment > trajectory_data_
QuinticSplineSegment::Time Time
Relative time in seconds.
CartesianTrajectory()=default