normal_distribution_sampling.h
Go to the documentation of this file.
1 
26 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_NOISE_GENERATORS_NORMAL_DISTRIBUTION_SAMPLING_H_
27 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_NOISE_GENERATORS_NORMAL_DISTRIBUTION_SAMPLING_H_
28 
30 #include <stomp_moveit/utils/multivariate_gaussian.h>
31 
32 namespace stomp_moveit
33 {
34 
35 namespace noise_generators
36 {
37 
46 {
47 public:
49  virtual ~NormalDistributionSampling();
50 
52  virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
53  const std::string& group_name,const XmlRpc::XmlRpcValue& config) override;
54 
56  virtual bool configure(const XmlRpc::XmlRpcValue& config) override;
57 
59  virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
60  const moveit_msgs::MotionPlanRequest &req,
61  const stomp_core::StompConfiguration &config,
62  moveit_msgs::MoveItErrorCodes& error_code) override;
63 
75  virtual bool generateNoise(const Eigen::MatrixXd& parameters,
76  std::size_t start_timestep,
77  std::size_t num_timesteps,
78  int iteration_number,
79  int rollout_number,
80  Eigen::MatrixXd& parameters_noise,
81  Eigen::MatrixXd& noise) override;
82 
91  virtual void done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters){}
92 
93 
94  virtual std::string getName() const
95  {
96  return name_ + "/" + group_;
97  }
98 
99 
100  virtual std::string getGroupName() const
101  {
102  return group_;
103  }
104 
105 protected:
106 
107  // names
108  std::string name_;
109  std::string group_;
110 
111  // random noise generation
112  std::vector<utils::MultivariateGaussianPtr> rand_generators_;
113  Eigen::VectorXd raw_noise_;
114  std::vector<double> stddev_;
115 
116 };
117 
118 } /* namespace noise_generators */
119 } /* namespace stomp_moveit */
120 
121 #endif /* INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_NOISE_GENERATORS_NORMAL_DISTRIBUTION_SAMPLING_H_ */
This is the base class for all stomp noisy generators.
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.
Uses a normal distribution to apply noise onto the trajectory.
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 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 configure(const XmlRpc::XmlRpcValue &config) override
see base class for documentation
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.


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