Public Member Functions | Protected Attributes
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]

List of all members.

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_

Detailed Description

The PlannerManager implementation that loads STOMP into moveit.

Examples:
All examples are located here stomp_core examples

Definition at line 42 of file stomp_planner_manager.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 33 of file stomp_planner_manager.cpp.

Definition at line 40 of file stomp_planner_manager.cpp.


Member Function Documentation

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 [inline, override, virtual]

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 [override, virtual]

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 [override, virtual]

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 
) [override, virtual]

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.

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

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.


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


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