1 #ifndef MODERN_ROBOTICS__TRAJECTORY_GENERATION_HPP___
2 #define MODERN_ROBOTICS__TRAJECTORY_GENERATION_HPP___
50 const arma::vec & thetastart,
51 const arma::vec & thetaend,
72 const arma::mat44 & Xstart,
73 const arma::mat44 & Xend,
96 const arma::mat44 & Xstart,
97 const arma::mat44 & Xend,
const std::vector< arma::vec > 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.
Definition: trajectory_generation.cpp:36
const std::vector< arma::mat44 > 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 s...
Definition: trajectory_generation.cpp:61
double QuinticTimeScaling(const double Tf, const double t)
Computes s(t) for a quintic time scaling.
Definition: trajectory_generation.cpp:17
double CubicTimeScaling(const double Tf, const double t)
Computes s(t) for a cubic time scaling.
Definition: trajectory_generation.cpp:6
const std::vector< arma::mat44 > 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 f...
Definition: trajectory_generation.cpp:89
Definition: dynamics_of_open_chains.hpp:7
Method
Trajectory generation method.
Definition: trajectory_generation.hpp:13
@ Quintic
cubic time scaling using 3rd-order polynomial