TODO. More...
Go to the source code of this file.
Classes | |
struct | stomp_moveit::utils::polynomial::PolyFitRequest |
The Polynomial Fit request data. More... | |
struct | stomp_moveit::utils::polynomial::PolyFitResults |
The Polynomial Fit results data. More... | |
Namespaces | |
stomp_moveit | |
Functions | |
bool | stomp_moveit::utils::polynomial::applyPolynomialSmoothing (moveit::core::RobotModelConstPtr robot_model, const std::string &group_name, Eigen::MatrixXd ¶meters, int poly_order=5, double joint_limit_margin=1e-5) |
Applies a polynomial smoothing method to a trajectory. It checks for joint limits and makes corrections when these are exceeded as a result of the smoothing process. More... | |
void | stomp_moveit::utils::polynomial::fillVandermondeMatrix (const Eigen::ArrayXd &domain_vals, const int &order, Eigen::MatrixXd &v) |
Generates a Vandermonde matrix from the domain values as described here https://en.wikipedia.org/wiki/Vandermonde_matrix. It uses the poly_order parameter in order to set the size of the matrix. More... | |
void | stomp_moveit::utils::polynomial::generateMinimumDomainValues (const std::vector< const moveit::core::JointModel * > joint_models, const Eigen::MatrixXd ¶meters, Eigen::VectorXd &domain_values) |
Get the polynomial smoother domain values. More... | |
PolyFitResults | stomp_moveit::utils::polynomial::polyFit (const PolyFitRequest &request) |
Fit a polynomial with fixed indices. More... | |
TODO.
Definition in file polynomial.h.
bool stomp_moveit::utils::polynomial::applyPolynomialSmoothing | ( | moveit::core::RobotModelConstPtr | robot_model, |
const std::string & | group_name, | ||
Eigen::MatrixXd & | parameters, | ||
int | poly_order = 5 , |
||
double | joint_limit_margin = 1e-5 |
||
) |
Applies a polynomial smoothing method to a trajectory. It checks for joint limits and makes corrections when these are exceeded as a result of the smoothing process.
robot_model | |
group_name | |
parameters | |
poly_order | |
joint_limit_margin |
Definition at line 187 of file polynomial.cpp.
void stomp_moveit::utils::polynomial::fillVandermondeMatrix | ( | const Eigen::ArrayXd & | domain_vals, |
const int & | order, | ||
Eigen::MatrixXd & | v | ||
) |
Generates a Vandermonde matrix from the domain values as described here https://en.wikipedia.org/wiki/Vandermonde_matrix. It uses the poly_order parameter in order to set the size of the matrix.
domain_vals | The domain values |
order | The order of the polynomial |
v | The output matrix |
Definition at line 149 of file polynomial.cpp.
void stomp_moveit::utils::polynomial::generateMinimumDomainValues | ( | const std::vector< const moveit::core::JointModel * > | joint_models, |
const Eigen::MatrixXd & | parameters, | ||
Eigen::VectorXd & | domain_values | ||
) |
Get the polynomial smoother domain values.
The domain values is time. The time is calculated finding the joint that takes the longest given the total distance traveled and its max velocity. This is the dominating joint therefore its time is used as the domain values for the smoothing operation.
joint_models | List of active joint models |
parameters | The parameters generated in the previous iteration [num_dimensions x num_timesteps] |
domain_values | The time domain values for the trajectory [num_timesteps] |
Definition at line 156 of file polynomial.cpp.
PolyFitResults stomp_moveit::utils::polynomial::polyFit | ( | const PolyFitRequest & | request | ) |
Fit a polynomial with fixed indices.
request | The polynimal fit request data |
Definition at line 49 of file polynomial.cpp.