Skip to content

Commit

Permalink
ref(traffic_simulator): rename isEntitySpawned to isEntityExist
Browse files Browse the repository at this point in the history
  • Loading branch information
dmoszynski committed Dec 12, 2024
1 parent 4e0c479 commit 153e7b1
Show file tree
Hide file tree
Showing 9 changed files with 21 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
/**
Expand Down
2 changes: 1 addition & 1 deletion mock/cpp_mock_scenarios/src/pedestrian/walk_straight.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
/**
Expand Down
12 changes: 6 additions & 6 deletions mock/cpp_mock_scenarios/src/random_scenario/random001.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
}
Expand All @@ -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(
Expand Down Expand Up @@ -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()),
Expand All @@ -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);
}
Expand All @@ -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(
Expand All @@ -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);
}

Expand Down
12 changes: 6 additions & 6 deletions mock/cpp_mock_scenarios/src/traffic_simulation_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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");
Expand All @@ -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);
}
}
Expand All @@ -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);
}
}
Expand All @@ -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");
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<entity::EgoEntity>(
name, pose, parameters, getCurrentTime(), configuration, node_parameters_);
} else {
Expand Down Expand Up @@ -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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string>;

Expand Down
4 changes: 2 additions & 2 deletions simulation/traffic_simulator/src/entity/entity_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion test_runner/random_test_runner/test/test_test_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit 153e7b1

Please sign in to comment.