moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
global_planner_component.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2020, PickNik Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of PickNik Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
38#include <moveit_msgs/msg/move_it_error_codes.hpp>
39
40#include <chrono>
41#include <thread>
42
43namespace
44{
45const auto JOIN_THREAD_TIMEOUT = std::chrono::seconds(1);
46} // namespace
47
49{
50using namespace std::chrono_literals;
51const std::string UNDEFINED = "<undefined>";
52
53GlobalPlannerComponent::GlobalPlannerComponent(const rclcpp::NodeOptions& options)
54 : node_{ std::make_shared<rclcpp::Node>("global_planner_component", options) }
55{
56 if (!initializeGlobalPlanner())
57 {
58 throw std::runtime_error("Failed to initialize Global Planner Component");
59 }
60}
61
62bool GlobalPlannerComponent::initializeGlobalPlanner()
63{
64 // Initialize global planning request action server
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",
68 // Goal callback
69 [this](const rclcpp_action::GoalUUID& /*unused*/,
70 const std::shared_ptr<const moveit_msgs::action::GlobalPlanner::Goal>& /*unused*/) {
71 RCLCPP_INFO(node_->get_logger(), "Received global planning goal request");
72 // If another goal is active, cancel it and reject this goal
73 if (long_callback_thread_.joinable())
74 {
75 // Try to terminate the execution thread
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)
78 {
79 RCLCPP_WARN(node_->get_logger(), "Another goal was running. Rejecting the new hybrid planning goal.");
80 return rclcpp_action::GoalResponse::REJECT;
81 }
82 if (!global_planner_instance_->reset())
83 {
84 throw std::runtime_error("Failed to reset the global planner while aborting current global planning");
85 }
86 }
87 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
88 },
89 // Cancel callback
90 [this](const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::GlobalPlanner>>& /*unused*/) {
91 RCLCPP_INFO(node_->get_logger(), "Received request to cancel global planning goal");
92 if (long_callback_thread_.joinable())
93 {
94 long_callback_thread_.join();
95 }
96 if (!global_planner_instance_->reset())
97 {
98 throw std::runtime_error("Failed to reset the global planner while aborting current global planning");
99 }
100 return rclcpp_action::CancelResponse::ACCEPT;
101 },
102 // Execution callback
103 [this](const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::GlobalPlanner>>& goal_handle) {
104 // this needs to return quickly to avoid blocking the executor, so spin up a new thread
105 if (long_callback_thread_.joinable())
106 {
107 long_callback_thread_.join();
108 global_planner_instance_->reset();
109 }
110 long_callback_thread_ = std::thread(&GlobalPlannerComponent::globalPlanningRequestCallback, this, goal_handle);
111 },
112 rcl_action_server_get_default_options(), cb_group_);
113
114 global_trajectory_pub_ = node_->create_publisher<moveit_msgs::msg::MotionPlanResponse>("global_trajectory", 1);
115
116 // Load global planner plugin
117 planner_plugin_name_ = node_->declare_parameter<std::string>("global_planner_name", UNDEFINED);
118
119 try
120 {
121 global_planner_plugin_loader_ = std::make_unique<pluginlib::ClassLoader<GlobalPlannerInterface>>(
122 "moveit_hybrid_planning", "moveit::hybrid_planning::GlobalPlannerInterface");
123 }
124 catch (pluginlib::PluginlibException& ex)
125 {
126 RCLCPP_ERROR(node_->get_logger(), "Exception while creating global planner plugin loader: '%s'", ex.what());
127 return false;
128 }
129 try
130 {
131 global_planner_instance_ = global_planner_plugin_loader_->createUniqueInstance(planner_plugin_name_);
132 }
133 catch (pluginlib::PluginlibException& ex)
134 {
135 RCLCPP_ERROR(node_->get_logger(), "Exception while loading global planner '%s': '%s'", planner_plugin_name_.c_str(),
136 ex.what());
137 return false;
138 }
139
140 // Initialize global planner plugin
141 if (!global_planner_instance_->initialize(node_))
142 {
143 RCLCPP_ERROR(node_->get_logger(), "Unable to initialize global planner plugin '%s'", planner_plugin_name_.c_str());
144 return false;
145 }
146 RCLCPP_INFO(node_->get_logger(), "Using global planner plugin '%s'", planner_plugin_name_.c_str());
147 return true;
148}
149
150void GlobalPlannerComponent::globalPlanningRequestCallback(
151 const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::GlobalPlanner>>& goal_handle)
152{
153 // Plan global trajectory
154 moveit_msgs::msg::MotionPlanResponse planning_solution = global_planner_instance_->plan(goal_handle);
155
156 // Send action response
157 auto result = std::make_shared<moveit_msgs::action::GlobalPlanner::Result>();
158 result->response = planning_solution;
159
160 if (planning_solution.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
161 {
162 // Publish global planning solution to the local planner
163 global_trajectory_pub_->publish(planning_solution);
164 goal_handle->succeed(result);
165 }
166 else
167 {
168 goal_handle->abort(result);
169 }
170
171 // Reset the global planner
172 global_planner_instance_->reset();
173};
174} // namespace moveit::hybrid_planning
175
176// Register the component with class_loader
177#include <rclcpp_components/register_node_macro.hpp>
178RCLCPP_COMPONENTS_REGISTER_NODE(moveit::hybrid_planning::GlobalPlannerComponent)
GlobalPlannerComponent(const rclcpp::NodeOptions &options)
Constructor.