#include <armadillo>
#include <vector>
Go to the source code of this file.
|
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...
|
|