modern_robotics
|
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... | |
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.
Xstart | The initial end-effector configuration |
Xend | The final end-effector configuration |
Tf | Total time of the motion in seconds from rest to rest |
N | The number of points N > 1 (Start and stop) in the discrete representation of the trajectory |
method | The time-scaling method, where 3 indicates cubic (third- order polynomial) time scaling and 5 indicates quintic (fifth-order polynomial) time scaling |
This function is similar to ScrewTrajectory, except the origin of the end-effector frame follows a straight line, decoupled from the rotational motion.
double mr::CubicTimeScaling | ( | const double | Tf, |
const double | t | ||
) |
Computes s(t) for a cubic time scaling.
Tf | Total time of the motion in seconds from rest to rest |
t | The current time t satisfying 0 < t < Tf |
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.
thetastart | The initial joint variables |
thetaend | The final joint variables |
Tf | Total time of the motion in seconds from rest to rest |
N | The number of points N > 1 (Start and stop) in the discrete representation of the trajectory |
method | The time-scaling method, where 3 indicates cubic (third- order polynomial) time scaling and 5 indicates quintic (fifth-order polynomial) time scaling |
double mr::QuinticTimeScaling | ( | const double | Tf, |
const double | t | ||
) |
Computes s(t) for a quintic time scaling.
Tf | Total time of the motion in seconds from rest to rest |
t | The current time t satisfying 0 < t < Tf |
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.
Xstart | The initial end-effector configuration |
Xend | The final end-effector configuration |
Tf | Total time of the motion in seconds from rest to rest |
N | The number of points N > 1 (Start and stop) in the discrete representation of the trajectory |
method | The time-scaling method, where 3 indicates cubic (third- order polynomial) time scaling and 5 indicates quintic (fifth-order polynomial) time scaling |