stomp_update_filter.h
Go to the documentation of this file.
1 
26 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_STOMP_UPDATE_FILTER_H_
27 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_STOMP_UPDATE_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 
38 namespace stomp_moveit
39 {
40 
41 namespace update_filters
42 {
43 
52 class StompUpdateFilter;
53 typedef std::shared_ptr<StompUpdateFilter> StompUpdateFilterPtr;
54 
56 {
57 public:
59  virtual ~StompUpdateFilter(){}
60 
68  virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
69  const std::string& group_name,const XmlRpc::XmlRpcValue& config) = 0;
70 
76  virtual bool configure(const XmlRpc::XmlRpcValue& config) = 0;
77 
86  virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
87  const moveit_msgs::MotionPlanRequest &req,
88  const stomp_core::StompConfiguration &config,
89  moveit_msgs::MoveItErrorCodes& error_code) = 0;
90 
102  virtual bool filter(std::size_t start_timestep,
103  std::size_t num_timesteps,
104  int iteration_number,
105  const Eigen::MatrixXd& parameters,
106  Eigen::MatrixXd& updates,
107  bool& filtered) = 0 ;
108 
117  virtual void postIteration(std::size_t start_timestep,
118  std::size_t num_timesteps,int iteration_number,double cost,const Eigen::MatrixXd& parameters){}
119 
128  virtual void done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters){}
129 
130 
131  virtual std::string getName() const
132  {
133  return "Not implemented";
134  }
135 
136 
137  virtual std::string getGroupName() const
138  {
139  return "Not implemented";
140  }
141 
142 };
143 
144 } /* namespace update_filters */
145 
146 } /* namespace stomp_moveit */
147 
148 
149 
150 #endif /* INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_STOMP_UPDATE_FILTER_H_ */
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 initialize(moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, const XmlRpc::XmlRpcValue &config)=0
Initializes and configures.
Interface class which applies filtering methods to the update parameters before it is added onto the ...
virtual bool configure(const XmlRpc::XmlRpcValue &config)=0
Sets internal members of the plugin from the configuration data.
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 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 filter(std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, const Eigen::MatrixXd &parameters, Eigen::MatrixXd &updates, bool &filtered)=0
Filters the parameter updates and may change its values.


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