This is a constrained polynomial trajectory smoother. More...
#include <polynomial_smoother.h>
Public Member Functions | |
virtual bool | configure (const XmlRpc::XmlRpcValue &config) override |
see base class for documentation | |
virtual bool | filter (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, const Eigen::MatrixXd ¶meters, Eigen::MatrixXd &updates, bool &filtered) override |
smoothes the updates array by using a constrained polynomial fit. | |
virtual std::string | getGroupName () const |
virtual std::string | getName () const |
virtual bool | initialize (moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, const XmlRpc::XmlRpcValue &config) override |
see base class for documentation | |
PolynomialSmoother () | |
virtual bool | setMotionPlanRequest (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::MotionPlanRequest &req, const stomp_core::StompConfiguration &config, moveit_msgs::MoveItErrorCodes &error_code) override |
see base class for documentation | |
virtual | ~PolynomialSmoother () |
Protected Attributes | |
std::string | group_name_ |
std::string | name_ |
unsigned int | poly_order_ |
moveit::core::RobotModelConstPtr | robot_model_ |
This is a constrained polynomial trajectory smoother.
It uses the constrained least-squares technique shown below.
|p| - | 2*A*A', C |^-1 * | 2*A*b | |z| - | C', 0 | | d |
Where: p - An array of the polynomial coefficients solved for. z - An array of Lagrange mulitipliers A - Is the Vandermonde matrix of all (constrained and unconstrained) domain values C - Is the Vandermonde matrix of the constrained domain values b - An array of the values to perform the fit on d - An array of the values corresponding to the constrained domain values
Definition at line 59 of file polynomial_smoother.h.
stomp_moveit::update_filters::PolynomialSmoother::PolynomialSmoother | ( | ) |
Definition at line 47 of file polynomial_smoother.cpp.
stomp_moveit::update_filters::PolynomialSmoother::~PolynomialSmoother | ( | ) | [virtual] |
Definition at line 54 of file polynomial_smoother.cpp.
bool stomp_moveit::update_filters::PolynomialSmoother::configure | ( | const XmlRpc::XmlRpcValue & | config | ) | [override, virtual] |
see base class for documentation
Implements stomp_moveit::update_filters::StompUpdateFilter.
Definition at line 68 of file polynomial_smoother.cpp.
bool stomp_moveit::update_filters::PolynomialSmoother::filter | ( | std::size_t | start_timestep, |
std::size_t | num_timesteps, | ||
int | iteration_number, | ||
const Eigen::MatrixXd & | parameters, | ||
Eigen::MatrixXd & | updates, | ||
bool & | filtered | ||
) | [override, virtual] |
smoothes the updates array by using a constrained polynomial fit.
start_timestep | start index into the 'parameters' array, usually 0. |
num_timesteps | number of elements to use from 'parameters' starting from 'start_timestep' |
iteration_number | The current iteration count in the optimization loop |
parameters | The parameters generated in the previous iteration [num_dimensions x num_timesteps] |
updates | The updates to be applied to the parameters [num_dimensions x num_timesteps] |
filtered | set ot 'true' if the updates were modified. |
Implements stomp_moveit::update_filters::StompUpdateFilter.
Definition at line 95 of file polynomial_smoother.cpp.
virtual std::string stomp_moveit::update_filters::PolynomialSmoother::getGroupName | ( | ) | const [inline, virtual] |
Reimplemented from stomp_moveit::update_filters::StompUpdateFilter.
Definition at line 96 of file polynomial_smoother.h.
virtual std::string stomp_moveit::update_filters::PolynomialSmoother::getName | ( | ) | const [inline, virtual] |
Reimplemented from stomp_moveit::update_filters::StompUpdateFilter.
Definition at line 101 of file polynomial_smoother.h.
bool stomp_moveit::update_filters::PolynomialSmoother::initialize | ( | moveit::core::RobotModelConstPtr | robot_model_ptr, |
const std::string & | group_name, | ||
const XmlRpc::XmlRpcValue & | config | ||
) | [override, virtual] |
see base class for documentation
Implements stomp_moveit::update_filters::StompUpdateFilter.
Definition at line 59 of file polynomial_smoother.cpp.
bool stomp_moveit::update_filters::PolynomialSmoother::setMotionPlanRequest | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
const moveit_msgs::MotionPlanRequest & | req, | ||
const stomp_core::StompConfiguration & | config, | ||
moveit_msgs::MoveItErrorCodes & | error_code | ||
) | [override, virtual] |
see base class for documentation
Implements stomp_moveit::update_filters::StompUpdateFilter.
Definition at line 86 of file polynomial_smoother.cpp.
std::string stomp_moveit::update_filters::PolynomialSmoother::group_name_ [protected] |
Definition at line 109 of file polynomial_smoother.h.
std::string stomp_moveit::update_filters::PolynomialSmoother::name_ [protected] |
Definition at line 108 of file polynomial_smoother.h.
unsigned int stomp_moveit::update_filters::PolynomialSmoother::poly_order_ [protected] |
Definition at line 112 of file polynomial_smoother.h.
moveit::core::RobotModelConstPtr stomp_moveit::update_filters::PolynomialSmoother::robot_model_ [protected] |
Definition at line 115 of file polynomial_smoother.h.