|
| 1 | +// Copyright 2023 Tier IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include <emergency_goal_manager_core.hpp> |
| 16 | + |
| 17 | +namespace emergency_goal_manager |
| 18 | +{ |
| 19 | +EmergencyGoalManager::EmergencyGoalManager() : Node("emergency_goal_manager") |
| 20 | +{ |
| 21 | + // Subscriber |
| 22 | + sub_emergency_goals_ = create_subscription<tier4_system_msgs::msg::EmergencyGoalsStamped>( |
| 23 | + "~/input/emergency_goals", rclcpp::QoS{1}, |
| 24 | + std::bind(&EmergencyGoalManager::onEmergencyGoals, this, std::placeholders::_1)); |
| 25 | + sub_emergency_goals_clear_command_ = |
| 26 | + create_subscription<tier4_system_msgs::msg::EmergencyGoalsClearCommand>( |
| 27 | + "~/input/emergency_goals_clear_command", rclcpp::QoS{1}, |
| 28 | + std::bind(&EmergencyGoalManager::onEmergencyGoalsClearCommand, this, std::placeholders::_1)); |
| 29 | + |
| 30 | + // Client |
| 31 | + client_set_mrm_route_points_callback_group_ = |
| 32 | + create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); |
| 33 | + client_set_mrm_route_points_ = create_client<SetRoutePoints>( |
| 34 | + "/planning/mission_planning/mission_planner/srv/set_mrm_route", |
| 35 | + rmw_qos_profile_services_default, client_set_mrm_route_points_callback_group_); |
| 36 | + client_clear_mrm_route_callback_group_ = |
| 37 | + create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); |
| 38 | + client_clear_mrm_route_ = create_client<ClearRoute>( |
| 39 | + "/planning/mission_planning/mission_planner/srv/clear_mrm_route", |
| 40 | + rmw_qos_profile_services_default, client_clear_mrm_route_callback_group_); |
| 41 | + |
| 42 | + // Initialize |
| 43 | + while (!client_set_mrm_route_points_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) { |
| 44 | + } |
| 45 | + while (!client_clear_mrm_route_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) { |
| 46 | + } |
| 47 | +} |
| 48 | + |
| 49 | +void EmergencyGoalManager::onEmergencyGoals( |
| 50 | + const tier4_system_msgs::msg::EmergencyGoalsStamped::SharedPtr msg) |
| 51 | +{ |
| 52 | + std::queue<geometry_msgs::msg::Pose> emergency_goals_queue; |
| 53 | + for (const auto & goal : msg->goals) { |
| 54 | + emergency_goals_queue.push(goal); |
| 55 | + } |
| 56 | + emergency_goals_map_.emplace(msg->sender, emergency_goals_queue); |
| 57 | + |
| 58 | + callSetMrmRoutePoints(); |
| 59 | +} |
| 60 | + |
| 61 | +void EmergencyGoalManager::onEmergencyGoalsClearCommand( |
| 62 | + const tier4_system_msgs::msg::EmergencyGoalsClearCommand::SharedPtr msg) |
| 63 | +{ |
| 64 | + if (emergency_goals_map_.count(msg->sender) == 0) { |
| 65 | + RCLCPP_WARN(get_logger(), "Emergency goals from %s is empty.", msg->sender.c_str()); |
| 66 | + } |
| 67 | + |
| 68 | + emergency_goals_map_.erase(msg->sender); |
| 69 | + |
| 70 | + if (emergency_goals_map_.empty()) { |
| 71 | + callClearMrmRoute(); |
| 72 | + } else { |
| 73 | + callSetMrmRoutePoints(); |
| 74 | + } |
| 75 | +} |
| 76 | + |
| 77 | +void EmergencyGoalManager::callSetMrmRoutePoints() |
| 78 | +{ |
| 79 | + auto request = std::make_shared<SetRoutePoints::Request>(); |
| 80 | + request->header.frame_id = "map"; |
| 81 | + request->header.stamp = this->now(); |
| 82 | + request->option.allow_goal_modification = true; |
| 83 | + |
| 84 | + while (!emergency_goals_map_.empty()) { |
| 85 | + // TODO(Makoto Kurihara): set goals with the highest priority |
| 86 | + auto goals = emergency_goals_map_.begin(); |
| 87 | + |
| 88 | + auto sender = goals->first; |
| 89 | + auto & goal_queue = goals->second; |
| 90 | + if (goal_queue.empty()) { |
| 91 | + emergency_goals_map_.erase(sender); |
| 92 | + continue; |
| 93 | + } |
| 94 | + |
| 95 | + request->goal = goal_queue.front(); |
| 96 | + goal_queue.pop(); |
| 97 | + |
| 98 | + auto future = client_set_mrm_route_points_->async_send_request(request); |
| 99 | + const auto duration = std::chrono::duration<double, std::ratio<1>>(10); |
| 100 | + if (future.wait_for(duration) != std::future_status::ready) { |
| 101 | + RCLCPP_WARN(get_logger(), "MRM Route service timeout."); |
| 102 | + continue; |
| 103 | + } else { |
| 104 | + if (future.get()->status.success) { |
| 105 | + RCLCPP_INFO(get_logger(), "MRM Route has been successfully sent."); |
| 106 | + return; |
| 107 | + } else { |
| 108 | + RCLCPP_WARN(get_logger(), "MRM Route service has failed."); |
| 109 | + std::this_thread::sleep_for(std::chrono::seconds(1)); |
| 110 | + continue; |
| 111 | + } |
| 112 | + } |
| 113 | + } |
| 114 | + |
| 115 | + callClearMrmRoute(); |
| 116 | +} |
| 117 | + |
| 118 | +void EmergencyGoalManager::callClearMrmRoute() |
| 119 | +{ |
| 120 | + auto request = std::make_shared<ClearRoute::Request>(); |
| 121 | + const auto duration = std::chrono::duration<double, std::ratio<1>>(10); |
| 122 | + const auto start_time = std::chrono::steady_clock::now(); |
| 123 | + |
| 124 | + while (rclcpp::ok()) { |
| 125 | + if (std::chrono::steady_clock::now() - start_time > duration) { |
| 126 | + RCLCPP_WARN(get_logger(), "Clear MRM Route operation timeout."); |
| 127 | + return; |
| 128 | + } |
| 129 | + |
| 130 | + auto future = client_clear_mrm_route_->async_send_request(request); |
| 131 | + if (future.wait_for(duration) != std::future_status::ready) { |
| 132 | + RCLCPP_WARN(get_logger(), "Clear MRM Route service timeout."); |
| 133 | + return; |
| 134 | + } else { |
| 135 | + if (future.get()->status.success) { |
| 136 | + RCLCPP_INFO(get_logger(), "Clear MRM Route has been successfully sent."); |
| 137 | + return; |
| 138 | + } else { |
| 139 | + std::this_thread::sleep_for(std::chrono::seconds(1)); |
| 140 | + RCLCPP_WARN(get_logger(), "Clear MRM Route has failed."); |
| 141 | + continue; |
| 142 | + } |
| 143 | + } |
| 144 | + } |
| 145 | +} |
| 146 | +} // namespace emergency_goal_manager |
0 commit comments