38#include <moveit_msgs/msg/move_it_error_codes.hpp>
45const auto JOIN_THREAD_TIMEOUT = std::chrono::seconds(1);
50using namespace std::chrono_literals;
54 : node_{ std::make_shared<
rclcpp::Node>(
"global_planner_component", options) }
56 if (!initializeGlobalPlanner())
58 throw std::runtime_error(
"Failed to initialize Global Planner Component");
62bool GlobalPlannerComponent::initializeGlobalPlanner()
65 cb_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
66 global_planning_request_server_ = rclcpp_action::create_server<moveit_msgs::action::GlobalPlanner>(
67 node_,
"global_planning_action",
69 [
this](
const rclcpp_action::GoalUUID& ,
70 const std::shared_ptr<const moveit_msgs::action::GlobalPlanner::Goal>& ) {
71 RCLCPP_INFO(node_->get_logger(),
"Received global planning goal request");
73 if (long_callback_thread_.joinable())
76 auto future = std::async(std::launch::async, &std::thread::join, &long_callback_thread_);
77 if (future.wait_for(JOIN_THREAD_TIMEOUT) == std::future_status::timeout)
79 RCLCPP_WARN(node_->get_logger(),
"Another goal was running. Rejecting the new hybrid planning goal.");
80 return rclcpp_action::GoalResponse::REJECT;
82 if (!global_planner_instance_->reset())
84 throw std::runtime_error(
"Failed to reset the global planner while aborting current global planning");
87 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
90 [
this](
const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::GlobalPlanner>>& ) {
91 RCLCPP_INFO(node_->get_logger(),
"Received request to cancel global planning goal");
92 if (long_callback_thread_.joinable())
94 long_callback_thread_.join();
96 if (!global_planner_instance_->reset())
98 throw std::runtime_error(
"Failed to reset the global planner while aborting current global planning");
100 return rclcpp_action::CancelResponse::ACCEPT;
103 [
this](
const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::GlobalPlanner>>& goal_handle) {
105 if (long_callback_thread_.joinable())
107 long_callback_thread_.join();
108 global_planner_instance_->reset();
110 long_callback_thread_ = std::thread(&GlobalPlannerComponent::globalPlanningRequestCallback,
this, goal_handle);
112 rcl_action_server_get_default_options(), cb_group_);
114 global_trajectory_pub_ = node_->create_publisher<moveit_msgs::msg::MotionPlanResponse>(
"global_trajectory", 1);
117 planner_plugin_name_ = node_->declare_parameter<std::string>(
"global_planner_name",
UNDEFINED);
121 global_planner_plugin_loader_ = std::make_unique<pluginlib::ClassLoader<GlobalPlannerInterface>>(
122 "moveit_hybrid_planning",
"moveit::hybrid_planning::GlobalPlannerInterface");
124 catch (pluginlib::PluginlibException& ex)
126 RCLCPP_ERROR(node_->get_logger(),
"Exception while creating global planner plugin loader: '%s'", ex.what());
131 global_planner_instance_ = global_planner_plugin_loader_->createUniqueInstance(planner_plugin_name_);
133 catch (pluginlib::PluginlibException& ex)
135 RCLCPP_ERROR(node_->get_logger(),
"Exception while loading global planner '%s': '%s'", planner_plugin_name_.c_str(),
141 if (!global_planner_instance_->initialize(node_))
143 RCLCPP_ERROR(node_->get_logger(),
"Unable to initialize global planner plugin '%s'", planner_plugin_name_.c_str());
146 RCLCPP_INFO(node_->get_logger(),
"Using global planner plugin '%s'", planner_plugin_name_.c_str());
150void GlobalPlannerComponent::globalPlanningRequestCallback(
151 const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::GlobalPlanner>>& goal_handle)
154 moveit_msgs::msg::MotionPlanResponse planning_solution = global_planner_instance_->plan(goal_handle);
157 auto result = std::make_shared<moveit_msgs::action::GlobalPlanner::Result>();
158 result->response = planning_solution;
160 if (planning_solution.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
163 global_trajectory_pub_->publish(planning_solution);
164 goal_handle->succeed(result);
168 goal_handle->abort(result);
172 global_planner_instance_->reset();
177#include <rclcpp_components/register_node_macro.hpp>
GlobalPlannerComponent(const rclcpp::NodeOptions &options)
Constructor.
const std::string UNDEFINED