Public Types | Public Member Functions | List of all members
ros_controllers_cartesian::CartesianTrajectorySegment Class Reference

Cartesian segment between two trajectory waypoints. More...

#include <cartesian_trajectory_segment.h>

Inheritance diagram for ros_controllers_cartesian::CartesianTrajectorySegment:
Inheritance graph
[legend]

Public Types

using SplineState = QuinticSplineSegment::State
 State of a 7-dimensional Spline. More...
 
using State = CartesianState
 
using Time = QuinticSplineSegment::Time
 Relative time in seconds. More...
 
- Public Types inherited from trajectory_interface::QuinticSplineSegment< class >
typedef ScalarType Scalar
 
typedef PosVelAccState< ScalarState
 
typedef Scalar Time
 

Public Member Functions

 CartesianTrajectorySegment ()=delete
 
 CartesianTrajectorySegment (const Time &start_time, const CartesianState &start_state, const Time &end_time, const CartesianState &end_state)
 Construct a Cartesian trajectory segment from start and end state. More...
 
void sample (const Time &time, CartesianState &state) const
 Sample the CartesianState at the given time. More...
 
virtual ~CartesianTrajectorySegment ()
 
- Public Member Functions inherited from trajectory_interface::QuinticSplineSegment< class >
Time endTime () const
 
void init (const Time &start_time, const State &start_state, const Time &end_time, const State &end_state)
 
 QuinticSplineSegment ()
 
 QuinticSplineSegment (const Time &start_time, const State &start_state, const Time &end_time, const State &end_state)
 
void sample (const Time &time, State &state) const
 
unsigned int size () const
 
Time startTime () const
 
Time timeFromStart () const
 

Detailed Description

Cartesian segment between two trajectory waypoints.

Various of these segments form a Cartesian trajectory.

They use the QuinticSplineSegment implementation from the joint_trajectory_controller package. For each of the seven Cartesian dimensions, they implement linear, cubic or quintic spline interpolation, depending on the waypoints specification by parameterizing unique polynomials between the two waypoints.

This wrapper takes care of converting Cartesian pose, velocity and acceleration setpoints into quaternion quantities for specifying spline boundary conditions (during initialization), and re-converting the interpolated values back into Cartesian quantities that can be commanded to robot control (upon sampling).

Definition at line 63 of file cartesian_trajectory_segment.h.

Member Typedef Documentation

◆ SplineState

State of a 7-dimensional Spline.

The first three dimensions represent Cartesian translation and the last four represent the rotation quaternion (w, x, y, z). Each dimension has its own position, velocity and acceleration value.

Definition at line 81 of file cartesian_trajectory_segment.h.

◆ State

Definition at line 71 of file cartesian_trajectory_segment.h.

◆ Time

Relative time in seconds.

Definition at line 69 of file cartesian_trajectory_segment.h.

Constructor & Destructor Documentation

◆ CartesianTrajectorySegment() [1/2]

ros_controllers_cartesian::CartesianTrajectorySegment::CartesianTrajectorySegment ( )
delete

◆ ~CartesianTrajectorySegment()

virtual ros_controllers_cartesian::CartesianTrajectorySegment::~CartesianTrajectorySegment ( )
inlinevirtual

Definition at line 85 of file cartesian_trajectory_segment.h.

◆ CartesianTrajectorySegment() [2/2]

ros_controllers_cartesian::CartesianTrajectorySegment::CartesianTrajectorySegment ( const Time start_time,
const CartesianState start_state,
const Time end_time,
const CartesianState end_state 
)

Construct a Cartesian trajectory segment from start and end state.

This uses the quintic spline interpolation from the joint_trajectory_controller under the hood. The Cartesian states are converted to spline states to fit into their pipeline. Here is the essential part of the documentation that also applies here:

The start and end states need not necessarily be specified all the way to the acceleration level:

  • If only positions are specified, linear interpolation will be used.
  • If positions and velocities are specified, a cubic spline will be used.
  • If positions, velocities and accelerations are specified, a quintic spline will be used.
Note
If start and end states have different specifications (eg. start is positon-only, end is position-velocity), the lowest common specification will be used (position-only in the example).
Parameters
start_timeTime in seconds when this segment starts
start_stateCartesianState at start time
end_timeTime in seconds when this segment ends
end_stateCartesianState at end time

Definition at line 41 of file cartesian_trajectory_segment.cpp.

Member Function Documentation

◆ sample()

void ros_controllers_cartesian::CartesianTrajectorySegment::sample ( const Time time,
CartesianState state 
) const

Sample the CartesianState at the given time.

Note
Will use QuinticSplineSegment::sample internally with the following characteristics:
Within the [start_time, end_time] interval, spline interpolation takes place, outside it this method will output the start/end states with zero velocity and acceleration.
Parameters
timeThe time at which to sample
stateThe CartesianState at the requested time

Definition at line 45 of file cartesian_trajectory_segment.cpp.


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