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_ 31 #include <stomp_core/utils.h> 35 #include <moveit_msgs/MotionPlanRequest.h> 40 namespace noise_generators
43 class StompNoiseGenerator;
44 typedef std::shared_ptr<StompNoiseGenerator> StompNoiseGeneratorPtr;
66 virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
85 const moveit_msgs::MotionPlanRequest &req,
87 moveit_msgs::MoveItErrorCodes& error_code) = 0;
100 virtual bool generateNoise(
const Eigen::MatrixXd& parameters,
101 std::size_t start_timestep,
102 std::size_t num_timesteps,
103 int iteration_number,
105 Eigen::MatrixXd& parameters_noise,
106 Eigen::MatrixXd& noise) = 0;
117 std::size_t num_timesteps,
int iteration_number,
double cost,
const Eigen::MatrixXd& parameters){}
127 virtual void done(
bool success,
int total_iterations,
double final_cost,
const Eigen::MatrixXd& parameters){}
130 virtual std::string getName()
const 132 return "Not implemented";
136 virtual std::string getGroupName()
const 138 return "Not implemented";
virtual void postIteration(std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, double cost, const Eigen::MatrixXd ¶meters)
Called by STOMP at the end of each iteration.
virtual bool generateNoise(const Eigen::MatrixXd ¶meters, std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::MatrixXd ¶meters_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 ¶meters)
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.