Robowflex  v0.1
Making MoveIt Easy
robowflex::OMPL::FetchOMPLPipelinePlanner Class Reference

Convenience class for the default motion planning pipeline for Fetch. More...

#include <fetch.h>

+ Inheritance diagram for robowflex::OMPL::FetchOMPLPipelinePlanner:

Public Member Functions

 FetchOMPLPipelinePlanner (const RobotPtr &robot, const std::string &name="")
 Constructor. More...
 
bool initialize (const Settings &settings=Settings(), const std::vector< std::string > &adapters=DEFAULT_ADAPTERS)
 Initialize the planning context. All parameter provided are defaults. More...
 
- Public Member Functions inherited from robowflex::OMPL::OMPLPipelinePlanner
 OMPLPipelinePlanner (const RobotPtr &robot, const std::string &name="")
 
 OMPLPipelinePlanner (OMPLPipelinePlanner const &)=delete
 
void operator= (OMPLPipelinePlanner const &)=delete
 
bool initialize (const std::string &config_file="", const Settings &settings=Settings(), const std::string &plugin=DEFAULT_PLUGIN, const std::vector< std::string > &adapters=DEFAULT_ADAPTERS)
 Initialize planning pipeline. Loads OMPL planning plugin plugin with the planning adapters adapters. Parameters are set on the parameter server from settings and planning configurations are loaded from the YAML file config_file. More...
 
std::vector< std::stringgetPlannerConfigs () const override
 Return all planner configurations offered by this planner. Any of the configurations returned can be set as the planner for a motion planning query sent to plan(). More...
 
- Public Member Functions inherited from robowflex::PipelinePlanner
 PipelinePlanner (const RobotPtr &robot, const std::string &name="")
 Constructor. More...
 
 PipelinePlanner (PipelinePlanner const &)=delete
 
void operator= (PipelinePlanner const &)=delete
 
planning_interface::MotionPlanResponse plan (const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request) override
 Plan a motion given a request and a scene. Uses the planning pipeline's generatePlan() method, which goes through planning adapters. More...
 
template<typename T >
std::shared_ptr< T > extractPlanningContext (const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request) const
 Retrieve planning context and dynamically cast to desired type from planning pipeline. More...
 
- Public Member Functions inherited from robowflex::Planner
 Planner (const RobotPtr &robot, const std::string &name="")
 Constructor. Takes in a robot description and an optional namespace name. If name is specified, planner parameters are namespaced under the namespace of robot. More...
 
 Planner (Planner const &)=delete
 
void operator= (Planner const &)=delete
 
virtual std::map< std::string, ProgressPropertygetProgressProperties (const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request) const
 Retrieve the planner progress property map for this planner given a specific request. More...
 
const RobotPtr getRobot () const
 Return the robot for this planner. More...
 
const std::stringgetName () const
 Get the name of the planner. More...
 
virtual void preRun (const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request)
 This function is called before benchmarking. More...
 

Static Private Attributes

static const std::string DEFAULT_CONFIG {"package://fetch_moveit_config/config/ompl_planning.yaml"}
 Default planning configuration. More...
 
static const std::string RESOURCE_CONFIG
 Planning configuration from robowflex_resources. More...
 

Additional Inherited Members

- Public Types inherited from robowflex::Planner
using ProgressProperty = std::function< std::string()>
 A function that returns the value of a planner property over the course of a run. More...
 
- Protected Attributes inherited from robowflex::PipelinePlanner
planning_pipeline::PlanningPipelinePtr pipeline_
 Loaded planning pipeline plugin. More...
 
- Protected Attributes inherited from robowflex::Planner
RobotPtr robot_
 The robot to plan for. More...
 
IO::Handler handler_
 The parameter handler for the planner. More...
 
const std::string name_
 Namespace for the planner. More...
 
- Static Protected Attributes inherited from robowflex::OMPL::OMPLPipelinePlanner
static const std::string DEFAULT_PLUGIN
 The default OMPL plugin. More...
 
static const std::vector< std::stringDEFAULT_ADAPTERS
 The default planning adapters. More...
 

Detailed Description

Convenience class for the default motion planning pipeline for Fetch.

Definition at line 93 of file fetch.h.

Constructor & Destructor Documentation

◆ FetchOMPLPipelinePlanner()

OMPL::FetchOMPLPipelinePlanner::FetchOMPLPipelinePlanner ( const RobotPtr robot,
const std::string name = "" 
)

Constructor.

Parameters
[in]robotRobot to create planner for.
[in]nameNamespace of this planner.

Definition at line 141 of file fetch.cpp.

142  : OMPLPipelinePlanner(robot, name)
143 {
144 }
OMPLPipelinePlanner(const RobotPtr &robot, const std::string &name="")
Functions for loading and animating robots in Blender.

Member Function Documentation

◆ initialize()

bool OMPL::FetchOMPLPipelinePlanner::initialize ( const Settings settings = Settings(),
const std::vector< std::string > &  adapters = DEFAULT_ADAPTERS 
)

Initialize the planning context. All parameter provided are defaults.

Parameters
[in]settingsSettings to set on the parameter server.
[in]adaptersPlanning adapters to load.
Returns
True on success, false on failure.

Definition at line 146 of file fetch.cpp.

148 {
149  if (IO::resolvePackage(RESOURCE_CONFIG).empty())
152 }
static const std::string RESOURCE_CONFIG
Planning configuration from robowflex_resources.
Definition: fetch.h:112
static const std::string DEFAULT_CONFIG
Default planning configuration.
Definition: fetch.h:111
static const std::string DEFAULT_PLUGIN
The default OMPL plugin.
bool initialize(const std::string &config_file="", const Settings &settings=Settings(), const std::string &plugin=DEFAULT_PLUGIN, const std::vector< std::string > &adapters=DEFAULT_ADAPTERS)
Initialize planning pipeline. Loads OMPL planning plugin plugin with the planning adapters adapters....
std::string resolvePackage(const std::string &path)
Resolves package:// URLs to their canonical form. The path does not need to exist,...

Member Data Documentation

◆ DEFAULT_CONFIG

const std::string OMPL::FetchOMPLPipelinePlanner::DEFAULT_CONFIG {"package://fetch_moveit_config/config/ompl_planning.yaml"}
staticprivate

Default planning configuration.

Definition at line 111 of file fetch.h.

◆ RESOURCE_CONFIG

const std::string OMPL::FetchOMPLPipelinePlanner::RESOURCE_CONFIG
staticprivate
Initial value:
{"package://robowflex_resources/fetch/config/"
"ompl_planning.yaml"}

Planning configuration from robowflex_resources.

Definition at line 112 of file fetch.h.


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