67 if (long_callback_thread_.joinable())
69 long_callback_thread_.join();
83 return node_->get_node_base_interface();
96 std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanner>> goal_handle);
124 std::shared_ptr<
rclcpp::Node> node_;
133 std::atomic<
bool> stop_hybrid_planning_;
136 std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanner>> hybrid_planning_goal_handle_;
139 std::shared_ptr<moveit_msgs::action::HybridPlanner_Feedback> hybrid_planning_progess_;
142 rclcpp_action::Client<moveit_msgs::action::LocalPlanner>::SharedPtr local_planner_action_client_;
143 rclcpp_action::Client<moveit_msgs::action::GlobalPlanner>::SharedPtr global_planner_action_client_;
146 rclcpp_action::Server<moveit_msgs::action::HybridPlanner>::SharedPtr hybrid_planning_request_server_;
149 rclcpp::Subscription<moveit_msgs::msg::MotionPlanResponse>::SharedPtr global_solution_sub_;
152 std::thread long_callback_thread_;
155 rclcpp::CallbackGroup::SharedPtr cb_group_;