|
| | TrajOptPlannerManager () |
| |
| bool | initialize (const moveit::core::RobotModelConstPtr &model, const std::string &ns) override |
| |
| bool | canServiceRequest (const moveit_msgs::MotionPlanRequest &req) const override |
| |
| std::string | getDescription () const override |
| | Get. More...
|
| |
| void | getPlanningAlgorithms (std::vector< std::string > &algs) const override |
| | Get the names of the known planning algorithms (values that can be filled as planner_id in the planning request) More...
|
| |
| planning_interface::PlanningContextPtr | getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code) const override |
| |
| | PlannerManager () |
| |
| virtual | ~PlannerManager () |
| |
| virtual bool | initialize (const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) |
| |
| virtual PlanningContextPtr | getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const =0 |
| | Construct a planning context given the current scene and a planning request. If a problem is encountered, error code is set and empty ptr is returned. The returned motion planner context is clean – the motion planner will start from scratch every time a context is constructed. More...
|
| |
| PlanningContextPtr | getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req) const |
| | Calls the function above but ignores the error_code. More...
|
| |
| virtual bool | canServiceRequest (const MotionPlanRequest &req) const =0 |
| | Determine whether this plugin instance is able to represent this planning request. More...
|
| |
| virtual void | setPlannerConfigurations (const PlannerConfigurationMap &pcs)=0 |
| | Specify the settings to be used for specific algorithms. More...
|
| |
| const PlannerConfigurationMap & | getPlannerConfigurations () const |
| | Get the settings for a specific algorithm. More...
|
| |
| void | terminate () const |
| | Request termination, if a solve() function is currently computing plans. More...
|
| |
Definition at line 49 of file trajopt_planner_manager.cpp.