Go to the documentation of this file.00001
00028 #ifndef INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_CONTROL_COST_PROJECTION_H_
00029 #define INDUSTRIAL_MOVEIT_STOMP_MOVEIT_INCLUDE_STOMP_MOVEIT_UPDATE_FILTERS_CONTROL_COST_PROJECTION_H_
00030
00031 #include <stomp_moveit/update_filters/stomp_update_filter.h>
00032 #include <Eigen/Core>
00033
00034 namespace stomp_moveit
00035 {
00036 namespace update_filters
00037 {
00038
00048 class ControlCostProjection : public StompUpdateFilter
00049 {
00050 public:
00051 ControlCostProjection();
00052 virtual ~ControlCostProjection();
00053
00055 virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
00056 const std::string& group_name,const XmlRpc::XmlRpcValue& config) override;
00057
00059 virtual bool configure(const XmlRpc::XmlRpcValue& config) override;
00060
00062 virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
00063 const moveit_msgs::MotionPlanRequest &req,
00064 const stomp_core::StompConfiguration &config,
00065 moveit_msgs::MoveItErrorCodes& error_code) override;
00066
00078 virtual bool filter(std::size_t start_timestep,
00079 std::size_t num_timesteps,
00080 int iteration_number,
00081 const Eigen::MatrixXd& parameters,
00082 Eigen::MatrixXd& updates,
00083 bool& filtered) override;
00084
00085 virtual std::string getGroupName() const
00086 {
00087 return group_name_;
00088 }
00089
00090 virtual std::string getName() const
00091 {
00092 return name_ + "/" + group_name_;
00093 }
00094
00095 protected:
00096
00097
00098 std::string name_;
00099
00100
00101 moveit::core::RobotModelConstPtr robot_model_;
00102 std::string group_name_;
00103
00104
00105 int num_timesteps_;
00106 Eigen::MatrixXd projection_matrix_M_;
00107
00108 };
00109
00110 }
00111 }
00112
00113 #endif