Public Member Functions | Protected Attributes | List of all members
stomp_moveit::noise_generators::NormalDistributionSampling Class Reference

Uses a normal distribution to apply noise onto the trajectory. More...

#include <normal_distribution_sampling.h>

Inheritance diagram for stomp_moveit::noise_generators::NormalDistributionSampling:
Inheritance graph
[legend]

Public Member Functions

virtual bool configure (const XmlRpc::XmlRpcValue &config) override
 see base class for documentation
 
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 generateNoise (const Eigen::MatrixXd &parameters, std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::MatrixXd &parameters_noise, Eigen::MatrixXd &noise) override
 Generates a noisy trajectory from the parameters. 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
 
- Public Member Functions inherited from stomp_moveit::noise_generators::StompNoiseGenerator
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...
 

Protected Attributes

std::string group_
 
std::string name_
 
std::vector< utils::MultivariateGaussianPtr > rand_generators_
 
Eigen::VectorXd raw_noise_
 
std::vector< double > stddev_
 

Detailed Description

Uses a normal distribution to apply noise onto the trajectory.

Examples:
All examples are located here STOMP MoveIt! examples

Definition at line 45 of file normal_distribution_sampling.h.

Member Function Documentation

virtual void stomp_moveit::noise_generators::NormalDistributionSampling::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]

Reimplemented from stomp_moveit::noise_generators::StompNoiseGenerator.

Definition at line 91 of file normal_distribution_sampling.h.

bool stomp_moveit::noise_generators::NormalDistributionSampling::generateNoise ( const Eigen::MatrixXd &  parameters,
std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
int  rollout_number,
Eigen::MatrixXd &  parameters_noise,
Eigen::MatrixXd &  noise 
)
overridevirtual

Generates a noisy trajectory from the parameters.

Parameters
parametersThe current value of the optimized parameters to add noise to [num_dimensions x num_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.
parameters_noisethe parameters + noise
noisethe noise applied to the parameters
Returns
true if cost were properly computed

Implements stomp_moveit::noise_generators::StompNoiseGenerator.

Definition at line 152 of file normal_distribution_sampling.cpp.


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


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