53 : node_{ std::make_shared<
rclcpp::Node>(
"hybrid_planning_manager", options) }, stop_hybrid_planning_(false)
58 planner_logic_plugin_loader_ = std::make_unique<pluginlib::ClassLoader<PlannerLogicInterface>>(
59 "moveit_hybrid_planning",
"moveit::hybrid_planning::PlannerLogicInterface");
61 catch (pluginlib::PluginlibException& ex)
63 RCLCPP_ERROR(getLogger(),
"Exception while creating planner logic plugin loader '%s'", ex.what());
66 auto param_listener = hp_manager_parameters::ParamListener(node_,
"");
67 const auto params = param_listener.get_params();
70 planner_logic_instance_ = planner_logic_plugin_loader_->createUniqueInstance(params.planner_logic_plugin_name);
71 if (!planner_logic_instance_->initialize())
73 throw std::runtime_error(
"Unable to initialize planner logic plugin");
75 RCLCPP_INFO(getLogger(),
"Using planner logic interface '%s'", params.planner_logic_plugin_name.c_str());
77 catch (pluginlib::PluginlibException& ex)
79 RCLCPP_ERROR(getLogger(),
"Exception while loading planner logic '%s': '%s'",
80 params.planner_logic_plugin_name.c_str(), ex.what());
85 local_planner_action_client_ =
86 rclcpp_action::create_client<moveit_msgs::action::LocalPlanner>(node_,
"local_planning_action");
87 if (!local_planner_action_client_->wait_for_action_server(2s))
89 RCLCPP_ERROR(getLogger(),
"Local planner action server not available after waiting");
94 global_planner_action_client_ =
95 rclcpp_action::create_client<moveit_msgs::action::GlobalPlanner>(node_,
"global_planning_action");
96 if (!global_planner_action_client_->wait_for_action_server(2s))
98 RCLCPP_ERROR(getLogger(),
"Global planner action server not available after waiting");
103 cb_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
104 hybrid_planning_request_server_ = rclcpp_action::create_server<moveit_msgs::action::HybridPlanner>(
105 node_,
"run_hybrid_planning",
107 [](
const rclcpp_action::GoalUUID& ,
108 const std::shared_ptr<const moveit_msgs::action::HybridPlanner::Goal>& ) {
109 RCLCPP_INFO(getLogger(),
"Received goal request");
110 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
113 [&](
const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanner>>& ) {
115 RCLCPP_INFO(getLogger(),
"Received request to cancel goal");
116 return rclcpp_action::CancelResponse::ACCEPT;
119 [&](
const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanner>>& goal_handle) {
121 if (long_callback_thread_.joinable())
127 rcl_action_server_get_default_options(), cb_group_);
130 global_solution_sub_ = node_->create_subscription<moveit_msgs::msg::MotionPlanResponse>(
131 "global_trajectory", rclcpp::SystemDefaultsQoS(),
132 [&](
const moveit_msgs::msg::MotionPlanResponse::ConstSharedPtr& ) {
167 auto global_goal_options = rclcpp_action::Client<moveit_msgs::action::GlobalPlanner>::SendGoalOptions();
170 global_goal_options.goal_response_callback =
171 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::GlobalPlanner>::SharedPtr& goal_handle) {
172 auto planning_progress = std::make_shared<moveit_msgs::action::HybridPlanner::Feedback>();
173 auto& feedback = planning_progress->feedback;
176 feedback =
"Global goal was rejected by server";
180 feedback =
"Global goal accepted by server";
182 hybrid_planning_goal_handle_->publish_feedback(planning_progress);
185 global_goal_options.result_callback =
186 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::GlobalPlanner>::WrappedResult& global_result) {
190 switch (global_result.code)
192 case rclcpp_action::ResultCode::SUCCEEDED:
195 case rclcpp_action::ResultCode::CANCELED:
198 case rclcpp_action::ResultCode::ABORTED:
209 auto global_goal_msg = moveit_msgs::action::GlobalPlanner::Goal();
210 global_goal_msg.motion_sequence =
211 (hybrid_planning_goal_handle_->get_goal())->motion_sequence;
212 global_goal_msg.planning_group = (hybrid_planning_goal_handle_->get_goal())->planning_group;
214 if (stop_hybrid_planning_)
220 auto goal_handle_future = global_planner_action_client_->async_send_goal(global_goal_msg, global_goal_options);
227 auto local_goal_msg = moveit_msgs::action::LocalPlanner::Goal();
228 auto local_goal_options = rclcpp_action::Client<moveit_msgs::action::LocalPlanner>::SendGoalOptions();
229 rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr goal_handle;
232 local_goal_options.goal_response_callback =
233 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr& goal_handle) {
234 auto planning_progress = std::make_shared<moveit_msgs::action::HybridPlanner::Feedback>();
235 auto& feedback = planning_progress->feedback;
238 feedback =
"Local goal was rejected by server";
242 feedback =
"Local goal accepted by server";
244 hybrid_planning_goal_handle_->publish_feedback(planning_progress);
248 local_goal_options.feedback_callback =
249 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr& ,
250 const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Feedback>& local_planner_feedback) {
255 local_goal_options.result_callback =
256 [&](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::WrappedResult& local_result) {
260 switch (local_result.code)
262 case rclcpp_action::ResultCode::SUCCEEDED:
265 case rclcpp_action::ResultCode::CANCELED:
268 case rclcpp_action::ResultCode::ABORTED:
277 if (stop_hybrid_planning_)
283 auto goal_handle_future = local_planner_action_client_->async_send_goal(local_goal_msg, local_goal_options);