control_cost_projection.h
Go to the documentation of this file.
1 
28 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_CONTROL_COST_PROJECTION_H_
29 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_CONTROL_COST_PROJECTION_H_
30 
32 #include <Eigen/Core>
33 
34 namespace stomp_moveit
35 {
36 namespace update_filters
37 {
38 
49 {
50 public:
52  virtual ~ControlCostProjection();
53 
55  virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
56  const std::string& group_name,const XmlRpc::XmlRpcValue& config) override;
57 
59  virtual bool configure(const XmlRpc::XmlRpcValue& config) override;
60 
62  virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
63  const moveit_msgs::MotionPlanRequest &req,
64  const stomp_core::StompConfiguration &config,
65  moveit_msgs::MoveItErrorCodes& error_code) override;
66 
78  virtual bool filter(std::size_t start_timestep,
79  std::size_t num_timesteps,
80  int iteration_number,
81  const Eigen::MatrixXd& parameters,
82  Eigen::MatrixXd& updates,
83  bool& filtered) override;
84 
85  virtual std::string getGroupName() const
86  {
87  return group_name_;
88  }
89 
90  virtual std::string getName() const
91  {
92  return name_ + "/" + group_name_;
93  }
94 
95 protected:
96 
97  // local
98  std::string name_;
99 
100  // robot properties
101  moveit::core::RobotModelConstPtr robot_model_;
102  std::string group_name_;
103 
104  // smoothing matrix
105  int num_timesteps_;
106  Eigen::MatrixXd projection_matrix_M_;
107 
108 };
109 
110 } /* namespace smoothers */
111 } /* namespace stomp_moveit */
112 
113 #endif /* INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_CONTROL_COST_PROJECTION_H_ */
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
virtual bool configure(const XmlRpc::XmlRpcValue &config) 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
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. Uses the Control Cost Matrix projection.


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