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_ 30 #include <stomp_moveit/utils/multivariate_gaussian.h> 35 namespace noise_generators
52 virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
60 const moveit_msgs::MotionPlanRequest &req,
62 moveit_msgs::MoveItErrorCodes& error_code)
override;
76 std::size_t start_timestep,
77 std::size_t num_timesteps,
80 Eigen::MatrixXd& parameters_noise,
81 Eigen::MatrixXd& noise)
override;
91 virtual void done(
bool success,
int total_iterations,
double final_cost,
const Eigen::MatrixXd& parameters){}
94 virtual std::string getName()
const 96 return name_ +
"/" + group_;
100 virtual std::string getGroupName()
const 112 std::vector<utils::MultivariateGaussianPtr> rand_generators_;
113 Eigen::VectorXd raw_noise_;
114 std::vector<double> stddev_;
This is the base class for all stomp noisy generators.
virtual void done(bool success, int total_iterations, double final_cost, const Eigen::MatrixXd ¶meters)
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 ¶meters, std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::MatrixXd ¶meters_noise, Eigen::MatrixXd &noise) override
Generates a noisy trajectory from the parameters.