Public Member Functions | Protected Attributes | List of all members
stomp_moveit::StompPlannerManager Class Reference

The PlannerManager implementation that loads STOMP into moveit. More...

#include <stomp_planner_manager.h>

Inheritance diagram for stomp_moveit::StompPlannerManager:
Inheritance graph
[legend]

Public Member Functions

bool canServiceRequest (const moveit_msgs::MotionPlanRequest &req) const override
 Checks if the request can be planned for. More...
 
std::string getDescription () const override
 Description string getter. More...
 
void getPlanningAlgorithms (std::vector< std::string > &algs) const override
 Getter for a list of the available planners, usually one STOMP planner per planning group. More...
 
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. More...
 
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. More...
 
void setPlannerConfigurations (const planning_interface::PlannerConfigurationMap &pcs) override
 Not applicable. More...
 
 StompPlannerManager ()
 Constructor.
 
- Public Member Functions inherited from planning_interface::PlannerManager
const PlannerConfigurationMapgetPlannerConfigurations () const
 
PlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req) const
 
void terminate () const
 

Protected Attributes

ros::NodeHandle nh_
 
std::map< std::string, planning_interface::PlanningContextPtr > planners_
 
moveit::core::RobotModelConstPtr robot_model_
 
- Protected Attributes inherited from planning_interface::PlannerManager
PlannerConfigurationMap config_settings_
 

Detailed Description

The PlannerManager implementation that loads STOMP into moveit.

Examples:
All examples are located here STOMP MoveIt! examples

Definition at line 42 of file stomp_planner_manager.h.

Member Function Documentation

bool stomp_moveit::StompPlannerManager::canServiceRequest ( const moveit_msgs::MotionPlanRequest req) const
overridevirtual

Checks if the request can be planned for.

Parameters
req
Returns
True if succeeded, False otherwise

Implements planning_interface::PlannerManager.

Definition at line 84 of file stomp_planner_manager.cpp.

std::string stomp_moveit::StompPlannerManager::getDescription ( ) const
inlineoverridevirtual

Description string getter.

Returns
Description string

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
overridevirtual

Getter for a list of the available planners, usually one STOMP planner per planning group.

Parameters
algsList 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
overridevirtual

Provides a planning context that matches the desired plan requests specifications.

Parameters
planning_sceneA pointer to the planning scene
reqThe motion plan request
error_codeError code, will be set to moveit_msgs::MoveItErrorCodes::SUCCESS if it succeeded
Returns
A pointer to the planning context

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 
)
overridevirtual

Loads the ros parameters for each planning group and initializes the all the planners.

Parameters
modelThe robot model
nsThe parameter namespace
Returns
True if succeeded, False otherwise

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)
overridevirtual

Not applicable.

Parameters
pcsthis argument is ignored.

Reimplemented from planning_interface::PlannerManager.

Definition at line 105 of file stomp_planner_manager.cpp.

Member Data Documentation

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.


The documentation for this class was generated from the following files:


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