stomp_noisy_filter.h
Go to the documentation of this file.
1 
26 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_NOISY_FILTER_H_
27 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_NOISY_FILTER_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 noisy_filters
41 {
42 
43 class StompNoisyFilter;
44 typedef std::shared_ptr<StompNoisyFilter> StompNoisyFilterPtr;
45 
46 
55 {
56 public:
58  virtual ~StompNoisyFilter(){}
59 
67  virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
68  const std::string& group_name,const XmlRpc::XmlRpcValue& config) = 0;
69 
75  virtual bool configure(const XmlRpc::XmlRpcValue& config) = 0;
76 
85  virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
86  const moveit_msgs::MotionPlanRequest &req,
87  const stomp_core::StompConfiguration &config,
88  moveit_msgs::MoveItErrorCodes& error_code) = 0;
89 
101  virtual bool filter(std::size_t start_timestep,
102  std::size_t num_timesteps,
103  int iteration_number,
104  int rollout_number,
105  Eigen::MatrixXd& parameters,
106  bool& filtered) = 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 };
143 
144 } /* namespace filters */
145 
146 } /* namespace stomp_moveit */
147 
148 #endif /* INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_NOISY_FILTER_H_ */
virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, const XmlRpc::XmlRpcValue &config)=0
Initializes and configures.
Interface class for filtering noisy trajectories.
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 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.
virtual bool filter(std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::MatrixXd &parameters, bool &filtered)=0
Applies a filtering method to the parameters which may modify the original values.
virtual void done(bool success, int total_iterations, double final_cost, const Eigen::MatrixXd &parameters)
Called by the Stomp at the end of the optimization process.
virtual bool configure(const XmlRpc::XmlRpcValue &config)=0
Sets internal members of the plugin from the configuration data.


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