modern_robotics
Functions
Chapter 9. Trajectory Generation

Functions

double mr::CubicTimeScaling (const double Tf, const double t)
 Computes s(t) for a cubic time scaling. More...
 
double mr::QuinticTimeScaling (const double Tf, const double t)
 Computes s(t) for a quintic time scaling. More...
 
const std::vector< arma::vec > mr::JointTrajectory (const arma::vec &thetastart, const arma::vec &thetaend, const double Tf, const size_t N, const Method &method)
 Computes a straight-line trajectory in joint space. More...
 
const std::vector< arma::mat44 > mr::ScrewTrajectory (const arma::mat44 &Xstart, const arma::mat44 &Xend, const double Tf, const size_t N, const Method &method)
 Computes a trajectory as a list of N SE(3) matrices corresponding to the screw motion about a space screw axis. More...
 
const std::vector< arma::mat44 > mr::CartesianTrajectory (const arma::mat44 &Xstart, const arma::mat44 &Xend, const double Tf, const size_t N, const Method &method)
 Computes a trajectory as a list of N SE(3) matrices corresponding to the origin of the end-effector frame following a straight line. More...
 

Detailed Description

Function Documentation

◆ CartesianTrajectory()

const std::vector< arma::mat44 > mr::CartesianTrajectory ( const arma::mat44 &  Xstart,
const arma::mat44 &  Xend,
const double  Tf,
const size_t  N,
const Method method 
)

Computes a trajectory as a list of N SE(3) matrices corresponding to the origin of the end-effector frame following a straight line.

Parameters
XstartThe initial end-effector configuration
XendThe final end-effector configuration
TfTotal time of the motion in seconds from rest to rest
NThe number of points N > 1 (Start and stop) in the discrete representation of the trajectory
methodThe time-scaling method, where 3 indicates cubic (third- order polynomial) time scaling and 5 indicates quintic (fifth-order polynomial) time scaling
Returns
The discretized trajectory as a list of N matrices in SE(3) separated in time by Tf/(N-1). The first in the list is Xstart and the Nth is Xend

This function is similar to ScrewTrajectory, except the origin of the end-effector frame follows a straight line, decoupled from the rotational motion.

◆ CubicTimeScaling()

double mr::CubicTimeScaling ( const double  Tf,
const double  t 
)

Computes s(t) for a cubic time scaling.

Parameters
TfTotal time of the motion in seconds from rest to rest
tThe current time t satisfying 0 < t < Tf
Returns
The path parameter s(t) corresponding to a third-order polynomial motion that begins and ends at zero velocity

◆ JointTrajectory()

const std::vector< arma::vec > mr::JointTrajectory ( const arma::vec &  thetastart,
const arma::vec &  thetaend,
const double  Tf,
const size_t  N,
const Method method 
)

Computes a straight-line trajectory in joint space.

Parameters
thetastartThe initial joint variables
thetaendThe final joint variables
TfTotal time of the motion in seconds from rest to rest
NThe number of points N > 1 (Start and stop) in the discrete representation of the trajectory
methodThe time-scaling method, where 3 indicates cubic (third- order polynomial) time scaling and 5 indicates quintic (fifth-order polynomial) time scaling
Returns
A trajectory as an N x n matrix, where each row is an n-vector of joint variables at an instant in time. The first row is thetastart and the Nth row is thetaend . The elapsed time between each row is Tf / (N - 1)

◆ QuinticTimeScaling()

double mr::QuinticTimeScaling ( const double  Tf,
const double  t 
)

Computes s(t) for a quintic time scaling.

Parameters
TfTotal time of the motion in seconds from rest to rest
tThe current time t satisfying 0 < t < Tf
Returns
The path parameter s(t) corresponding to a fifth-order polynomial motion that begins and ends at zero velocity and zero acceleration

◆ ScrewTrajectory()

const std::vector< arma::mat44 > mr::ScrewTrajectory ( const arma::mat44 &  Xstart,
const arma::mat44 &  Xend,
const double  Tf,
const size_t  N,
const Method method 
)

Computes a trajectory as a list of N SE(3) matrices corresponding to the screw motion about a space screw axis.

Parameters
XstartThe initial end-effector configuration
XendThe final end-effector configuration
TfTotal time of the motion in seconds from rest to rest
NThe number of points N > 1 (Start and stop) in the discrete representation of the trajectory
methodThe time-scaling method, where 3 indicates cubic (third- order polynomial) time scaling and 5 indicates quintic (fifth-order polynomial) time scaling
Returns
The discretized trajectory as a list of N matrices in SE(3) separated in time by Tf/(N-1). The first in the list is Xstart and the Nth is Xend