Public Member Functions | List of all members
stomp_moveit::noisy_filters::StompNoisyFilter Class Referenceabstract

Interface class for filtering noisy trajectories. More...

#include <stomp_noisy_filter.h>

Inheritance diagram for stomp_moveit::noisy_filters::StompNoisyFilter:
Inheritance graph
[legend]

Public Member Functions

virtual bool configure (const XmlRpc::XmlRpcValue &config)=0
 Sets internal members of the plugin from the configuration data. More...
 
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. More...
 
virtual bool filter (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::MatrixXd &parameters, bool &filtered)=0
 Applies a filtering method to the parameters which may modify the original values. 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)=0
 Initializes and configures. More...
 
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. More...
 
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. More...
 

Detailed Description

Interface class for filtering noisy trajectories.

Examples:
All examples are located here STOMP MoveIt! examples

Definition at line 54 of file stomp_noisy_filter.h.

Member Function Documentation

virtual bool stomp_moveit::noisy_filters::StompNoisyFilter::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::noisy_filters::MultiTrajectoryVisualization, and stomp_moveit::noisy_filters::JointLimits.

virtual void stomp_moveit::noisy_filters::StompNoisyFilter::done ( bool  success,
int  total_iterations,
double  final_cost,
const Eigen::MatrixXd &  parameters 
)
inlinevirtual

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]

Definition at line 127 of file stomp_noisy_filter.h.

virtual bool stomp_moveit::noisy_filters::StompNoisyFilter::filter ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
int  rollout_number,
Eigen::MatrixXd &  parameters,
bool &  filtered 
)
pure virtual

Applies a filtering method to the parameters which may modify the original 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.
rollout_numberIndex of the noisy trajectory whose cost is being evaluated.
parametersOutput argument containing the parameters to be filtered [num_dimensions x num_timesteps].
filteredOutput argument that's set to 'true' if the parameters were changed according to the filtering method.
Returns
false if there was an irrecoverable failure, true otherwise.

Implemented in stomp_moveit::noisy_filters::JointLimits, and stomp_moveit::noisy_filters::MultiTrajectoryVisualization.

virtual bool stomp_moveit::noisy_filters::StompNoisyFilter::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::noisy_filters::MultiTrajectoryVisualization, and stomp_moveit::noisy_filters::JointLimits.

virtual void stomp_moveit::noisy_filters::StompNoisyFilter::postIteration ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
double  cost,
const Eigen::MatrixXd &  parameters 
)
inlinevirtual

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 116 of file stomp_noisy_filter.h.

virtual bool stomp_moveit::noisy_filters::StompNoisyFilter::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::noisy_filters::MultiTrajectoryVisualization, and stomp_moveit::noisy_filters::JointLimits.


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


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Fri May 8 2020 03:35:47