stomp_planner_manager.h
Go to the documentation of this file.
00001 
00026 #ifndef STOMP_MOVEIT_STOMP_PLANNER_MANAGER_H_
00027 #define STOMP_MOVEIT_STOMP_PLANNER_MANAGER_H_
00028 
00029 #include <moveit/planning_interface/planning_interface.h>
00030 #include <ros/node_handle.h>
00031 
00032 namespace stomp_moveit
00033 {
00042 class StompPlannerManager : public planning_interface::PlannerManager
00043 {
00044 public:
00048   StompPlannerManager();
00049 
00050   virtual ~StompPlannerManager();
00051 
00058   bool initialize(const robot_model::RobotModelConstPtr& model, const std::string &ns) override;
00059 
00065   bool canServiceRequest(const moveit_msgs::MotionPlanRequest &req) const override;
00066 
00071   std::string getDescription() const override
00072   {
00073     return "Stomp Planner";
00074   }
00075 
00080   void getPlanningAlgorithms(std::vector<std::string> &algs) const override;
00081 
00086   void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pcs) override;
00087 
00095   planning_interface::PlanningContextPtr getPlanningContext(
00096       const planning_scene::PlanningSceneConstPtr &planning_scene,
00097       const planning_interface::MotionPlanRequest &req,
00098       moveit_msgs::MoveItErrorCodes &error_code) const override;
00099 
00100 
00101 protected:
00102   ros::NodeHandle nh_;
00103 
00104 
00105   std::map< std::string, planning_interface::PlanningContextPtr> planners_; 
00107   // the robot model
00108   moveit::core::RobotModelConstPtr robot_model_;
00109 };
00110 
00111 } /* namespace stomp_moveit */
00112 
00113 #endif /* STOMP_MOVEIT_STOMP_PLANNER_MANAGER_H_ */


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Sat Jun 8 2019 19:24:01