Public Member Functions
stomp_moveit::update_filters::StompUpdateFilter Class Reference

Interface class which applies filtering methods to the update parameters before it is added onto the optimized trajectory. More...

#include <stomp_update_filter.h>

Inheritance diagram for stomp_moveit::update_filters::StompUpdateFilter:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool configure (const XmlRpc::XmlRpcValue &config)=0
 Sets internal members of the plugin from the configuration data.
virtual void done (bool success, int total_iterations, double final_cost, const Eigen::MatrixXd &parameters)
 Called by the Stomp at the end of the optimization process.
virtual bool filter (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, const Eigen::MatrixXd &parameters, Eigen::MatrixXd &updates, bool &filtered)=0
 Filters the parameter updates and may change its values.
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)=0
 Initializes and configures.
virtual void postIteration (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, double cost, const Eigen::MatrixXd &parameters)
 Called by STOMP at the end of each iteration.
virtual bool setMotionPlanRequest (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::MotionPlanRequest &req, const stomp_core::StompConfiguration &config, moveit_msgs::MoveItErrorCodes &error_code)=0
 Stores the planning details.
 StompUpdateFilter ()
virtual ~StompUpdateFilter ()

Detailed Description

Interface class which applies filtering methods to the update parameters before it is added onto the optimized trajectory.

Examples:
All examples are located here stomp_core examples

Definition at line 55 of file stomp_update_filter.h.


Constructor & Destructor Documentation

stomp_moveit::update_filters::StompUpdateFilter::StompUpdateFilter ( ) [inline]

Definition at line 58 of file stomp_update_filter.h.

virtual stomp_moveit::update_filters::StompUpdateFilter::~StompUpdateFilter ( ) [inline, virtual]

Definition at line 59 of file stomp_update_filter.h.


Member Function Documentation

virtual bool stomp_moveit::update_filters::StompUpdateFilter::configure ( const XmlRpc::XmlRpcValue config) [pure virtual]

Sets internal members of the plugin from the configuration data.

Parameters:
configThe configuration data. Usually loaded from the ros parameter server
Returns:
true if succeeded, false otherwise.

Implemented in stomp_moveit::update_filters::PolynomialSmoother, stomp_moveit::update_filters::TrajectoryVisualization, stomp_moveit::update_filters::ControlCostProjection, and stomp_moveit::update_filters::UpdateLogger.

virtual void stomp_moveit::update_filters::StompUpdateFilter::done ( bool  success,
int  total_iterations,
double  final_cost,
const Eigen::MatrixXd &  parameters 
) [inline, virtual]

Called by the Stomp at the end of the optimization process.

Parameters:
successWhether the optimization succeeded
total_iterationsNumber of iterations used
final_costThe cost value after optimizing.
parametersThe parameters generated at the end of current iteration [num_dimensions x num_timesteps]

Reimplemented in stomp_moveit::update_filters::TrajectoryVisualization, and stomp_moveit::update_filters::UpdateLogger.

Definition at line 128 of file stomp_update_filter.h.

virtual bool stomp_moveit::update_filters::StompUpdateFilter::filter ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
const Eigen::MatrixXd &  parameters,
Eigen::MatrixXd &  updates,
bool &  filtered 
) [pure virtual]

Filters the parameter updates and may change its values.

Parameters:
start_timestepstart index into the 'parameters' array, usually 0.
num_timestepsnumber of elements to use from 'parameters' starting from 'start_timestep'
iteration_numberThe current iteration count in the optimization loop
parametersThe parameters generated in the previous iteration [num_dimensions x num_timesteps]
updatesOutput argument which contains the updates to be applied to the parameters [num_dimensions x num_timesteps]
filteredOutput argument which is set to 'true' if the updates were modified.
Returns:
false if there was an irrecoverable failure, true otherwise.

Implemented in stomp_moveit::update_filters::PolynomialSmoother, stomp_moveit::update_filters::TrajectoryVisualization, stomp_moveit::update_filters::ControlCostProjection, and stomp_moveit::update_filters::UpdateLogger.

virtual std::string stomp_moveit::update_filters::StompUpdateFilter::getGroupName ( ) const [inline, virtual]
virtual std::string stomp_moveit::update_filters::StompUpdateFilter::getName ( ) const [inline, virtual]
virtual bool stomp_moveit::update_filters::StompUpdateFilter::initialize ( moveit::core::RobotModelConstPtr  robot_model_ptr,
const std::string &  group_name,
const XmlRpc::XmlRpcValue config 
) [pure virtual]

Initializes and configures.

Parameters:
robot_model_ptrA pointer to the robot model.
group_nameThe designated planning group.
configThe configuration data. Usually loaded from the ros parameter server
Returns:
true if succeeded, false otherwise.

Implemented in stomp_moveit::update_filters::PolynomialSmoother, stomp_moveit::update_filters::TrajectoryVisualization, stomp_moveit::update_filters::ControlCostProjection, and stomp_moveit::update_filters::UpdateLogger.

virtual void stomp_moveit::update_filters::StompUpdateFilter::postIteration ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
double  cost,
const Eigen::MatrixXd &  parameters 
) [inline, virtual]

Called by STOMP at the end of each iteration.

Parameters:
start_timestepThe start index into the 'parameters' array, usually 0.
num_timestepsThe number of elements to use from 'parameters' starting from 'start_timestep'
iteration_numberThe current iteration count in the optimization loop
costThe cost value for the current parameters.
parametersThe value of the parameters at the end of the current iteration [num_dimensions x num_timesteps].

Definition at line 117 of file stomp_update_filter.h.

virtual bool stomp_moveit::update_filters::StompUpdateFilter::setMotionPlanRequest ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const moveit_msgs::MotionPlanRequest req,
const stomp_core::StompConfiguration &  config,
moveit_msgs::MoveItErrorCodes &  error_code 
) [pure virtual]

Stores the planning details.

Parameters:
planning_sceneA smart pointer to the planning scene
reqThe motion planning request
configThe Stomp configuration.
error_codeMoveit error code.
Returns:
true if succeeded, false otherwise.

Implemented in stomp_moveit::update_filters::PolynomialSmoother, stomp_moveit::update_filters::TrajectoryVisualization, stomp_moveit::update_filters::ControlCostProjection, and stomp_moveit::update_filters::UpdateLogger.


The documentation for this class was generated from the following file:


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Sat Jun 8 2019 19:24:01