diff --git a/planning/autoware_rtc_interface/CMakeLists.txt b/planning/autoware_rtc_interface/CMakeLists.txt index cd36121e6aee8..9cb83577348d5 100644 --- a/planning/autoware_rtc_interface/CMakeLists.txt +++ b/planning/autoware_rtc_interface/CMakeLists.txt @@ -1,6 +1,9 @@ cmake_minimum_required(VERSION 3.5) project(autoware_rtc_interface) +find_package(autoware_cmake REQUIRED) +autoware_package() + ### Compile options if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 17) @@ -18,8 +21,12 @@ ament_auto_add_library(autoware_rtc_interface SHARED # Test if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + test/test_rtc_interface.cpp + ) + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) endif() ament_auto_package() diff --git a/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp b/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp index 705395c2b1741..4d7e2aec46e33 100644 --- a/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp +++ b/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp @@ -54,7 +54,7 @@ class RTCInterface void publishCooperateStatus(const rclcpp::Time & stamp); void updateCooperateStatus( const UUID & uuid, const bool safe, const uint8_t state, const double start_distance, - const double finish_distance, const rclcpp::Time & stamp); + const double finish_distance, const rclcpp::Time & stamp, const bool requested = false); void removeCooperateStatus(const UUID & uuid); void removeExpiredCooperateStatus(); void clearCooperateStatus(); @@ -103,6 +103,9 @@ class RTCInterface std::string enable_auto_mode_namespace_ = "/planning/enable_auto_mode"; mutable std::mutex mutex_; + +public: + friend class RTCInterfaceTest; }; } // namespace autoware::rtc_interface diff --git a/planning/autoware_rtc_interface/package.xml b/planning/autoware_rtc_interface/package.xml index d08467d8f15a9..8ac9d32ba9b04 100644 --- a/planning/autoware_rtc_interface/package.xml +++ b/planning/autoware_rtc_interface/package.xml @@ -15,12 +15,15 @@ ament_cmake_auto + autoware_universe_utils rclcpp tier4_rtc_msgs unique_identifier_msgs + ament_cmake_ros ament_lint_auto autoware_lint_common + autoware_test_utils ament_cmake diff --git a/planning/autoware_rtc_interface/src/rtc_interface.cpp b/planning/autoware_rtc_interface/src/rtc_interface.cpp index 25dd34332f684..71a197ccb93b4 100644 --- a/planning/autoware_rtc_interface/src/rtc_interface.cpp +++ b/planning/autoware_rtc_interface/src/rtc_interface.cpp @@ -14,8 +14,6 @@ #include "autoware/rtc_interface/rtc_interface.hpp" -#include - namespace { using tier4_rtc_msgs::msg::Module; @@ -33,7 +31,8 @@ std::string command_to_string(const uint8_t type) { if (type == tier4_rtc_msgs::msg::Command::ACTIVATE) { return "ACTIVATE"; - } else if (type == tier4_rtc_msgs::msg::Command::DEACTIVATE) { + } + if (type == tier4_rtc_msgs::msg::Command::DEACTIVATE) { return "DEACTIVATE"; } @@ -44,13 +43,17 @@ std::string state_to_string(const uint8_t type) { if (type == tier4_rtc_msgs::msg::State::WAITING_FOR_EXECUTION) { return "WAITING_FOR_EXECUTION"; - } else if (type == tier4_rtc_msgs::msg::State::RUNNING) { + } + if (type == tier4_rtc_msgs::msg::State::RUNNING) { return "RUNNING"; - } else if (type == tier4_rtc_msgs::msg::State::ABORTING) { + } + if (type == tier4_rtc_msgs::msg::State::ABORTING) { return "ABORTING"; - } else if (type == tier4_rtc_msgs::msg::State::SUCCEEDED) { + } + if (type == tier4_rtc_msgs::msg::State::SUCCEEDED) { return "SUCCEEDED"; - } else if (type == tier4_rtc_msgs::msg::State::FAILED) { + } + if (type == tier4_rtc_msgs::msg::State::FAILED) { return "FAILED"; } @@ -242,7 +245,7 @@ void RTCInterface::onTimer() void RTCInterface::updateCooperateStatus( const UUID & uuid, const bool safe, const uint8_t state, const double start_distance, - const double finish_distance, const rclcpp::Time & stamp) + const double finish_distance, const rclcpp::Time & stamp, const bool requested) { std::lock_guard lock(mutex_); // Find registered status which has same uuid @@ -257,6 +260,7 @@ void RTCInterface::updateCooperateStatus( status.uuid = uuid; status.module = module_; status.safe = safe; + status.requested = requested; status.command_status.type = Command::DEACTIVATE; status.state.type = State::WAITING_FOR_EXECUTION; status.start_distance = start_distance; @@ -370,11 +374,10 @@ bool RTCInterface::isActivated(const UUID & uuid) const if (itr->state.type == State::FAILED || itr->state.type == State::SUCCEEDED) { return false; } - if (itr->auto_mode) { + if (itr->auto_mode && !itr->requested) { return itr->safe; - } else { - return itr->command_status.type == Command::ACTIVATE; } + return itr->command_status.type == Command::ACTIVATE; } RCLCPP_WARN_STREAM( @@ -393,11 +396,8 @@ bool RTCInterface::isForceActivated(const UUID & uuid) const if (itr->state.type != State::WAITING_FOR_EXECUTION && itr->state.type != State::RUNNING) { return false; } - if (itr->command_status.type == Command::ACTIVATE && !itr->safe) { - return true; - } else { - return false; - } + if (itr->command_status.type != Command::ACTIVATE) return false; + return !itr->safe || itr->requested; } RCLCPP_WARN_STREAM( @@ -417,11 +417,7 @@ bool RTCInterface::isForceDeactivated(const UUID & uuid) const if (itr->state.type != State::RUNNING) { return false; } - if (itr->command_status.type == Command::DEACTIVATE && itr->safe && !itr->auto_mode) { - return true; - } else { - return false; - } + return itr->command_status.type == Command::DEACTIVATE && itr->safe && !itr->auto_mode; } RCLCPP_WARN_STREAM( diff --git a/planning/autoware_rtc_interface/test/test_rtc_interface.cpp b/planning/autoware_rtc_interface/test/test_rtc_interface.cpp new file mode 100644 index 0000000000000..84c6dbd343ea2 --- /dev/null +++ b/planning/autoware_rtc_interface/test/test_rtc_interface.cpp @@ -0,0 +1,174 @@ +// Copyright 2024 TIER IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/rtc_interface/rtc_interface.hpp" + +#include +#include +#include + +#include "tier4_rtc_msgs/msg/detail/command__struct.hpp" + +#include + +using tier4_rtc_msgs::msg::State; + +namespace autoware::rtc_interface +{ +class RTCInterfaceTest : public ::testing::Test +{ +public: + void update_cooperate_command_status(const std::vector & commands) + { + rtc_interface_->updateCooperateCommandStatus(commands); + } + + std::vector get_stored_command() { return rtc_interface_->stored_commands_; } + +protected: + rclcpp::Node::SharedPtr node; + std::shared_ptr rtc_interface_; + + void SetUp() override + { + rclcpp::init(0, nullptr); + node = std::make_shared("rtc_interface_node_test"); + rtc_interface_ = + std::make_shared(node.get(), "TestRTC", false); + } + + void TearDown() override { rclcpp::shutdown(); } +}; + +TEST_F(RTCInterfaceTest, uuid_to_string) +{ + auto uuid = autoware::universe_utils::generateUUID(); + rclcpp::Time stamp(1.0, 0); + + // Condition: no registered uuid + EXPECT_FALSE(rtc_interface_->isRegistered(uuid)); + EXPECT_FALSE(rtc_interface_->isActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceDeactivated(uuid)); + EXPECT_TRUE(rtc_interface_->isRTCEnabled(uuid)); + EXPECT_TRUE(rtc_interface_->isTerminated(uuid)); + + // Condition: register uuid with WAITING_FOR_EXECUTION + rtc_interface_->updateCooperateStatus( + uuid, true, State::WAITING_FOR_EXECUTION, 10.0, 100.0, stamp); + EXPECT_TRUE(rtc_interface_->isRegistered(uuid)); + EXPECT_TRUE(rtc_interface_->isActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceDeactivated(uuid)); + EXPECT_FALSE(rtc_interface_->isRTCEnabled(uuid)); + EXPECT_FALSE(rtc_interface_->isTerminated(uuid)); + + // Condition: remove registered uuid + rtc_interface_->removeCooperateStatus(uuid); + EXPECT_FALSE(rtc_interface_->isRegistered(uuid)); + + // Condition: register uuid with FAILED (should start with WAITING_FOR_EXECUTION) + rtc_interface_->updateCooperateStatus(uuid, true, State::FAILED, 10.0, 100.0, stamp); + EXPECT_TRUE(rtc_interface_->isRegistered(uuid)); + EXPECT_TRUE(rtc_interface_->isActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceDeactivated(uuid)); + EXPECT_FALSE(rtc_interface_->isRTCEnabled(uuid)); + EXPECT_FALSE(rtc_interface_->isTerminated(uuid)); + + // Condition: update uuid as force activated + std::vector commands; + CooperateCommand command; + command.uuid = uuid; + command.command.type = tier4_rtc_msgs::msg::Command::ACTIVATE; + commands.push_back(command); + rtc_interface_->updateCooperateStatus(uuid, false, State::RUNNING, 10.0, 100.0, stamp); + update_cooperate_command_status(commands); + EXPECT_TRUE(rtc_interface_->isRegistered(uuid)); + EXPECT_TRUE(rtc_interface_->isActivated(uuid)); + EXPECT_TRUE(rtc_interface_->isForceActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceDeactivated(uuid)); + EXPECT_TRUE(rtc_interface_->isRTCEnabled(uuid)); + EXPECT_FALSE(rtc_interface_->isTerminated(uuid)); + + // Condition: terminate uuid by transiting to SUCCEEDED + rtc_interface_->updateCooperateStatus(uuid, false, State::SUCCEEDED, 10.0, 100.0, stamp); + EXPECT_TRUE(rtc_interface_->isRegistered(uuid)); + EXPECT_FALSE(rtc_interface_->isActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceDeactivated(uuid)); + EXPECT_TRUE(rtc_interface_->isRTCEnabled(uuid)); + EXPECT_TRUE(rtc_interface_->isTerminated(uuid)); + + // Condition: clear registered uuid + rtc_interface_->clearCooperateStatus(); + EXPECT_FALSE(rtc_interface_->isRegistered(uuid)); + EXPECT_TRUE(get_stored_command().empty()); + + // Condition: update uuid as force deactivated + commands.front().command.type = tier4_rtc_msgs::msg::Command::DEACTIVATE; + rtc_interface_->updateCooperateStatus( + uuid, true, State::WAITING_FOR_EXECUTION, 10.0, 100.0, stamp); + rtc_interface_->updateCooperateStatus(uuid, true, State::RUNNING, 10.0, 100.0, stamp); + update_cooperate_command_status(commands); + EXPECT_TRUE(rtc_interface_->isRegistered(uuid)); + EXPECT_FALSE(rtc_interface_->isActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceActivated(uuid)); + EXPECT_TRUE(rtc_interface_->isForceDeactivated(uuid)); + EXPECT_TRUE(rtc_interface_->isRTCEnabled(uuid)); + EXPECT_FALSE(rtc_interface_->isTerminated(uuid)); + + // Condition: uuid transiting to ABORTING + rtc_interface_->updateCooperateStatus(uuid, true, State::ABORTING, 10.0, 100.0, stamp); + EXPECT_TRUE(rtc_interface_->isRegistered(uuid)); + EXPECT_FALSE(rtc_interface_->isActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceDeactivated(uuid)); + EXPECT_TRUE(rtc_interface_->isRTCEnabled(uuid)); + EXPECT_FALSE(rtc_interface_->isTerminated(uuid)); + + // Condition: uuid transiting to FAILED + rtc_interface_->updateCooperateStatus(uuid, true, State::FAILED, 10.0, 100.0, stamp); + EXPECT_TRUE(rtc_interface_->isRegistered(uuid)); + EXPECT_FALSE(rtc_interface_->isActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceDeactivated(uuid)); + EXPECT_TRUE(rtc_interface_->isRTCEnabled(uuid)); + EXPECT_TRUE(rtc_interface_->isTerminated(uuid)); + + rtc_interface_->clearCooperateStatus(); + + // Condition: register uuid with request to operator and transit to RUNNING (which shouldn't be + // allowed) + rtc_interface_->updateCooperateStatus( + uuid, true, State::WAITING_FOR_EXECUTION, 10.0, 100.0, stamp, true); + rtc_interface_->updateCooperateStatus(uuid, true, State::RUNNING, 10.0, 100.0, stamp); + EXPECT_TRUE(rtc_interface_->isRegistered(uuid)); + EXPECT_FALSE(rtc_interface_->isActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceDeactivated(uuid)); + EXPECT_FALSE(rtc_interface_->isRTCEnabled(uuid)); + EXPECT_FALSE(rtc_interface_->isTerminated(uuid)); + + // Condition: update uuid cooperate command + commands.front().command.type = tier4_rtc_msgs::msg::Command::ACTIVATE; + update_cooperate_command_status(commands); + EXPECT_TRUE(rtc_interface_->isRegistered(uuid)); + EXPECT_TRUE(rtc_interface_->isActivated(uuid)); + EXPECT_TRUE(rtc_interface_->isForceActivated(uuid)); + EXPECT_FALSE(rtc_interface_->isForceDeactivated(uuid)); + EXPECT_TRUE(rtc_interface_->isRTCEnabled(uuid)); + EXPECT_FALSE(rtc_interface_->isTerminated(uuid)); +} +} // namespace autoware::rtc_interface