stomp_noise_generator.h
Go to the documentation of this file.
1 
26 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_NOISE_GENERATORS_STOMP_NOISE_GENERATOR_H_
27 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_NOISE_GENERATORS_STOMP_NOISE_GENERATOR_H_
28 
29 #include <Eigen/Core>
30 #include <XmlRpc.h>
31 #include <stomp_core/utils.h>
35 #include <moveit_msgs/MotionPlanRequest.h>
36 
37 namespace stomp_moveit
38 {
39 
40 namespace noise_generators
41 {
42 
43 class StompNoiseGenerator;
44 typedef std::shared_ptr<StompNoiseGenerator> StompNoiseGeneratorPtr;
45 
54 {
55 public:
57  virtual ~StompNoiseGenerator(){}
58 
66  virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
67  const std::string& group_name,const XmlRpc::XmlRpcValue& config) = 0;
68 
74  virtual bool configure(const XmlRpc::XmlRpcValue& config) = 0;
75 
84  virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
85  const moveit_msgs::MotionPlanRequest &req,
86  const stomp_core::StompConfiguration &config,
87  moveit_msgs::MoveItErrorCodes& error_code) = 0;
88 
100  virtual bool generateNoise(const Eigen::MatrixXd& parameters,
101  std::size_t start_timestep,
102  std::size_t num_timesteps,
103  int iteration_number,
104  int rollout_number,
105  Eigen::MatrixXd& parameters_noise,
106  Eigen::MatrixXd& noise) = 0;
107 
116  virtual void postIteration(std::size_t start_timestep,
117  std::size_t num_timesteps,int iteration_number,double cost,const Eigen::MatrixXd& parameters){}
118 
127  virtual void done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters){}
128 
129 
130  virtual std::string getName() const
131  {
132  return "Not implemented";
133  }
134 
135 
136  virtual std::string getGroupName() const
137  {
138  return "Not implemented";
139  }
140 };
141 
142 } /* namespace noise_generators */
143 } /* namespace stomp_moveit */
144 
145 
146 
147 #endif /* INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_NOISE_GENERATORS_STOMP_NOISE_GENERATOR_H_ */
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.
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)=0
Generates a noisy trajectory from the parameters.
virtual void done(bool success, int total_iterations, double final_cost, const Eigen::MatrixXd &parameters)
Called by the STOMP instance at the end of the optimization process.
virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, const XmlRpc::XmlRpcValue &config)=0
Initializes and configures.
virtual bool configure(const XmlRpc::XmlRpcValue &config)=0
Sets internal members of the plugin from the configuration data.
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.


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