40 const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"hybrid_planning_manager");
45 using namespace std::chrono_literals;
48 : Node(
"hybrid_planning_manager",
options), initialized_(false), stop_hybrid_planning_(false)
52 timer_ = this->create_wall_timer(1ms, [
this]() {
61 const std::string error =
"Failed to initialize global planner";
63 throw std::runtime_error(error);
75 planner_logic_plugin_loader_ = std::make_unique<pluginlib::ClassLoader<PlannerLogicInterface>>(
76 "moveit_hybrid_planning",
"moveit::hybrid_planning::PlannerLogicInterface");
78 catch (pluginlib::PluginlibException& ex)
80 RCLCPP_ERROR(LOGGER,
"Exception while creating planner logic plugin loader '%s'", ex.what());
83 std::string logic_plugin_name =
"";
84 if (this->has_parameter(
"planner_logic_plugin_name"))
86 this->get_parameter<std::string>(
"planner_logic_plugin_name", logic_plugin_name);
90 logic_plugin_name = this->declare_parameter<std::string>(
"planner_logic_plugin_name",
91 "moveit::hybrid_planning/ReplanInvalidatedTrajectory");
95 planner_logic_instance_ = planner_logic_plugin_loader_->createUniqueInstance(logic_plugin_name);
98 throw std::runtime_error(
"Unable to initialize planner logic plugin");
100 RCLCPP_INFO(LOGGER,
"Using planner logic interface '%s'", logic_plugin_name.c_str());
102 catch (pluginlib::PluginlibException& ex)
104 RCLCPP_ERROR(LOGGER,
"Exception while loading planner logic '%s': '%s'", logic_plugin_name.c_str(), ex.what());
108 std::string local_planning_action_name = this->declare_parameter<std::string>(
"local_planning_action_name",
"");
109 this->get_parameter<std::string>(
"local_planning_action_name", local_planning_action_name);
110 if (local_planning_action_name.empty())
112 RCLCPP_ERROR(LOGGER,
"local_planning_action_name parameter was not defined");
115 local_planner_action_client_ =
116 rclcpp_action::create_client<moveit_msgs::action::LocalPlanner>(
this, local_planning_action_name);
117 if (!local_planner_action_client_->wait_for_action_server(2s))
119 RCLCPP_ERROR(LOGGER,
"Local planner action server not available after waiting");
124 std::string global_planning_action_name = this->declare_parameter<std::string>(
"global_planning_action_name",
"");
125 this->get_parameter<std::string>(
"global_planning_action_name", global_planning_action_name);
126 if (global_planning_action_name.empty())
128 RCLCPP_ERROR(LOGGER,
"global_planning_action_name parameter was not defined");
131 global_planner_action_client_ =
132 rclcpp_action::create_client<moveit_msgs::action::GlobalPlanner>(
this, global_planning_action_name);
133 if (!global_planner_action_client_->wait_for_action_server(2s))
135 RCLCPP_ERROR(LOGGER,
"Global planner action server not available after waiting");
140 std::string hybrid_planning_action_name = this->declare_parameter<std::string>(
"hybrid_planning_action_name",
"");
141 this->get_parameter<std::string>(
"hybrid_planning_action_name", hybrid_planning_action_name);
142 if (hybrid_planning_action_name.empty())
144 RCLCPP_ERROR(LOGGER,
"hybrid_planning_action_name parameter was not defined");
147 cb_group_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
148 hybrid_planning_request_server_ = rclcpp_action::create_server<moveit_msgs::action::HybridPlanner>(
149 this->get_node_base_interface(), this->get_node_clock_interface(), this->get_node_logging_interface(),
150 this->get_node_waitables_interface(), hybrid_planning_action_name,
152 [](
const rclcpp_action::GoalUUID& ,
153 const std::shared_ptr<const moveit_msgs::action::HybridPlanner::Goal>& ) {
154 RCLCPP_INFO(LOGGER,
"Received goal request");
155 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
158 [
this](
const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanner>>& ) {
160 RCLCPP_INFO(LOGGER,
"Received request to cancel goal");
161 return rclcpp_action::CancelResponse::ACCEPT;
164 [
this](std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanner>> goal_handle) {
166 if (long_callback_thread_.joinable())
172 rcl_action_server_get_default_options(), cb_group_);
175 global_solution_sub_ = create_subscription<moveit_msgs::msg::MotionPlanResponse>(
176 "global_trajectory", rclcpp::SystemDefaultsQoS(),
177 [
this](
const moveit_msgs::msg::MotionPlanResponse::ConstSharedPtr& ) {
180 if (reaction_result.
error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
182 auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
183 result->error_code.val = reaction_result.error_code.val;
184 result->error_message = reaction_result.error_message;
185 hybrid_planning_goal_handle_->abort(result);
186 RCLCPP_ERROR(LOGGER,
"Hybrid Planning Manager failed to react to '%s'", reaction_result.event.c_str());
195 stop_hybrid_planning_ =
true;
197 local_planner_action_client_->async_cancel_all_goals();
199 global_planner_action_client_->async_cancel_all_goals();
200 if (long_callback_thread_.joinable())
202 long_callback_thread_.join();
207 std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::HybridPlanner>> goal_handle)
210 stop_hybrid_planning_ =
false;
213 hybrid_planning_goal_handle_ = std::move(goal_handle);
218 if (reaction_result.
error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
220 auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
221 result->error_code.val = reaction_result.
error_code.val;
223 hybrid_planning_goal_handle_->abort(result);
224 RCLCPP_ERROR_STREAM(LOGGER,
"Hybrid Planning Manager failed to react to " << reaction_result.
event);
230 auto global_goal_options = rclcpp_action::Client<moveit_msgs::action::GlobalPlanner>::SendGoalOptions();
233 global_goal_options.goal_response_callback =
234 [
this](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::GlobalPlanner>::SharedPtr& goal_handle) {
235 auto planning_progress = std::make_shared<moveit_msgs::action::HybridPlanner::Feedback>();
236 auto& feedback = planning_progress->feedback;
239 feedback =
"Global goal was rejected by server";
243 feedback =
"Global goal accepted by server";
245 hybrid_planning_goal_handle_->publish_feedback(planning_progress);
248 global_goal_options.result_callback =
249 [
this](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::GlobalPlanner>::WrappedResult& global_result) {
253 switch (global_result.code)
255 case rclcpp_action::ResultCode::SUCCEEDED:
258 case rclcpp_action::ResultCode::CANCELED:
261 case rclcpp_action::ResultCode::ABORTED:
268 if (reaction_result.
error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
270 auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
271 result->error_code.val = reaction_result.
error_code.val;
274 hybrid_planning_goal_handle_->abort(result);
275 RCLCPP_ERROR(LOGGER,
"Hybrid Planning Manager failed to react to '%s'", reaction_result.
event.c_str());
280 auto global_goal_msg = moveit_msgs::action::GlobalPlanner::Goal();
281 global_goal_msg.motion_sequence =
282 (hybrid_planning_goal_handle_->get_goal())->motion_sequence;
283 global_goal_msg.planning_group = (hybrid_planning_goal_handle_->get_goal())->planning_group;
285 if (stop_hybrid_planning_)
291 auto goal_handle_future = global_planner_action_client_->async_send_goal(global_goal_msg, global_goal_options);
298 auto local_goal_msg = moveit_msgs::action::LocalPlanner::Goal();
299 auto local_goal_options = rclcpp_action::Client<moveit_msgs::action::LocalPlanner>::SendGoalOptions();
300 rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr goal_handle;
303 local_goal_options.goal_response_callback =
304 [
this](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr& goal_handle) {
305 auto planning_progress = std::make_shared<moveit_msgs::action::HybridPlanner::Feedback>();
306 auto& feedback = planning_progress->feedback;
309 feedback =
"Local goal was rejected by server";
313 feedback =
"Local goal accepted by server";
315 hybrid_planning_goal_handle_->publish_feedback(planning_progress);
319 local_goal_options.feedback_callback =
320 [
this](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr& ,
321 const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Feedback>& local_planner_feedback) {
323 ReactionResult reaction_result = planner_logic_instance_->react(local_planner_feedback->feedback);
324 if (reaction_result.
error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
326 auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
327 result->error_code.val = reaction_result.
error_code.val;
329 hybrid_planning_goal_handle_->abort(result);
330 RCLCPP_ERROR(LOGGER,
"Hybrid Planning Manager failed to react to '%s'", reaction_result.
event.c_str());
335 local_goal_options.result_callback =
336 [
this](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::WrappedResult& local_result) {
340 switch (local_result.code)
342 case rclcpp_action::ResultCode::SUCCEEDED:
345 case rclcpp_action::ResultCode::CANCELED:
348 case rclcpp_action::ResultCode::ABORTED:
355 if (reaction_result.
error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
357 const moveit_msgs::action::HybridPlanner::Result result([reaction_result]() {
358 moveit_msgs::action::HybridPlanner::Result result;
359 result.error_code.val = reaction_result.
error_code.val;
363 hybrid_planning_goal_handle_->abort(std::make_shared<moveit_msgs::action::HybridPlanner::Result>(result));
364 RCLCPP_ERROR_STREAM(LOGGER,
"Hybrid Planning Manager failed to react to " << reaction_result.
event);
368 if (stop_hybrid_planning_)
374 auto goal_handle_future = local_planner_action_client_->async_send_goal(local_goal_msg, local_goal_options);
381 auto result = std::make_shared<moveit_msgs::action::HybridPlanner::Result>();
384 result->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
385 hybrid_planning_goal_handle_->succeed(result);
389 result->error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
390 hybrid_planning_goal_handle_->abort(result);
396 #include <rclcpp_components/register_node_macro.hpp>
HybridPlanningManager(const rclcpp::NodeOptions &options)
Constructor.
void cancelHybridManagerGoals() noexcept
std::shared_ptr< HybridPlanningManager > shared_from_this()
void sendHybridPlanningResponse(bool success)
void executeHybridPlannerGoal(std::shared_ptr< rclcpp_action::ServerGoalHandle< moveit_msgs::action::HybridPlanner >> goal_handle)
bool sendLocalPlannerAction()
bool sendGlobalPlannerAction()
@ GLOBAL_SOLUTION_AVAILABLE
@ GLOBAL_PLANNING_ACTION_SUCCESSFUL
@ GLOBAL_PLANNING_ACTION_ABORTED
@ HYBRID_PLANNING_REQUEST_RECEIVED
@ LOCAL_PLANNING_ACTION_SUCCESSFUL
@ LOCAL_PLANNING_ACTION_ABORTED
@ GLOBAL_PLANNING_ACTION_CANCELED
@ LOCAL_PLANNING_ACTION_CANCELED
const rclcpp::Logger LOGGER
MoveItErrorCode error_code
std::string error_message