44 const std::string
UNDEFINED =
"<undefined>";
63 node->declare_parameter<std::vector<std::string>>(
"ompl.planning_plugins", {
"ompl_interface/OMPLPlanner" });
75 node->declare_parameter<std::string>(
"moveit_controller_manager",
UNDEFINED);
81 moveit_cpp_ = std::make_shared<moveit_cpp::MoveItCpp>(node, moveit_cpp_options);
93 const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::GlobalPlanner>> global_goal_handle)
95 moveit_msgs::msg::MotionPlanResponse response;
97 if ((global_goal_handle->get_goal())->motion_sequence.items.empty())
99 RCLCPP_WARN(node_ptr_->get_logger(),
100 "Global planner received motion sequence request with no items. At least one is needed.");
101 response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
106 if ((global_goal_handle->get_goal())->motion_sequence.items.size() > 1)
108 RCLCPP_WARN(node_ptr_->get_logger(),
109 "Global planner received motion sequence request with more than one item but the "
110 "'moveit_planning_pipeline' plugin only accepts one item. Just using the first item as global "
113 auto motion_plan_req = (global_goal_handle->get_goal())->motion_sequence.items[0].req;
117 plan_params.
planner_id = motion_plan_req.planner_id;
118 plan_params.planning_pipeline = motion_plan_req.pipeline_id;
119 plan_params.planning_attempts = motion_plan_req.num_planning_attempts;
120 plan_params.planning_time = motion_plan_req.allowed_planning_time;
121 plan_params.max_velocity_scaling_factor = motion_plan_req.max_velocity_scaling_factor;
122 plan_params.max_acceleration_scaling_factor = motion_plan_req.max_acceleration_scaling_factor;
125 auto planning_components = std::make_shared<moveit_cpp::PlanningComponent>(motion_plan_req.group_name, moveit_cpp_);
128 planning_components->setGoal(motion_plan_req.goal_constraints);
131 auto plan_solution = planning_components->plan(plan_params);
132 if (!
bool(plan_solution.error_code))
134 response.error_code = plan_solution.error_code;
139 response.trajectory_start = plan_solution.start_state;
140 response.group_name = motion_plan_req.group_name;
141 plan_solution.trajectory->getRobotTrajectoryMsg(response.trajectory);
142 response.error_code = plan_solution.error_code;
148 #include <pluginlib/class_list_macros.hpp>
moveit_msgs::msg::MotionPlanResponse plan(const std::shared_ptr< rclcpp_action::ServerGoalHandle< moveit_msgs::action::GlobalPlanner >> global_goal_handle) override
bool reset() noexcept override
bool initialize(const rclcpp::Node::SharedPtr &node) override
PLUGINLIB_EXPORT_CLASS(moveit::hybrid_planning::MoveItPlanningPipeline, moveit::hybrid_planning::GlobalPlannerInterface)
const std::string PLANNING_SCENE_MONITOR_NS
const std::string PLAN_REQUEST_PARAM_NS
const std::string PLANNING_PIPELINES_NS
const std::string UNDEFINED
Parameter container for initializing MoveItCpp.
Planner parameters provided with the MotionPlanRequest.