diff --git a/mock/cpp_mock_scenarios/src/random_scenario/random001.cpp b/mock/cpp_mock_scenarios/src/random_scenario/random001.cpp index 405eb6344d2..4b97671343d 100644 --- a/mock/cpp_mock_scenarios/src/random_scenario/random001.cpp +++ b/mock/cpp_mock_scenarios/src/random_scenario/random001.cpp @@ -195,12 +195,12 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode 34606, 0.0, 0.0, api_.getHdmapUtils()); const auto entity_name = "spawn_nearby_ego"; - if (const auto ego = api_.getEntity("ego")) { - if (api_.isInPosition("ego", trigger_position, 20.0) && !api_.isEntitySpawned(entity_name)) { + if (ego_entity) { + if (ego_entity->isInPosition(trigger_position, 20.0) && !api_.isEntitySpawned(entity_name)) { api_.spawn( entity_name, traffic_simulator::pose::transformRelativePoseToGlobal( - ego->getMapPose(), + ego_entity->getMapPose(), geometry_msgs::build() .position(geometry_msgs::build().x(10).y(-5).z(0)) .orientation(geometry_msgs::msg::Quaternion())), @@ -208,12 +208,12 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::entity::VehicleEntity::BuiltinBehavior::doNothing()); } - if (!api_.isInPosition("ego", trigger_position, 20.0) && api_.isEntitySpawned(entity_name)) { + if (!ego_entity->isInPosition(trigger_position, 20.0) && api_.isEntitySpawned(entity_name)) { api_.despawn(entity_name); } } - if (api_.isInPosition("ego", ego_goal_position, 1.0)) { + if (ego_entity->isInPosition(ego_goal_position, 1.0)) { api_.despawn("ego"); stop(cpp_mock_scenarios::Result::SUCCESS); }