Go to the documentation of this file.00001
00026 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_NOISE_GENERATORS_STOMP_NOISE_GENERATOR_H_
00027 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_NOISE_GENERATORS_STOMP_NOISE_GENERATOR_H_
00028
00029 #include <Eigen/Core>
00030 #include <XmlRpc.h>
00031 #include <stomp_core/utils.h>
00032 #include <moveit/robot_model/robot_model.h>
00033 #include <moveit/robot_trajectory/robot_trajectory.h>
00034 #include <moveit/planning_scene/planning_scene.h>
00035 #include <moveit_msgs/MotionPlanRequest.h>
00036
00037 namespace stomp_moveit
00038 {
00039
00040 namespace noise_generators
00041 {
00042
00043 class StompNoiseGenerator;
00044 typedef boost::shared_ptr<StompNoiseGenerator> StompNoiseGeneratorPtr;
00045
00053 class StompNoiseGenerator
00054 {
00055 public:
00056 StompNoiseGenerator(){}
00057 virtual ~StompNoiseGenerator(){}
00058
00066 virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
00067 const std::string& group_name,const XmlRpc::XmlRpcValue& config) = 0;
00068
00074 virtual bool configure(const XmlRpc::XmlRpcValue& config) = 0;
00075
00084 virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
00085 const moveit_msgs::MotionPlanRequest &req,
00086 const stomp_core::StompConfiguration &config,
00087 moveit_msgs::MoveItErrorCodes& error_code) = 0;
00088
00100 virtual bool generateNoise(const Eigen::MatrixXd& parameters,
00101 std::size_t start_timestep,
00102 std::size_t num_timesteps,
00103 int iteration_number,
00104 int rollout_number,
00105 Eigen::MatrixXd& parameters_noise,
00106 Eigen::MatrixXd& noise) = 0;
00107
00116 virtual void postIteration(std::size_t start_timestep,
00117 std::size_t num_timesteps,int iteration_number,double cost,const Eigen::MatrixXd& parameters){}
00118
00127 virtual void done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters){}
00128
00129
00130 virtual std::string getName() const
00131 {
00132 return "Not implemented";
00133 }
00134
00135
00136 virtual std::string getGroupName() const
00137 {
00138 return "Not implemented";
00139 }
00140 };
00141
00142 }
00143 }
00144
00145
00146
00147 #endif