From 57fcf94fee1762b33824ebfa19e3da6701adea01 Mon Sep 17 00:00:00 2001 From: Dawid Moszynski Date: Fri, 3 Jan 2025 12:27:32 +0100 Subject: [PATCH] ref(random_test_runner): adapt to getEntity changes - return reference --- .../random_test_runner/test_executor.hpp | 30 +++++++++---------- .../test/test_test_executor.cpp | 16 +++++----- 2 files changed, 22 insertions(+), 24 deletions(-) diff --git a/test_runner/random_test_runner/include/random_test_runner/test_executor.hpp b/test_runner/random_test_runner/include/random_test_runner/test_executor.hpp index 146dad86889..8f1bde68670 100644 --- a/test_runner/random_test_runner/include/random_test_runner/test_executor.hpp +++ b/test_runner/random_test_runner/include/random_test_runner/test_executor.hpp @@ -92,9 +92,9 @@ class TestExecutor ego_name_, ego_start_canonicalized_lanelet_pose.value(), getVehicleParameters(), traffic_simulator::VehicleBehavior::autoware(), "lexus_rx450h"); - auto ego_entity = api_->getEgoEntity(ego_name_); + auto & ego_entity = api_->getEgoEntity(ego_name_); - ego_entity->setStatus( + ego_entity.setStatus( ego_start_canonicalized_lanelet_pose.value(), traffic_simulator::helper::constructActionStatus()); @@ -122,15 +122,15 @@ class TestExecutor return configuration; }()); - ego_entity->template setParameter("allow_goal_modification", true); + ego_entity.template setParameter("allow_goal_modification", true); } // XXX dirty hack: wait for autoware system to launch // ugly but helps for now std::this_thread::sleep_for(std::chrono::milliseconds{5000}); - ego_entity->requestAssignRoute(std::vector({test_description_.ego_goal_pose})); - ego_entity->engage(); + ego_entity.requestAssignRoute(std::vector({test_description_.ego_goal_pose})); + ego_entity.engage(); goal_reached_metric_.setGoal(test_description_.ego_goal_pose); @@ -149,13 +149,13 @@ class TestExecutor npc_descr.name, npc_start_canonicalized_lanelet_pose.value(), getVehicleParameters(), traffic_simulator::VehicleBehavior::defaultBehavior(), "taxi"); - auto entity = api_->getEntity(npc_descr.name); + auto & entity = api_->getEntity(npc_descr.name); - entity->setStatus( + entity.setStatus( npc_start_canonicalized_lanelet_pose.value(), traffic_simulator::helper::constructActionStatus(npc_descr.speed)); - entity->requestSpeedChange(npc_descr.speed, true); + entity.requestSpeedChange(npc_descr.speed, true); } } } @@ -166,9 +166,9 @@ class TestExecutor { executeWithErrorHandling([this]() { if (!api_->isNpcLogicStarted()) { - if (api_->isAnyEgoSpawned()) { - auto ego_entity = api_->getEgoEntity(ego_name_); - if (ego_entity->isEngageable()) { + if (api_->isEntityExist(ego_name_)) { + auto & ego_entity = api_->getEgoEntity(ego_name_); + if (ego_entity.isEngageable()) { api_->startNpcLogic(); } } else { @@ -180,14 +180,14 @@ class TestExecutor if (!std::isnan(current_time)) { if (goal_reached_metric_.isGoalReached( - api_->getEntity(ego_name_)->getCanonicalizedStatus())) { + api_->getEntity(ego_name_).getCanonicalizedStatus())) { scenario_completed_ = true; } bool timeout_reached = current_time >= test_timeout_; if (timeout_reached) { if (!goal_reached_metric_.isGoalReached( - api_->getEntity(ego_name_)->getCanonicalizedStatus())) { + api_->getEntity(ego_name_).getCanonicalizedStatus())) { RCLCPP_INFO(logger_, "Timeout reached"); error_reporter_.reportTimeout(); } @@ -208,10 +208,10 @@ class TestExecutor } if (almost_standstill_metric_.isAlmostStandingStill( - api_->getEntity(ego_name_)->getCanonicalizedStatus())) { + api_->getEntity(ego_name_).getCanonicalizedStatus())) { RCLCPP_INFO(logger_, "Standstill duration exceeded"); if (goal_reached_metric_.isGoalReached( - api_->getEntity(ego_name_)->getCanonicalizedStatus())) { + api_->getEntity(ego_name_).getCanonicalizedStatus())) { RCLCPP_INFO(logger_, "Goal reached, standstill expected"); } else { error_reporter_.reportStandStill(); diff --git a/test_runner/random_test_runner/test/test_test_executor.cpp b/test_runner/random_test_runner/test/test_test_executor.cpp index 6d51bb3080e..4f0503afe95 100644 --- a/test_runner/random_test_runner/test/test_test_executor.cpp +++ b/test_runner/random_test_runner/test/test_test_executor.cpp @@ -121,7 +121,6 @@ class MockTrafficSimulatorAPI (const std::string &, const traffic_simulator::CanonicalizedLaneletPose &, const traffic_simulator_msgs::msg::VehicleParameters &), ()); - MOCK_METHOD(bool, isAnyEgoSpawned, (), ()); MOCK_METHOD(bool, isNpcLogicStarted, (), ()); MOCK_METHOD(void, startNpcLogic, (), ()); MOCK_METHOD(bool, despawn, (const std::string), ()); @@ -133,21 +132,20 @@ class MockTrafficSimulatorAPI MOCK_METHOD(bool, isEntityExist, (const std::string &), ()); MOCK_METHOD(bool, checkCollision, (const std::string &, const std::string &), ()); - auto getEntity(const std::string & name) const - -> std::shared_ptr<::testing::StrictMock> + auto getEntity(const std::string & name) -> ::testing::StrictMock & { getEntityMock(name); if (name == ego_name_) { - return ego_entity_; + return *ego_entity_; + } else { + throw std::runtime_error("Entity " + name + " does not exist"); } - return std::make_shared<::testing::StrictMock>(); } - auto getEgoEntity(const std::string & name) const - -> std::shared_ptr<::testing::StrictMock> + auto getEgoEntity(const std::string & name) -> ::testing::StrictMock & { getEgoEntityMock(name); - return ego_entity_; + return *ego_entity_; } /// Real member function required for the canonicalization of the lanelet pose in TestExecutor.InitializeWithNoNPCs test @@ -229,7 +227,7 @@ TEST(TestExecutor, UpdateNoNPCs) .Times(1) .InSequence(sequence) .WillOnce(::testing::Return(false)); - EXPECT_CALL(*MockAPI, isAnyEgoSpawned) + EXPECT_CALL(*MockAPI, isEntityExist) .Times(1) .InSequence(sequence) .WillOnce(::testing::Return(false));