#include <multi_planner.h>

Public Types | |
| using | PlannerList = std::vector< solvers::PlannerInterfacePtr > |
Public Member Functions | |
| void | init (const moveit::core::RobotModelConstPtr &robot_model) override |
| Result | plan (const planning_scene::PlanningSceneConstPtr &from, const moveit::core::LinkModel &link, const Eigen::Isometry3d &offset, const Eigen::Isometry3d &target, const moveit::core::JointModelGroup *jmg, double timeout, robot_trajectory::RobotTrajectoryPtr &result, const moveit_msgs::Constraints &path_constraints=moveit_msgs::Constraints()) override |
| plan trajectory from current robot state to Cartesian target, such that pose(link)*offset == target More... | |
| Result | plan (const planning_scene::PlanningSceneConstPtr &from, const planning_scene::PlanningSceneConstPtr &to, const moveit::core::JointModelGroup *jmg, double timeout, robot_trajectory::RobotTrajectoryPtr &result, const moveit_msgs::Constraints &path_constraints=moveit_msgs::Constraints()) override |
| plan trajectory between to robot states More... | |
Public Member Functions inherited from moveit::task_constructor::solvers::PlannerInterface | |
| PlannerInterface () | |
| PropertyMap & | properties () |
| const PropertyMap & | properties () const |
| void | setMaxAccelerationScalingFactor (double factor) |
| void | setMaxVelocityScalingFactor (double factor) |
| void | setProperty (const std::string &name, const boost::any &value) |
| void | setTimeout (double timeout) |
| void | setTimeParameterization (const trajectory_processing::TimeParameterizationPtr &tp) |
| virtual | ~PlannerInterface () |
A meta planner that runs multiple alternative planners in sequence and returns the first found solution.
This is useful to sequence different planning strategies of increasing complexity, e.g. Cartesian or joint-space interpolation first, then OMPL, ... This is (slightly) different from the Fallbacks container, as the MultiPlanner directly applies its planners to each individual planning job. In contrast, the Fallbacks container first runs the active child to exhaustion before switching to the next child, which possibly applies a different planning strategy.
Definition at line 154 of file multi_planner.h.
| using moveit::task_constructor::solvers::MultiPlanner::PlannerList = std::vector<solvers::PlannerInterfacePtr> |
Definition at line 157 of file multi_planner.h.
|
overridevirtual |
Implements moveit::task_constructor::solvers::PlannerInterface.
Definition at line 143 of file multi_planner.cpp.
|
overridevirtual |
plan trajectory from current robot state to Cartesian target, such that pose(link)*offset == target
Implements moveit::task_constructor::solvers::PlannerInterface.
Definition at line 175 of file multi_planner.cpp.
|
overridevirtual |
plan trajectory between to robot states
Implements moveit::task_constructor::solvers::PlannerInterface.
Definition at line 148 of file multi_planner.cpp.