The PlannerManager implementation that loads STOMP into moveit. More...
#include <stomp_planner_manager.h>
Public Member Functions | |
bool | canServiceRequest (const moveit_msgs::MotionPlanRequest &req) const override |
Checks if the request can be planned for. | |
std::string | getDescription () const override |
Description string getter. | |
void | getPlanningAlgorithms (std::vector< std::string > &algs) const override |
Getter for a list of the available planners, usually one STOMP planner per planning group. | |
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. | |
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. | |
void | setPlannerConfigurations (const planning_interface::PlannerConfigurationMap &pcs) override |
Not applicable. | |
StompPlannerManager () | |
Constructor. | |
virtual | ~StompPlannerManager () |
Protected Attributes | |
ros::NodeHandle | nh_ |
std::map< std::string, planning_interface::PlanningContextPtr > | planners_ |
moveit::core::RobotModelConstPtr | robot_model_ |
The PlannerManager implementation that loads STOMP into moveit.
Definition at line 42 of file stomp_planner_manager.h.
Constructor.
Definition at line 33 of file stomp_planner_manager.cpp.
stomp_moveit::StompPlannerManager::~StompPlannerManager | ( | ) | [virtual] |
Definition at line 40 of file stomp_planner_manager.cpp.
bool stomp_moveit::StompPlannerManager::canServiceRequest | ( | const moveit_msgs::MotionPlanRequest & | req | ) | const [override, virtual] |
Checks if the request can be planned for.
req |
Implements planning_interface::PlannerManager.
Definition at line 84 of file stomp_planner_manager.cpp.
std::string stomp_moveit::StompPlannerManager::getDescription | ( | ) | const [inline, override, virtual] |
Description string getter.
Reimplemented from planning_interface::PlannerManager.
Definition at line 71 of file stomp_planner_manager.h.
void stomp_moveit::StompPlannerManager::getPlanningAlgorithms | ( | std::vector< std::string > & | algs | ) | const [override, virtual] |
Getter for a list of the available planners, usually one STOMP planner per planning group.
algs | List of available planners. |
Reimplemented from planning_interface::PlannerManager.
Definition at line 96 of file stomp_planner_manager.cpp.
planning_interface::PlanningContextPtr stomp_moveit::StompPlannerManager::getPlanningContext | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
const planning_interface::MotionPlanRequest & | req, | ||
moveit_msgs::MoveItErrorCodes & | error_code | ||
) | const [override, virtual] |
Provides a planning context that matches the desired plan requests specifications.
planning_scene | A pointer to the planning scene |
req | The motion plan request |
error_code | Error code, will be set to moveit_msgs::MoveItErrorCodes::SUCCESS if it succeeded |
Implements planning_interface::PlannerManager.
Definition at line 110 of file stomp_planner_manager.cpp.
bool stomp_moveit::StompPlannerManager::initialize | ( | const robot_model::RobotModelConstPtr & | model, |
const std::string & | ns | ||
) | [override, virtual] |
Loads the ros parameters for each planning group and initializes the all the planners.
model | The robot model |
ns | The parameter namespace |
Reimplemented from planning_interface::PlannerManager.
Definition at line 45 of file stomp_planner_manager.cpp.
void stomp_moveit::StompPlannerManager::setPlannerConfigurations | ( | const planning_interface::PlannerConfigurationMap & | pcs | ) | [override, virtual] |
Not applicable.
pcs | this argument is ignored. |
Reimplemented from planning_interface::PlannerManager.
Definition at line 105 of file stomp_planner_manager.cpp.
Definition at line 102 of file stomp_planner_manager.h.
std::map< std::string, planning_interface::PlanningContextPtr> stomp_moveit::StompPlannerManager::planners_ [protected] |
The planners for each planning group
Definition at line 105 of file stomp_planner_manager.h.
moveit::core::RobotModelConstPtr stomp_moveit::StompPlannerManager::robot_model_ [protected] |
Definition at line 108 of file stomp_planner_manager.h.