|
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. Uses the Control Cost Matrix projection. More...
|
|
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
|
|
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 void | done (bool success, int total_iterations, double final_cost, const Eigen::MatrixXd ¶meters) |
| Called by the Stomp at the end of the optimization process. More...
|
|
virtual void | postIteration (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, double cost, const Eigen::MatrixXd ¶meters) |
| Called by STOMP at the end of each iteration. More...
|
|
|
std::string | group_name_ |
|
std::string | name_ |
|
int | num_timesteps_ |
|
Eigen::MatrixXd | projection_matrix_M_ |
|
moveit::core::RobotModelConstPtr | robot_model_ |
|
Definition at line 48 of file control_cost_projection.h.
bool stomp_moveit::update_filters::ControlCostProjection::filter |
( |
std::size_t |
start_timestep, |
|
|
std::size_t |
num_timesteps, |
|
|
int |
iteration_number, |
|
|
const Eigen::MatrixXd & |
parameters, |
|
|
Eigen::MatrixXd & |
updates, |
|
|
bool & |
filtered |
|
) |
| |
|
overridevirtual |
smoothes the updates array. Uses the Control Cost Matrix projection.
- Parameters
-
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 | Output argument which contains the updates to be applied to the parameters [num_dimensions x num_timesteps] |
filtered | Output argument which is set to 'true' if the updates were modified. |
- Returns
- false if there was an irrecoverable failure, true otherwise.
Implements stomp_moveit::update_filters::StompUpdateFilter.
Definition at line 95 of file control_cost_projection.cpp.
The documentation for this class was generated from the following files: