modern_robotics
trajectory_generation.hpp
Go to the documentation of this file.
1 #ifndef MODERN_ROBOTICS__TRAJECTORY_GENERATION_HPP___
2 #define MODERN_ROBOTICS__TRAJECTORY_GENERATION_HPP___
3 
4 #include <armadillo>
5 #include <vector>
6 
7 namespace mr
8 {
10 
12 enum class Method : uint8_t
13 {
14  Cubic,
15  Quintic
16 };
17 
24 double CubicTimeScaling(const double Tf, const double t);
25 
33 double QuinticTimeScaling(const double Tf, const double t);
34 
49 const std::vector<arma::vec> JointTrajectory(
50  const arma::vec & thetastart,
51  const arma::vec & thetaend,
52  const double Tf,
53  const size_t N,
54  const Method & method
55 );
56 
71 const std::vector<arma::mat44> ScrewTrajectory(
72  const arma::mat44 & Xstart,
73  const arma::mat44 & Xend,
74  const double Tf,
75  const size_t N,
76  const Method & method
77 );
78 
95 const std::vector<arma::mat44> CartesianTrajectory(
96  const arma::mat44 & Xstart,
97  const arma::mat44 & Xend,
98  const double Tf,
99  const size_t N,
100  const Method & method
101 );
102 }
103 
104 #endif
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