diff --git a/mock/cpp_mock_scenarios/src/crosswalk/stop_at_crosswalk.cpp b/mock/cpp_mock_scenarios/src/crosswalk/stop_at_crosswalk.cpp index 3c645ea754d..7e08349f415 100644 --- a/mock/cpp_mock_scenarios/src/crosswalk/stop_at_crosswalk.cpp +++ b/mock/cpp_mock_scenarios/src/crosswalk/stop_at_crosswalk.cpp @@ -40,7 +40,7 @@ class StopAtCrosswalkScenario : public cpp_mock_scenarios::CppScenarioNode { const auto t = api_.getCurrentTime(); // LCOV_EXCL_START - if (api_.isEntitySpawned("bob") && api_.checkCollision("ego", "bob")) { + if (api_.isEntityExist("bob") && api_.checkCollision("ego", "bob")) { stop(cpp_mock_scenarios::Result::FAILURE); } /** diff --git a/mock/cpp_mock_scenarios/src/pedestrian/walk_straight.cpp b/mock/cpp_mock_scenarios/src/pedestrian/walk_straight.cpp index 3ec1dc88d53..fb910e766c9 100644 --- a/mock/cpp_mock_scenarios/src/pedestrian/walk_straight.cpp +++ b/mock/cpp_mock_scenarios/src/pedestrian/walk_straight.cpp @@ -40,7 +40,7 @@ class WalkStraightScenario : public cpp_mock_scenarios::CppScenarioNode { const auto t = api_.getCurrentTime(); // LCOV_EXCL_START - if (api_.isEntitySpawned("bob") && api_.checkCollision("ego", "bob")) { + if (api_.isEntityExist("bob") && api_.checkCollision("ego", "bob")) { stop(cpp_mock_scenarios::Result::FAILURE); } /** diff --git a/mock/cpp_mock_scenarios/src/random_scenario/random001.cpp b/mock/cpp_mock_scenarios/src/random_scenario/random001.cpp index 8023ebc75a6..620f1583bed 100644 --- a/mock/cpp_mock_scenarios/src/random_scenario/random001.cpp +++ b/mock/cpp_mock_scenarios/src/random_scenario/random001.cpp @@ -98,7 +98,7 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode { for (int i = 0; i < params_.random_parameters.crossing_pedestrian.number_of_pedestrian; i++) { std::string entity_name = "pedestrian" + std::to_string(i); - if (api_.isEntitySpawned(entity_name)) { + if (api_.isEntityExist(entity_name)) { api_.despawn(entity_name); } } @@ -120,7 +120,7 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode }; const auto spawn_and_change_lane = [&](const auto & entity_name, const auto spawn_s_value) { - if (!api_.isEntitySpawned(entity_name)) { + if (!api_.isEntityExist(entity_name)) { api_.spawn( entity_name, traffic_simulator::helper::constructCanonicalizedLaneletPose( @@ -158,7 +158,7 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode std::string entity_name = "pedestrian" + std::to_string(entity_index); constexpr lanelet::Id lanelet_id = 34392; if ( - !api_.isEntitySpawned(entity_name) && + !api_.isEntityExist(entity_name) && !ego_entity->isInPosition( traffic_simulator::helper::constructCanonicalizedLaneletPose( 34576, 25.0, 0.0, api_.getHdmapUtils()), @@ -179,7 +179,7 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode entity->setLinearVelocity(speed); } if ( - api_.isEntitySpawned(entity_name) && + api_.isEntityExist(entity_name) && api_.getEntity(entity_name)->getStandStillDuration() >= 0.5) { api_.despawn(entity_name); } @@ -191,7 +191,7 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode const auto trigger_position = traffic_simulator::helper::constructCanonicalizedLaneletPose( 34621, 10, 0.0, api_.getHdmapUtils()); constexpr auto entity_name = "spawn_nearby_ego"; - if (ego_entity->isInPosition(trigger_position, 20.0) && !api_.isEntitySpawned(entity_name)) { + if (ego_entity->isInPosition(trigger_position, 20.0) && !api_.isEntityExist(entity_name)) { api_.spawn( entity_name, traffic_simulator::pose::transformRelativePoseToGlobal( @@ -203,7 +203,7 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::entity::VehicleEntity::BuiltinBehavior::doNothing()); } - if (!ego_entity->isInPosition(trigger_position, 20.0) && api_.isEntitySpawned(entity_name)) { + if (!ego_entity->isInPosition(trigger_position, 20.0) && api_.isEntityExist(entity_name)) { api_.despawn(entity_name); } diff --git a/mock/cpp_mock_scenarios/src/traffic_simulation_demo.cpp b/mock/cpp_mock_scenarios/src/traffic_simulation_demo.cpp index d53b4cd426e..6ca6d01363d 100644 --- a/mock/cpp_mock_scenarios/src/traffic_simulation_demo.cpp +++ b/mock/cpp_mock_scenarios/src/traffic_simulation_demo.cpp @@ -42,17 +42,17 @@ class TrafficSimulationDemoScenario : public cpp_mock_scenarios::CppScenarioNode if (api_.getCurrentTime() >= 60) { stop(cpp_mock_scenarios::Result::SUCCESS); } - if (api_.getCurrentTime() >= 4 && api_.isEntitySpawned("tom")) { + if (api_.getCurrentTime() >= 4 && api_.isEntityExist("tom")) { api_.despawn("tom"); } - if (api_.getCurrentTime() >= 4 && api_.isEntitySpawned("obstacle")) { + if (api_.getCurrentTime() >= 4 && api_.isEntityExist("obstacle")) { api_.getEntity("obstacle") ->setStatus( traffic_simulator::helper::constructCanonicalizedLaneletPose( 120545, 0.0, 0.0, api_.getHdmapUtils()), traffic_simulator::helper::constructActionStatus(10)); } - if (api_.getCurrentTime() >= 6 && api_.isEntitySpawned("obstacle")) { + if (api_.getCurrentTime() >= 6 && api_.isEntityExist("obstacle")) { api_.despawn("obstacle"); } const auto ego_entity = api_.getEntity("ego"); @@ -64,7 +64,7 @@ class TrafficSimulationDemoScenario : public cpp_mock_scenarios::CppScenarioNode ego_entity->requestAcquirePosition( traffic_simulator::helper::constructCanonicalizedLaneletPose( 35026, 0.0, 0.0, api_.getHdmapUtils())); - if (api_.isEntitySpawned("npc2")) { + if (api_.isEntityExist("npc2")) { npc2_entity->requestSpeedChange(13, true); } } @@ -75,7 +75,7 @@ class TrafficSimulationDemoScenario : public cpp_mock_scenarios::CppScenarioNode ego_entity->requestAcquirePosition( traffic_simulator::helper::constructCanonicalizedLaneletPose( 34675, 0.0, 0.0, api_.getHdmapUtils())); - if (api_.isEntitySpawned("npc2")) { + if (api_.isEntityExist("npc2")) { npc2_entity->requestSpeedChange(3, true); } } @@ -88,7 +88,7 @@ class TrafficSimulationDemoScenario : public cpp_mock_scenarios::CppScenarioNode 34630, 0.0, 0.0, api_.getHdmapUtils())); npc2_entity->requestSpeedChange(13, true); } - if (api_.getCurrentTime() > 10.0 && api_.isEntitySpawned("bob")) { + if (api_.getCurrentTime() > 10.0 && api_.isEntityExist("bob")) { api_.despawn("bob"); } } diff --git a/simulation/traffic_simulator/include/traffic_simulator/api/api.hpp b/simulation/traffic_simulator/include/traffic_simulator/api/api.hpp index c319cd48e12..32778ca8ee3 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/api/api.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/api/api.hpp @@ -143,7 +143,7 @@ class API { auto register_to_entity_manager = [&]() { if (behavior == VehicleBehavior::autoware()) { - return entity_manager_ptr_->isEntitySpawned(name) or + return entity_manager_ptr_->isEntityExist(name) or entity_manager_ptr_->spawnEntity( name, pose, parameters, getCurrentTime(), configuration, node_parameters_); } else { @@ -321,7 +321,7 @@ class API static_assert(true, "") // clang-format on - FORWARD_TO_ENTITY_MANAGER(isEntitySpawned); + FORWARD_TO_ENTITY_MANAGER(isEntityExist); FORWARD_TO_ENTITY_MANAGER(getEgoEntity); FORWARD_TO_ENTITY_MANAGER(getEntityNames); FORWARD_TO_ENTITY_MANAGER(getEntityOrNullptr); diff --git a/simulation/traffic_simulator/include/traffic_simulator/entity/entity_manager.hpp b/simulation/traffic_simulator/include/traffic_simulator/entity/entity_manager.hpp index d8251820fba..3041fcf8595 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/entity/entity_manager.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/entity/entity_manager.hpp @@ -168,7 +168,7 @@ class EntityManager bool despawnEntity(const std::string & name); - auto isEntitySpawned(const std::string & name) const -> bool; + auto isEntityExist(const std::string & name) const -> bool; auto getEntityNames() const -> const std::vector; diff --git a/simulation/traffic_simulator/src/entity/entity_manager.cpp b/simulation/traffic_simulator/src/entity/entity_manager.cpp index 86bfd7fd3a3..bfe923a1001 100644 --- a/simulation/traffic_simulator/src/entity/entity_manager.cpp +++ b/simulation/traffic_simulator/src/entity/entity_manager.cpp @@ -123,10 +123,10 @@ visualization_msgs::msg::MarkerArray EntityManager::makeDebugMarker() const bool EntityManager::despawnEntity(const std::string & name) { - return isEntitySpawned(name) && entities_.erase(name); + return isEntityExist(name) && entities_.erase(name); } -auto EntityManager::isEntitySpawned(const std::string & name) const -> bool +auto EntityManager::isEntityExist(const std::string & name) const -> bool { return entities_.find(name) != std::end(entities_); } 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 7d157689eac..146dad86889 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 @@ -197,7 +197,7 @@ class TestExecutor } for (const auto & npc : test_description_.npcs_descriptions) { - if (api_->isEntitySpawned(npc.name) && api_->checkCollision(ego_name_, npc.name)) { + if (api_->isEntityExist(npc.name) && api_->checkCollision(ego_name_, npc.name)) { if (ego_collision_metric_.isThereEgosCollisionWith(npc.name, current_time)) { std::string message = fmt::format("New collision occurred between ego and {}", npc.name); 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 9cd7889a4f2..6d51bb3080e 100644 --- a/test_runner/random_test_runner/test/test_test_executor.cpp +++ b/test_runner/random_test_runner/test/test_test_executor.cpp @@ -130,7 +130,7 @@ class MockTrafficSimulatorAPI MOCK_METHOD(void, getEntityMock, (const std::string &), (const)); MOCK_METHOD(void, getEgoEntityMock, (const std::string &), (const)); MOCK_METHOD(void, getHdmapUtilsMock, (), ()); - MOCK_METHOD(bool, isEntitySpawned, (const std::string &), ()); + MOCK_METHOD(bool, isEntityExist, (const std::string &), ()); MOCK_METHOD(bool, checkCollision, (const std::string &, const std::string &), ()); auto getEntity(const std::string & name) const