Public Types | Public Member Functions | List of all members
moveit::task_constructor::solvers::MultiPlanner Class Reference

#include <multi_planner.h>

Inheritance diagram for moveit::task_constructor::solvers::MultiPlanner:
Inheritance graph
[legend]

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 ()
 
PropertyMapproperties ()
 
const PropertyMapproperties () 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 ()
 

Detailed Description

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.

Member Typedef Documentation

◆ PlannerList

using moveit::task_constructor::solvers::MultiPlanner::PlannerList = std::vector<solvers::PlannerInterfacePtr>

Definition at line 157 of file multi_planner.h.

Member Function Documentation

◆ init()

void moveit::task_constructor::solvers::MultiPlanner::init ( const moveit::core::RobotModelConstPtr &  robot_model)
overridevirtual

◆ plan() [1/2]

PlannerInterface::Result moveit::task_constructor::solvers::MultiPlanner::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() 
)
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.

◆ plan() [2/2]

PlannerInterface::Result moveit::task_constructor::solvers::MultiPlanner::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() 
)
overridevirtual

plan trajectory between to robot states

Implements moveit::task_constructor::solvers::PlannerInterface.

Definition at line 148 of file multi_planner.cpp.


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


core
Author(s):
autogenerated on Sat May 3 2025 02:40:11