normal_distribution_sampling.h
Go to the documentation of this file.
00001 
00026 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_NOISE_GENERATORS_NORMAL_DISTRIBUTION_SAMPLING_H_
00027 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_NOISE_GENERATORS_NORMAL_DISTRIBUTION_SAMPLING_H_
00028 
00029 #include <stomp_moveit/noise_generators/stomp_noise_generator.h>
00030 #include <stomp_moveit/utils/multivariate_gaussian.h>
00031 
00032 namespace stomp_moveit
00033 {
00034 
00035 namespace noise_generators
00036 {
00037 
00045 class NormalDistributionSampling: public StompNoiseGenerator
00046 {
00047 public:
00048   NormalDistributionSampling();
00049   virtual ~NormalDistributionSampling();
00050 
00052   virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
00053                           const std::string& group_name,const XmlRpc::XmlRpcValue& config) override;
00054 
00056   virtual bool configure(const XmlRpc::XmlRpcValue& config) override;
00057 
00059   virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
00060                    const moveit_msgs::MotionPlanRequest &req,
00061                    const stomp_core::StompConfiguration &config,
00062                    moveit_msgs::MoveItErrorCodes& error_code) override;
00063 
00075   virtual bool generateNoise(const Eigen::MatrixXd& parameters,
00076                                        std::size_t start_timestep,
00077                                        std::size_t num_timesteps,
00078                                        int iteration_number,
00079                                        int rollout_number,
00080                                        Eigen::MatrixXd& parameters_noise,
00081                                        Eigen::MatrixXd& noise) override;
00082 
00091   virtual void done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters){}
00092 
00093 
00094   virtual std::string getName() const
00095   {
00096     return name_ + "/" + group_;
00097   }
00098 
00099 
00100   virtual std::string getGroupName() const
00101   {
00102     return group_;
00103   }
00104 
00105 protected:
00106 
00107   // names
00108   std::string name_;
00109   std::string group_;
00110 
00111   // random noise generation
00112   std::vector<utils::MultivariateGaussianPtr> rand_generators_;
00113   Eigen::VectorXd raw_noise_;
00114   std::vector<double> stddev_;
00115 
00116 };
00117 
00118 } /* namespace noise_generators */
00119 } /* namespace stomp_moveit */
00120 
00121 #endif /* INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_NOISE_GENERATORS_NORMAL_DISTRIBUTION_SAMPLING_H_ */


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