41 #include <moveit/task_constructor/solvers/planner_interface.h>
45 namespace task_constructor {
48 MOVEIT_CLASS_FORWARD(MultiPlanner);
61 using PlannerList = std::vector<solvers::PlannerInterfacePtr>;
62 using PlannerList::PlannerList;
64 void init(
const moveit::core::RobotModelConstPtr& robot_model)
override;
66 Result plan(
const planning_scene::PlanningSceneConstPtr& from,
const planning_scene::PlanningSceneConstPtr& to,
67 const moveit::core::JointModelGroup* jmg,
double timeout, robot_trajectory::RobotTrajectoryPtr& result,
68 const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints())
override;
70 Result plan(
const planning_scene::PlanningSceneConstPtr& from,
const moveit::core::LinkModel& link,
71 const Eigen::Isometry3d& offset,
const Eigen::Isometry3d& target,
72 const moveit::core::JointModelGroup* jmg,
double timeout, robot_trajectory::RobotTrajectoryPtr& result,
73 const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints())
override;
Definition: multi_planner.h:59
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
Definition: multi_planner.cpp:52
Definition: planner_interface.h:69
Definition: planner_interface.h:75