41 #include <moveit/task_constructor/solvers/planner_interface.h>
42 #include <moveit_msgs/MotionPlanRequest.h>
43 #include <moveit/macros/class_forward.h>
45 namespace planning_pipeline {
46 MOVEIT_CLASS_FORWARD(PlanningPipeline);
50 namespace task_constructor {
53 MOVEIT_CLASS_FORWARD(PipelinePlanner);
61 moveit::core::RobotModelConstPtr model;
62 std::string ns{
"move_group" };
63 std::string pipeline{
"ompl" };
64 std::string adapter_param{
"request_adapters" };
67 static planning_pipeline::PlanningPipelinePtr create(
const moveit::core::RobotModelConstPtr& model) {
73 static planning_pipeline::PlanningPipelinePtr create(
const Specification& spec);
77 PipelinePlanner(
const planning_pipeline::PlanningPipelinePtr& planning_pipeline);
79 void setPlannerId(
const std::string& planner) { setProperty(
"planner", planner); }
81 void init(
const moveit::core::RobotModelConstPtr& robot_model)
override;
83 Result plan(
const planning_scene::PlanningSceneConstPtr& from,
const planning_scene::PlanningSceneConstPtr& to,
84 const core::JointModelGroup* jmg,
double timeout, robot_trajectory::RobotTrajectoryPtr& result,
85 const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints())
override;
87 Result plan(
const planning_scene::PlanningSceneConstPtr& from,
const moveit::core::LinkModel& link,
88 const Eigen::Isometry3d& offset,
const Eigen::Isometry3d& target,
89 const moveit::core::JointModelGroup* jmg,
double timeout, robot_trajectory::RobotTrajectoryPtr& result,
90 const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints())
override;
93 Result plan(
const planning_scene::PlanningSceneConstPtr& from,
const moveit_msgs::MotionPlanRequest& req,
94 robot_trajectory::RobotTrajectoryPtr& result);
96 std::string pipeline_name_;
97 planning_pipeline::PlanningPipelinePtr planner_;
Definition: pipeline_planner.h:57
Definition: planner_interface.h:69
Definition: pipeline_planner.h:60