Public Member Functions | Private Attributes | List of all members
pilz::CommandPlanner Class Reference

Moveit Plugin for Planning with Standart Robot Commands This planner is dedicated to return a instance of PlanningContext that corresponds to the requested motion command set as planner_id in the MotionPlanRequest). It can be easily extended with additional commands by creating a class inherting from PlanningContextLoader. More...

#include <pilz_command_planner.h>

Inheritance diagram for pilz::CommandPlanner:
Inheritance graph
[legend]

Public Member Functions

virtual bool canServiceRequest (const planning_interface::MotionPlanRequest &req) const override
 Checks if the request can be handled. More...
 
virtual std::string getDescription () const override
 Description of the planner. More...
 
virtual void getPlanningAlgorithms (std::vector< std::string > &algs) const override
 Returns the available planning commands. More...
 
virtual planning_interface::PlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code) const override
 Returns a PlanningContext that can be used to solve(calculate) the trajectory that corresponds to command given in motion request as planner_id. More...
 
virtual bool initialize (const robot_model::RobotModelConstPtr &model, const std::string &ns) override
 Initializes the planner Upon initialization this planner will look for plugins implementing pilz::PlanningContextLoader. More...
 
void registerContextLoader (const pilz::PlanningContextLoaderPtr &planning_context_loader)
 Register a PlanningContextLoader to be used by the CommandPlanner. More...
 
virtual ~CommandPlanner ()
 
- Public Member Functions inherited from planning_interface::PlannerManager
const PlannerConfigurationMapgetPlannerConfigurations () const
 
PlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req) const
 
 PlannerManager ()
 
virtual void setPlannerConfigurations (const PlannerConfigurationMap &pcs)
 
void terminate () const
 
virtual ~PlannerManager ()
 

Private Attributes

pilz::JointLimitsContainer aggregated_limit_active_joints_
 aggregated limits of the active joints More...
 
pilz::CartesianLimit cartesian_limit_
 cartesian limit More...
 
std::map< std::string, pilz::PlanningContextLoaderPtrcontext_loader_map_
 Mapping from command to loader. More...
 
moveit::core::RobotModelConstPtr model_
 Robot model obtained at initialize. More...
 
std::string namespace_
 Namespace where the parameters are stored, obtained at initialize. More...
 
boost::scoped_ptr< pluginlib::ClassLoader< PlanningContextLoader > > planner_context_loader
 Plugin loader. More...
 

Additional Inherited Members

- Protected Attributes inherited from planning_interface::PlannerManager
PlannerConfigurationMap config_settings_
 

Detailed Description

Moveit Plugin for Planning with Standart Robot Commands This planner is dedicated to return a instance of PlanningContext that corresponds to the requested motion command set as planner_id in the MotionPlanRequest). It can be easily extended with additional commands by creating a class inherting from PlanningContextLoader.

Definition at line 42 of file pilz_command_planner.h.

Constructor & Destructor Documentation

virtual pilz::CommandPlanner::~CommandPlanner ( )
inlinevirtual

Definition at line 45 of file pilz_command_planner.h.

Member Function Documentation

bool pilz::CommandPlanner::canServiceRequest ( const planning_interface::MotionPlanRequest req) const
overridevirtual

Checks if the request can be handled.

Parameters
motionrequest containing the planning_id that corresponds to the motion command
Returns
true if the request can be handled

Implements planning_interface::PlannerManager.

Definition at line 134 of file pilz_command_planner.cpp.

std::string pilz::CommandPlanner::getDescription ( ) const
overridevirtual

Description of the planner.

Reimplemented from planning_interface::PlannerManager.

Definition at line 89 of file pilz_command_planner.cpp.

void pilz::CommandPlanner::getPlanningAlgorithms ( std::vector< std::string > &  algs) const
overridevirtual

Returns the available planning commands.

Parameters
listwith the planning algorithms
Note
behined each command is a pilz::PlanningContextLoader loaded as plugin

Reimplemented from planning_interface::PlannerManager.

Definition at line 94 of file pilz_command_planner.cpp.

planning_interface::PlanningContextPtr pilz::CommandPlanner::getPlanningContext ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
moveit_msgs::MoveItErrorCodes &  error_code 
) const
overridevirtual

Returns a PlanningContext that can be used to solve(calculate) the trajectory that corresponds to command given in motion request as planner_id.

Parameters
planning_scene
req
error_code
Returns

Implements planning_interface::PlannerManager.

Definition at line 104 of file pilz_command_planner.cpp.

bool pilz::CommandPlanner::initialize ( const robot_model::RobotModelConstPtr &  model,
const std::string &  ns 
)
overridevirtual

Initializes the planner Upon initialization this planner will look for plugins implementing pilz::PlanningContextLoader.

Parameters
modelThe robot model
nsThe namespace
Returns
true on success, false otherwise

Reimplemented from planning_interface::PlannerManager.

Definition at line 38 of file pilz_command_planner.cpp.

void pilz::CommandPlanner::registerContextLoader ( const pilz::PlanningContextLoaderPtr planning_context_loader)

Register a PlanningContextLoader to be used by the CommandPlanner.

Parameters
planning_context_loader
Exceptions
ContextLoaderRegistrationExceptionif a loader with the same algorithm name is already registered

Definition at line 139 of file pilz_command_planner.cpp.

Member Data Documentation

pilz::JointLimitsContainer pilz::CommandPlanner::aggregated_limit_active_joints_
private

aggregated limits of the active joints

Definition at line 108 of file pilz_command_planner.h.

pilz::CartesianLimit pilz::CommandPlanner::cartesian_limit_
private

cartesian limit

Definition at line 111 of file pilz_command_planner.h.

std::map<std::string, pilz::PlanningContextLoaderPtr> pilz::CommandPlanner::context_loader_map_
private

Mapping from command to loader.

Definition at line 99 of file pilz_command_planner.h.

moveit::core::RobotModelConstPtr pilz::CommandPlanner::model_
private

Robot model obtained at initialize.

Definition at line 102 of file pilz_command_planner.h.

std::string pilz::CommandPlanner::namespace_
private

Namespace where the parameters are stored, obtained at initialize.

Definition at line 105 of file pilz_command_planner.h.

boost::scoped_ptr<pluginlib::ClassLoader<PlanningContextLoader> > pilz::CommandPlanner::planner_context_loader
private

Plugin loader.

Definition at line 96 of file pilz_command_planner.h.


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


pilz_trajectory_generation
Author(s):
autogenerated on Mon Apr 6 2020 03:17:33