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_ 36 namespace update_filters
55 virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
63 const moveit_msgs::MotionPlanRequest &req,
65 moveit_msgs::MoveItErrorCodes& error_code)
override;
78 virtual bool filter(std::size_t start_timestep,
79 std::size_t num_timesteps,
81 const Eigen::MatrixXd& parameters,
82 Eigen::MatrixXd& updates,
83 bool& filtered)
override;
85 virtual std::string getGroupName()
const 90 virtual std::string getName()
const 92 return name_ +
"/" + group_name_;
101 moveit::core::RobotModelConstPtr robot_model_;
102 std::string group_name_;
106 Eigen::MatrixXd projection_matrix_M_;
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 ¶meters, Eigen::MatrixXd &updates, bool &filtered) override
smoothes the updates array. Uses the Control Cost Matrix projection.