Robowflex
v0.1
Making MoveIt Easy
|
An abstract interface to a motion planning algorithm. More...
#include <planning.h>
Public Types | |
using | ProgressProperty = std::function< std::string()> |
A function that returns the value of a planner property over the course of a run. More... | |
Public Member Functions | |
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 planning_interface::MotionPlanResponse | plan (const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request)=0 |
Plan a motion given a request and a scene. A virtual method that must be implemented by any robowflex::Planner. More... | |
virtual std::vector< std::string > | getPlannerConfigs () const =0 |
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... | |
virtual std::map< std::string, ProgressProperty > | getProgressProperties (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::string & | getName () 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... | |
Protected Attributes | |
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... | |
An abstract interface to a motion planning algorithm.
Definition at line 33 of file robowflex_library/include/robowflex_library/planning.h.
A function that returns the value of a planner property over the course of a run.
Definition at line 38 of file robowflex_library/include/robowflex_library/planning.h.
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.
[in] | robot | The robot to plan for. |
[in] | name | Optional namespace for planner. |
Definition at line 26 of file robowflex_library/src/planning.cpp.
|
delete |
const std::string & Planner::getName | ( | ) | const |
Get the name of the planner.
Definition at line 36 of file robowflex_library/src/planning.cpp.
|
pure virtual |
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().
Implemented in robowflex::TrajOptPlanner, robowflex::OMPL::OMPLInterfacePlanner, robowflex::opt::CHOMPPipelinePlanner, robowflex::OMPL::OMPLPipelinePlanner, robowflex::SimpleCartesianPlanner, robowflex::PoolPlanner, and robowflex::darts::DARTPlanner.
|
virtual |
Retrieve the planner progress property map for this planner given a specific request.
[in] | scene | A planning scene for the same robot_ to compute the plan in. |
[in] | request | Request to get progress properties for. |
Reimplemented in robowflex::OMPL::OMPLInterfacePlanner.
Definition at line 46 of file robowflex_library/src/planning.cpp.
const RobotPtr Planner::getRobot | ( | ) | const |
Return the robot for this planner.
Definition at line 31 of file robowflex_library/src/planning.cpp.
|
delete |
|
pure virtual |
Plan a motion given a request and a scene. A virtual method that must be implemented by any robowflex::Planner.
[in] | scene | A planning scene for the same robot_ to compute the plan in. |
[in] | request | The motion planning request to solve. |
Implemented in robowflex::TrajOptPlanner, robowflex::OMPL::OMPLInterfacePlanner, robowflex::PipelinePlanner, robowflex::SimpleCartesianPlanner, robowflex::PoolPlanner, and robowflex::darts::DARTPlanner.
|
virtual |
This function is called before benchmarking.
[in] | scene | Scene to plan for. |
[in] | request | Planning request. |
Reimplemented in robowflex::OMPL::OMPLInterfacePlanner, and robowflex::darts::DARTPlanner.
Definition at line 41 of file robowflex_library/src/planning.cpp.
|
protected |
The parameter handler for the planner.
Definition at line 94 of file robowflex_library/include/robowflex_library/planning.h.
|
protected |
Namespace for the planner.
Definition at line 95 of file robowflex_library/include/robowflex_library/planning.h.
|
protected |
The robot to plan for.
Definition at line 93 of file robowflex_library/include/robowflex_library/planning.h.