A class for Cartesian trajectory representation and interpolation. More...
#include <cartesian_trajectory.h>
Public Member Functions | |
CartesianTrajectory ()=default | |
CartesianTrajectory (const cartesian_control_msgs::CartesianTrajectory &ros_trajectory) | |
Construct from ROS messages. More... | |
bool | init (const cartesian_control_msgs::CartesianTrajectory &ros_trajectory) |
Initialize from ROS message. More... | |
void | sample (const CartesianTrajectorySegment::Time &time, CartesianState &state) |
Sample a trajectory at a specified time. More... | |
virtual | ~CartesianTrajectory () |
Private Attributes | |
std::vector< CartesianTrajectorySegment > | trajectory_data_ |
A class for Cartesian trajectory representation and interpolation.
It's meant to be used inside ROS controllers to wrap the complexity of trajectory interpolation. Initialize instances of this helper with Cartesian ROS trajectories and sample CartesianState at specific time steps for robot control.
Definition at line 45 of file cartesian_trajectory.h.
|
default |
ros_controllers_cartesian::CartesianTrajectory::CartesianTrajectory | ( | const cartesian_control_msgs::CartesianTrajectory & | ros_trajectory | ) |
Construct from ROS messages.
Calls init() and throws std::invalid_argument if that fails.
ros_trajectory | The Cartesian trajectory composed with ROS message types |
Definition at line 37 of file cartesian_trajectory.cpp.
|
inlinevirtual |
Definition at line 59 of file cartesian_trajectory.h.
bool ros_controllers_cartesian::CartesianTrajectory::init | ( | const cartesian_control_msgs::CartesianTrajectory & | ros_trajectory | ) |
Initialize from ROS message.
ros_trajectory | The Cartesian trajectory composed with ROS message types |
Definition at line 45 of file cartesian_trajectory.cpp.
void ros_controllers_cartesian::CartesianTrajectory::sample | ( | const CartesianTrajectorySegment::Time & | time, |
CartesianState & | state | ||
) |
Sample a trajectory at a specified time.
The trajectory's waypoints are interpolated with splines (two-point polynomials) that are uniquely defined between each two waypoints and that scale with the fields given:
If this trajectory's waypoints have velocity and acceleration setpoints, state also contains the current velocity and acceleration, respectively. A typical application is using the sampled state as reference for robot control.
time | Time at which to sample the trajectory |
state | Cartesian state at time |
Definition at line 32 of file cartesian_trajectory.cpp.
|
private |
Definition at line 94 of file cartesian_trajectory.h.