polynomial_smoother.h
Go to the documentation of this file.
1 
28 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_POLYNOMIAL_SMOOTHER_H_
29 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_POLYNOMIAL_SMOOTHER_H_
30 
32 
33 namespace stomp_moveit
34 {
35 namespace update_filters
36 {
37 
60 {
61 public:
63  virtual ~PolynomialSmoother();
64 
66  virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
67  const std::string& group_name,const XmlRpc::XmlRpcValue& config) override;
68 
70  virtual bool configure(const XmlRpc::XmlRpcValue& config) override;
71 
73  virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
74  const moveit_msgs::MotionPlanRequest &req,
75  const stomp_core::StompConfiguration &config,
76  moveit_msgs::MoveItErrorCodes& error_code) override;
77 
89  virtual bool filter(std::size_t start_timestep,
90  std::size_t num_timesteps,
91  int iteration_number,
92  const Eigen::MatrixXd& parameters,
93  Eigen::MatrixXd& updates,
94  bool& filtered) override;
95 
96  virtual std::string getGroupName() const
97  {
98  return group_name_;
99  }
100 
101  virtual std::string getName() const
102  {
103  return name_ + "/" + group_name_;
104  }
105 
106 protected:
107 
108  std::string name_;
109  std::string group_name_;
110 
111  // parameters
112  unsigned int poly_order_;
113 
114  // robot
115  moveit::core::RobotModelConstPtr robot_model_;
116 };
117 
118 } /* namespace update_filters */
119 } /* namespace stomp_moveit */
120 
121 #endif /* INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_POLYNOMIAL_SMOOTHER_H_ */
virtual bool configure(const XmlRpc::XmlRpcValue &config) override
see base class for documentation
This is a constrained polynomial trajectory smoother.
Interface class which applies filtering methods to the update parameters before it is added onto the ...
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
This is the base class for all stomp update filters.
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) override
smoothes the updates array by using a constrained polynomial fit.
virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr, const std::string &group_name, const XmlRpc::XmlRpcValue &config) override
see base class for documentation


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