41 const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"global_planner_component");
49 const std::string
UNDEFINED =
"<undefined>";
68 node->declare_parameter<std::string>(
"ompl.planning_plugin",
"ompl_interface/OMPLPlanner");
80 node->declare_parameter<std::string>(
"moveit_controller_manager",
UNDEFINED);
86 moveit_cpp_ = std::make_shared<moveit_cpp::MoveItCpp>(node, moveit_cpp_options);
98 const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::GlobalPlanner>> global_goal_handle)
100 moveit_msgs::msg::MotionPlanResponse response;
102 if ((global_goal_handle->get_goal())->motion_sequence.items.empty())
104 RCLCPP_WARN(LOGGER,
"Global planner received motion sequence request with no items. At least one is needed.");
105 response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
110 if ((global_goal_handle->get_goal())->motion_sequence.items.size() > 1)
112 RCLCPP_WARN(LOGGER,
"Global planner received motion sequence request with more than one item but the "
113 "'moveit_planning_pipeline' plugin only accepts one item. Just using the first item as global "
116 auto motion_plan_req = (global_goal_handle->get_goal())->motion_sequence.items[0].req;
120 plan_params.
planner_id = motion_plan_req.planner_id;
121 plan_params.planning_pipeline = motion_plan_req.pipeline_id;
122 plan_params.planning_attempts = motion_plan_req.num_planning_attempts;
123 plan_params.planning_time = motion_plan_req.allowed_planning_time;
124 plan_params.max_velocity_scaling_factor = motion_plan_req.max_velocity_scaling_factor;
125 plan_params.max_acceleration_scaling_factor = motion_plan_req.max_acceleration_scaling_factor;
128 auto planning_components = std::make_shared<moveit_cpp::PlanningComponent>(motion_plan_req.group_name, moveit_cpp_);
131 planning_components->setGoal(motion_plan_req.goal_constraints);
134 auto plan_solution = planning_components->plan(plan_params);
135 if (plan_solution.error_code != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
137 response.error_code = plan_solution.error_code;
142 response.trajectory_start = plan_solution.start_state;
143 response.group_name = motion_plan_req.group_name;
144 plan_solution.trajectory->getRobotTrajectoryMsg(response.trajectory);
145 response.error_code = plan_solution.error_code;
151 #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
const rclcpp::Logger LOGGER
Parameter container for initializing MoveItCpp.
Planner parameters provided with the MotionPlanRequest.