From ad5031863a94c9899dadfd81f779aa984413004f Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Wed, 8 Mar 2023 19:20:00 +0900 Subject: [PATCH] fix(rtc_interface): fix initial auto mode Signed-off-by: Fumiya Watanabe --- .../rtc_interface/include/rtc_interface/rtc_interface.hpp | 2 +- planning/rtc_interface/src/rtc_interface.cpp | 8 +++----- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp index 4763fcc25f256..821dd4a6e6b1f 100644 --- a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp +++ b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp @@ -81,7 +81,7 @@ class RTCInterface Module module_; CooperateStatusArray registered_status_; std::vector stored_commands_; - bool is_auto_mode_; + bool is_auto_mode_init_; bool is_locked_; std::string cooperate_status_namespace_ = "/planning/cooperate_status"; diff --git a/planning/rtc_interface/src/rtc_interface.cpp b/planning/rtc_interface/src/rtc_interface.cpp index be8da279ec4fa..11230b3013ceb 100644 --- a/planning/rtc_interface/src/rtc_interface.cpp +++ b/planning/rtc_interface/src/rtc_interface.cpp @@ -74,7 +74,7 @@ namespace rtc_interface { RTCInterface::RTCInterface(rclcpp::Node * node, const std::string & name) : logger_{node->get_logger().get_child("RTCInterface[" + name + "]")}, - is_auto_mode_{false}, + is_auto_mode_init_{false}, is_locked_{false} { using std::placeholders::_1; @@ -160,7 +160,6 @@ void RTCInterface::updateCooperateCommandStatus(const std::vectorcommand_status = command.command; itr->auto_mode = false; - is_auto_mode_ = false; } } } @@ -169,7 +168,7 @@ void RTCInterface::onAutoModeService( const AutoMode::Request::SharedPtr request, const AutoMode::Response::SharedPtr response) { std::lock_guard lock(mutex_); - is_auto_mode_ = request->enable; + is_auto_mode_init_ = request->enable; for (auto & status : registered_status_.statuses) { status.auto_mode = request->enable; } @@ -196,7 +195,7 @@ void RTCInterface::updateCooperateStatus( status.command_status.type = Command::DEACTIVATE; status.start_distance = start_distance; status.finish_distance = finish_distance; - status.auto_mode = is_auto_mode_; + status.auto_mode = is_auto_mode_init_; registered_status_.statuses.push_back(status); return; } @@ -206,7 +205,6 @@ void RTCInterface::updateCooperateStatus( itr->safe = safe; itr->start_distance = start_distance; itr->finish_distance = finish_distance; - itr->auto_mode = is_auto_mode_; } void RTCInterface::removeCooperateStatus(const UUID & uuid)