diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index 6ce3f14f542f9..c82ff91f9ae7a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -73,6 +73,17 @@ class AvoidanceModule : public SceneModuleInterface } void setParameters(const AvoidanceParameters & parameters); + void lockRTCCommand() override + { + rtc_interface_left_.lockCommandUpdate(); + rtc_interface_right_.lockCommandUpdate(); + } + + void unlockRTCCommand() override + { + rtc_interface_left_.unlockCommandUpdate(); + rtc_interface_right_.unlockCommandUpdate(); + } private: AvoidanceParameters parameters_; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp index 8b06b5dc75820..9688f0426a004 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/lane_change_module.hpp @@ -109,6 +109,17 @@ class LaneChangeModule : public SceneModuleInterface } void setParameters(const LaneChangeParameters & parameters); + void lockRTCCommand() override + { + rtc_interface_left_.lockCommandUpdate(); + rtc_interface_right_.lockCommandUpdate(); + } + + void unlockRTCCommand() override + { + rtc_interface_left_.unlockCommandUpdate(); + rtc_interface_right_.unlockCommandUpdate(); + } private: LaneChangeParameters parameters_; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp index 22784545d10a0..e78b7f5741311 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp @@ -236,6 +236,22 @@ class SceneModuleInterface } bool isWaitingApproval() const { return is_waiting_approval_; } + virtual void lockRTCCommand() + { + if (!rtc_interface_ptr_) { + return; + } + rtc_interface_ptr_->lockCommandUpdate(); + } + + virtual void unlockRTCCommand() + { + if (!rtc_interface_ptr_) { + return; + } + rtc_interface_ptr_->unlockCommandUpdate(); + } + private: std::string name_; rclcpp::Logger logger_; diff --git a/planning/behavior_path_planner/src/scene_module/scene_module_bt_node_interface.cpp b/planning/behavior_path_planner/src/scene_module/scene_module_bt_node_interface.cpp index cef1669005d74..ebbd418efdd20 100644 --- a/planning/behavior_path_planner/src/scene_module/scene_module_bt_node_interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/scene_module_bt_node_interface.cpp @@ -50,6 +50,7 @@ BT::NodeStatus SceneModuleBTNodeInterface::tick() const bool is_waiting_approval = !scene_module_->isActivated(); if (is_waiting_approval && !is_lane_following) { + scene_module_->lockRTCCommand(); try { // NOTE: Since BehaviorTreeCpp has an issue to shadow the exception reason thrown // in the TreeNode, catch and display it here until the issue is fixed. @@ -64,12 +65,14 @@ BT::NodeStatus SceneModuleBTNodeInterface::tick() scene_module_->getLogger(), "behavior module has failed with exception: " << e.what()); // std::exit(EXIT_FAILURE); // TODO(Horibe) do appropriate handing } + scene_module_->unlockRTCCommand(); return BT::NodeStatus::SUCCESS; } while (rclcpp::ok()) { // NOTE: Since BehaviorTreeCpp has an issue to shadow the exception reason thrown // in the TreeNode, catch and display it here until the issue is fixed. + scene_module_->lockRTCCommand(); try { auto res = setOutput("output", scene_module_->run()); if (!res) { @@ -94,6 +97,7 @@ BT::NodeStatus SceneModuleBTNodeInterface::tick() break; } + scene_module_->unlockRTCCommand(); setStatusRunningAndYield(); } diff --git a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp index 6e3139254323d..be4dc2860db21 100644 --- a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp +++ b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp @@ -52,12 +52,18 @@ class RTCInterface void clearCooperateStatus(); bool isActivated(const UUID & uuid); bool isRegistered(const UUID & uuid); + void lockCommandUpdate(); + void unlockCommandUpdate(); private: void onCooperateCommandService( const CooperateCommands::Request::SharedPtr request, const CooperateCommands::Response::SharedPtr responses); + std::vector validateCooperateCommands( + const std::vector & commands); + void updateCooperateCommandStatus(const std::vector & commands); rclcpp::Logger getLogger() const; + bool isLocked() const; rclcpp::Publisher::SharedPtr pub_statuses_; rclcpp::Service::SharedPtr srv_commands_; @@ -67,6 +73,9 @@ class RTCInterface rclcpp::Logger logger_; Module module_; CooperateStatusArray registered_status_; + std::vector stored_commands_; + bool is_auto_mode_; + bool is_locked_; }; } // namespace rtc_interface diff --git a/planning/rtc_interface/src/rtc_interface.cpp b/planning/rtc_interface/src/rtc_interface.cpp index 3285a547a1a6f..b0fa8e4295e59 100644 --- a/planning/rtc_interface/src/rtc_interface.cpp +++ b/planning/rtc_interface/src/rtc_interface.cpp @@ -69,7 +69,9 @@ Module getModuleType(const std::string & module_name) namespace rtc_interface { RTCInterface::RTCInterface(rclcpp::Node * node, const std::string & name) -: logger_{node->get_logger().get_child("RTCInterface[" + name + "]")} +: logger_{node->get_logger().get_child("RTCInterface[" + name + "]")}, + is_auto_mode_{false}, + is_locked_{false} { using std::placeholders::_1; using std::placeholders::_2; @@ -101,7 +103,23 @@ void RTCInterface::onCooperateCommandService( const CooperateCommands::Response::SharedPtr responses) { std::lock_guard lock(mutex_); - for (const auto & command : request->commands) { + + responses->responses = validateCooperateCommands(request->commands); + + if (isLocked()) { + stored_commands_ = request->commands; + return; + } + + updateCooperateCommandStatus(request->commands); +} + +std::vector RTCInterface::validateCooperateCommands( + const std::vector & commands) +{ + std::vector responses; + + for (const auto & command : commands) { CooperateResponse response; response.uuid = command.uuid; response.module = command.module; @@ -109,18 +127,32 @@ void RTCInterface::onCooperateCommandService( const auto itr = std::find_if( registered_status_.statuses.begin(), registered_status_.statuses.end(), [command](auto & s) { return s.uuid == command.uuid; }); - - // Update command if the command has been already received if (itr != registered_status_.statuses.end()) { - itr->command_status = command.command; response.success = true; } else { RCLCPP_WARN_STREAM( - getLogger(), "[onCooperateCommandService] uuid : " << to_string(command.uuid) + getLogger(), "[validateCooperateCommands] uuid : " << to_string(command.uuid) << " is not found." << std::endl); response.success = false; } - responses->responses.push_back(response); + responses.push_back(response); + } + + return responses; +} + +void RTCInterface::updateCooperateCommandStatus(const std::vector & commands) +{ + for (const auto & command : commands) { + const auto itr = std::find_if( + registered_status_.statuses.begin(), registered_status_.statuses.end(), + [command](auto & s) { return s.uuid == command.uuid; }); + + // Update command if the command has been already received + if (itr != registered_status_.statuses.end()) { + itr->command_status = command.command; + is_auto_mode_ = false; + } } } @@ -201,6 +233,16 @@ bool RTCInterface::isRegistered(const UUID & uuid) return itr != registered_status_.statuses.end(); } +void RTCInterface::lockCommandUpdate() { is_locked_ = true; } + +void RTCInterface::unlockCommandUpdate() +{ + is_locked_ = false; + updateCooperateCommandStatus(stored_commands_); +} + rclcpp::Logger RTCInterface::getLogger() const { return logger_; } +bool RTCInterface::isLocked() const { return is_locked_; } + } // namespace rtc_interface