stomp_planner_manager.h
Go to the documentation of this file.
1 
26 #ifndef STOMP_MOVEIT_STOMP_PLANNER_MANAGER_H_
27 #define STOMP_MOVEIT_STOMP_PLANNER_MANAGER_H_
28 
30 #include <ros/node_handle.h>
31 
32 namespace stomp_moveit
33 {
43 {
44 public:
49 
50  virtual ~StompPlannerManager();
51 
58  bool initialize(const robot_model::RobotModelConstPtr& model, const std::string &ns) override;
59 
65  bool canServiceRequest(const moveit_msgs::MotionPlanRequest &req) const override;
66 
71  std::string getDescription() const override
72  {
73  return "Stomp Planner";
74  }
75 
80  void getPlanningAlgorithms(std::vector<std::string> &algs) const override;
81 
87 
95  planning_interface::PlanningContextPtr getPlanningContext(
96  const planning_scene::PlanningSceneConstPtr &planning_scene,
98  moveit_msgs::MoveItErrorCodes &error_code) const override;
99 
100 
101 protected:
102  ros::NodeHandle nh_;
103 
104 
105  std::map< std::string, planning_interface::PlanningContextPtr> planners_;
107  // the robot model
108  moveit::core::RobotModelConstPtr robot_model_;
109 };
110 
111 } /* namespace stomp_moveit */
112 
113 #endif /* STOMP_MOVEIT_STOMP_PLANNER_MANAGER_H_ */
bool initialize(const robot_model::RobotModelConstPtr &model, const std::string &ns) override
Loads the ros parameters for each planning group and initializes the all the planners.
std::map< std::string, planning_interface::PlanningContextPtr > planners_
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code) const override
Provides a planning context that matches the desired plan requests specifications.
std::string getDescription() const override
Description string getter.
The PlannerManager implementation that loads STOMP into moveit.
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pcs) override
Not applicable.
void getPlanningAlgorithms(std::vector< std::string > &algs) const override
Getter for a list of the available planners, usually one STOMP planner per planning group...
bool canServiceRequest(const moveit_msgs::MotionPlanRequest &req) const override
Checks if the request can be planned for.
moveit_msgs::MotionPlanRequest MotionPlanRequest


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