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

This class generates noisy trajectories to an under-constrained cartesian goal pose. More...

#include <goal_guided_multivariate_gaussian.h>

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

Public Member Functions

virtual bool configure (const XmlRpc::XmlRpcValue &config) override
 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 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
 
 GoalGuidedMultivariateGaussian ()
 
virtual bool initialize (moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, const XmlRpc::XmlRpcValue &config) override
 Initializes and configures. 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) override
 Stores the planning details. More...
 
virtual ~GoalGuidedMultivariateGaussian ()
 
- 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)
 

Protected Member Functions

virtual bool generateRandomGoal (const Eigen::VectorXd &reference_joint_pose, Eigen::VectorXd &goal_joint_pose)
 Genereates a random tool pose by apply noise on the redundant axis to a reference tool pose;. More...
 
virtual bool setupGoalConstraints (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::MotionPlanRequest &req, const stomp_core::StompConfiguration &config, moveit_msgs::MoveItErrorCodes &error_code)
 
virtual bool setupNoiseGeneration (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::MotionPlanRequest &req, const stomp_core::StompConfiguration &config, moveit_msgs::MoveItErrorCodes &error_code)
 

Protected Attributes

boost::shared_ptr< RandomGeneratorgoal_rand_generator_
 Random generator for the tool goal pose. More...
 
std::string group_
 
stomp_moveit::utils::kinematics::IKSolverPtr ik_solver_
 
std::string name_
 
Eigen::VectorXd raw_noise_
 The noise vector. More...
 
moveit::core::RobotModelConstPtr robot_model_
 
moveit::core::RobotStatePtr state_
 
std::vector< double > stddev_
 The standard deviations applied to each joint, [num_dimensions x 1. More...
 
Eigen::VectorXd tool_goal_tolerance_
 
std::string tool_link_
 
std::vector< utils::MultivariateGaussianPtr > traj_noise_generators_
 Randomized numerical distribution generators, [6 x 1]. More...
 

Detailed Description

This class generates noisy trajectories to an under-constrained cartesian goal pose.

Examples:
All examples are located here STOMP Plugins Examples

Definition at line 51 of file goal_guided_multivariate_gaussian.h.

Constructor & Destructor Documentation

stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::GoalGuidedMultivariateGaussian ( )

Definition at line 51 of file goal_guided_multivariate_gaussian.cpp.

stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::~GoalGuidedMultivariateGaussian ( )
virtual

Definition at line 58 of file goal_guided_multivariate_gaussian.cpp.

Member Function Documentation

bool stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::configure ( const XmlRpc::XmlRpcValue config)
overridevirtual

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.

Implements stomp_moveit::noise_generators::StompNoiseGenerator.

Definition at line 87 of file goal_guided_multivariate_gaussian.cpp.

virtual void stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::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 114 of file goal_guided_multivariate_gaussian.h.

bool stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::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 [num_dimensions x num_parameters]
start_timestepStart 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
rollout_numberThe index of the noisy trajectory.
parameters_noiseThe parameters + noise
noiseThe noise applied to the parameters
Returns
true if cost were properly computed, false otherwise.

Implements stomp_moveit::noise_generators::StompNoiseGenerator.

Definition at line 247 of file goal_guided_multivariate_gaussian.cpp.

bool stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::generateRandomGoal ( const Eigen::VectorXd &  reference_joint_pose,
Eigen::VectorXd &  goal_joint_pose 
)
protectedvirtual

Genereates a random tool pose by apply noise on the redundant axis to a reference tool pose;.

Parameters
reference_joint_poseJoint position used in computing the reference tool pose with FK
goal_joint_poseThe joint position corresponding to the randomized tool pose
Returns
True if succeded, false otherwise

Definition at line 292 of file goal_guided_multivariate_gaussian.cpp.

virtual std::string stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::getGroupName ( ) const
inlinevirtual

Definition at line 123 of file goal_guided_multivariate_gaussian.h.

virtual std::string stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::getName ( ) const
inlinevirtual

Definition at line 117 of file goal_guided_multivariate_gaussian.h.

bool stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::initialize ( moveit::core::RobotModelConstPtr  robot_model_ptr,
const std::string &  group_name,
const XmlRpc::XmlRpcValue config 
)
overridevirtual

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.

Implements stomp_moveit::noise_generators::StompNoiseGenerator.

Definition at line 63 of file goal_guided_multivariate_gaussian.cpp.

bool stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::setMotionPlanRequest ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const moveit_msgs::MotionPlanRequest req,
const stomp_core::StompConfiguration config,
moveit_msgs::MoveItErrorCodes &  error_code 
)
overridevirtual

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.

Implements stomp_moveit::noise_generators::StompNoiseGenerator.

Definition at line 122 of file goal_guided_multivariate_gaussian.cpp.

bool stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::setupGoalConstraints ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const moveit_msgs::MotionPlanRequest req,
const stomp_core::StompConfiguration config,
moveit_msgs::MoveItErrorCodes &  error_code 
)
protectedvirtual

Definition at line 180 of file goal_guided_multivariate_gaussian.cpp.

bool stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::setupNoiseGeneration ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const moveit_msgs::MotionPlanRequest req,
const stomp_core::StompConfiguration config,
moveit_msgs::MoveItErrorCodes &  error_code 
)
protectedvirtual

Definition at line 133 of file goal_guided_multivariate_gaussian.cpp.

Member Data Documentation

boost::shared_ptr<RandomGenerator> stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::goal_rand_generator_
protected

Random generator for the tool goal pose.

Definition at line 166 of file goal_guided_multivariate_gaussian.h.

std::string stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::group_
protected

Definition at line 152 of file goal_guided_multivariate_gaussian.h.

stomp_moveit::utils::kinematics::IKSolverPtr stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::ik_solver_
protected

Definition at line 171 of file goal_guided_multivariate_gaussian.h.

std::string stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::name_
protected

Definition at line 151 of file goal_guided_multivariate_gaussian.h.

Eigen::VectorXd stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::raw_noise_
protected

The noise vector.

Definition at line 163 of file goal_guided_multivariate_gaussian.h.

moveit::core::RobotModelConstPtr stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::robot_model_
protected

Definition at line 169 of file goal_guided_multivariate_gaussian.h.

moveit::core::RobotStatePtr stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::state_
protected

Definition at line 170 of file goal_guided_multivariate_gaussian.h.

std::vector<double> stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::stddev_
protected

The standard deviations applied to each joint, [num_dimensions x 1.

Definition at line 159 of file goal_guided_multivariate_gaussian.h.

Eigen::VectorXd stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::tool_goal_tolerance_
protected

Definition at line 156 of file goal_guided_multivariate_gaussian.h.

std::string stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::tool_link_
protected

Definition at line 155 of file goal_guided_multivariate_gaussian.h.

std::vector<utils::MultivariateGaussianPtr> stomp_moveit::noise_generators::GoalGuidedMultivariateGaussian::traj_noise_generators_
protected

Randomized numerical distribution generators, [6 x 1].

Definition at line 162 of file goal_guided_multivariate_gaussian.h.


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


stomp_plugins
Author(s): Jorge Nicho
autogenerated on Fri May 8 2020 03:35:53