Public Member Functions | Private Attributes | List of all members
PlannerManagerStub Class Reference
Inheritance diagram for PlannerManagerStub:
Inheritance graph
[legend]

Public Member Functions

bool canServiceRequest (planning_interface::MotionPlanRequest const &) const override
 Determine whether this plugin instance is able to represent this planning request. More...
 
planning_interface::PlanningContextPtr getPlanningContext (planning_scene::PlanningSceneConstPtr const &, planning_interface::MotionPlanRequest const &, moveit_msgs::MoveItErrorCodes &) const override
 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...
 
 PlannerManagerStub (planning_interface::PlanningContextPtr planningContext)
 
- Public Member Functions inherited from planning_interface::PlannerManager
virtual std::string getDescription () const
 Get. More...
 
const PlannerConfigurationMapgetPlannerConfigurations () const
 Get the settings for a specific algorithm. More...
 
virtual void getPlanningAlgorithms (std::vector< std::string > &algs) const
 Get the names of the known planning algorithms (values that can be filled as planner_id in the planning request) 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 initialize (const moveit::core::RobotModelConstPtr &model, const std::string &ns)
 
 PlannerManager ()
 
virtual void setPlannerConfigurations (const PlannerConfigurationMap &pcs)
 Specify the settings to be used for specific algorithms. More...
 
void terminate () const
 Request termination, if a solve() function is currently computing plans. More...
 
virtual ~PlannerManager ()
 

Private Attributes

planning_interface::PlanningContextPtr m_planningContext
 

Additional Inherited Members

- Protected Attributes inherited from planning_interface::PlannerManager
PlannerConfigurationMap config_settings_
 All the existing planning configurations. The name of the configuration is the key of the map. This name can be of the form "group_name[config_name]" if there are particular configurations specified for a group, or of the form "group_name" if default settings are to be used. More...
 

Detailed Description

Definition at line 81 of file test_planning_request_adapter_chain.cpp.

Constructor & Destructor Documentation

◆ PlannerManagerStub()

PlannerManagerStub::PlannerManagerStub ( planning_interface::PlanningContextPtr  planningContext)
inline

Definition at line 84 of file test_planning_request_adapter_chain.cpp.

Member Function Documentation

◆ canServiceRequest()

bool PlannerManagerStub::canServiceRequest ( planning_interface::MotionPlanRequest const &  req) const
inlineoverridevirtual

Determine whether this plugin instance is able to represent this planning request.

Implements planning_interface::PlannerManager.

Definition at line 96 of file test_planning_request_adapter_chain.cpp.

◆ getPlanningContext()

planning_interface::PlanningContextPtr PlannerManagerStub::getPlanningContext ( planning_scene::PlanningSceneConstPtr const &  planning_scene,
planning_interface::MotionPlanRequest const &  req,
moveit_msgs::MoveItErrorCodes &  error_code 
) const
inlineoverridevirtual

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.

Parameters
planning_sceneA const planning scene to use for planning
reqThe representation of the planning request
error_codeThis is where the error is set if constructing the planning context fails

Implements planning_interface::PlannerManager.

Definition at line 89 of file test_planning_request_adapter_chain.cpp.

Member Data Documentation

◆ m_planningContext

planning_interface::PlanningContextPtr PlannerManagerStub::m_planningContext
private

Definition at line 102 of file test_planning_request_adapter_chain.cpp.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Fri May 3 2024 02:28:41