Public Member Functions | Private Attributes | List of all members
ros_controllers_cartesian::CartesianTrajectory Class Reference

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< CartesianTrajectorySegmenttrajectory_data_
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ CartesianTrajectory() [1/2]

ros_controllers_cartesian::CartesianTrajectory::CartesianTrajectory ( )
default

◆ CartesianTrajectory() [2/2]

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.

Parameters
ros_trajectoryThe Cartesian trajectory composed with ROS message types

Definition at line 37 of file cartesian_trajectory.cpp.

◆ ~CartesianTrajectory()

virtual ros_controllers_cartesian::CartesianTrajectory::~CartesianTrajectory ( )
inlinevirtual

Definition at line 59 of file cartesian_trajectory.h.

Member Function Documentation

◆ init()

bool ros_controllers_cartesian::CartesianTrajectory::init ( const cartesian_control_msgs::CartesianTrajectory &  ros_trajectory)

Initialize from ROS message.

Note
The first waypoint is expected to be the current state with time_from_start == 0.
Parameters
ros_trajectoryThe Cartesian trajectory composed with ROS message types
Returns
True if ros_trajectory has increasing waypoints in time, else false.

Definition at line 45 of file cartesian_trajectory.cpp.

◆ sample()

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:

  • Only pose = linear interpolation
  • Pose and velocity = cubic interpolation
  • Pose, velocity and acceleration = quintic interpolation

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.

Parameters
timeTime at which to sample the trajectory
stateCartesian state at time

Definition at line 32 of file cartesian_trajectory.cpp.

Member Data Documentation

◆ trajectory_data_

std::vector<CartesianTrajectorySegment> ros_controllers_cartesian::CartesianTrajectory::trajectory_data_
private

Definition at line 94 of file cartesian_trajectory.h.


The documentation for this class was generated from the following files:


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