Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

RJD-1057 (4/5): Remove non-API member functions: EntityManager’s member functions forwarded to EntityBase (2/2) #1334

Open
wants to merge 53 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
53 commits
Select commit Hold shift + click to select a range
1a8485f
feat(traffic_simulator): separate ostream helpers, extend it
dmoszynski Jul 2, 2024
6c41a31
ref(api, entity_manager): improve spawn, spawnEntity - return shared_ptr
dmoszynski Jul 2, 2024
b96424d
ref(cpp_mock_scenarios): use returned spawn() pointer
dmoszynski Jul 2, 2024
cc5e670
ref(api): refactor the entire API, remove forwarding macro, separate …
dmoszynski Jul 2, 2024
09375d4
ref(entity_manager, entity_base): add as() to EntityBase, remove unne…
dmoszynski Jul 2, 2024
95a6f28
ref(entity_manager): refactor the entire Entity_manager, separate sec…
dmoszynski Jul 2, 2024
489cabe
fix(api): fix init order
dmoszynski Jul 2, 2024
ed13268
Merge branch 'RJD-1057-remove-traffic-lights-from-entity-manager' int…
TauTheLepton Jul 22, 2024
1a8001a
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Jul 23, 2024
2e994e9
Merge branch 'RJD-1057-remove-traffic-lights-from-entity-manager' int…
TauTheLepton Jul 25, 2024
267d564
Fix applyTeleportAction to correctly use templated function
TauTheLepton Jul 25, 2024
292719d
Fix Ego pose setting
TauTheLepton Jul 25, 2024
2ba6f86
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
TauTheLepton Jul 31, 2024
ff759fe
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
TauTheLepton Jul 31, 2024
2b3def2
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
TauTheLepton Oct 3, 2024
508e3f0
Merge remote-tracking branch 'origin/RJD-1057-remove-functions-forwar…
dmoszynski Oct 14, 2024
0149eec
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
dmoszynski Oct 14, 2024
88c58ed
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
dmoszynski Oct 15, 2024
7912eea
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
dmoszynski Oct 15, 2024
c4083af
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
dmoszynski Oct 16, 2024
5a8929b
ref(traffic_simulator): apply sonarcloud requested changes
dmoszynski Oct 16, 2024
fa3e08e
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
dmoszynski Dec 16, 2024
7ba59db
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
dmoszynski Dec 18, 2024
6532eb6
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
TauTheLepton Jan 7, 2025
61d9686
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Jan 8, 2025
ef82e98
Refactor: Replace std::is_same<>::value with std::is_same_v<>
TauTheLepton Jan 8, 2025
46a30cb
Refactor: Use in class initializer
TauTheLepton Jan 8, 2025
da355dc
Refactor: configuration -> configuration_
TauTheLepton Jan 8, 2025
e1b7b78
Remove unused member
TauTheLepton Jan 8, 2025
588f2a8
Use modern initialization
TauTheLepton Jan 8, 2025
7820ce5
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Jan 15, 2025
88de6b2
Use EntityBase `is` and `as` functions
TauTheLepton Jan 15, 2025
7700bf0
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
TauTheLepton Jan 16, 2025
c464ff2
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
TauTheLepton Jan 20, 2025
dfefd36
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Jan 29, 2025
062c50d
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
HansRobo Jan 30, 2025
c9d84a4
Fix typo
TauTheLepton Jan 30, 2025
6be401d
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
HansRobo Jan 31, 2025
532873e
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
TauTheLepton Jan 31, 2025
40a93eb
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
TauTheLepton Feb 5, 2025
f8306dd
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
TauTheLepton Feb 6, 2025
23e2b6e
Merge remote-tracking branch 'tier4/master' into RJD-1057-remove-func…
TauTheLepton Feb 10, 2025
b3f7235
Make `SimulatorCore::ActionApplication::applyAddEntityAction` deduce …
TauTheLepton Feb 10, 2025
f029407
Adjust `EntityBase::as` to return reference instead of shared_ptr
TauTheLepton Feb 11, 2025
66575dd
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
TauTheLepton Feb 12, 2025
c3e9294
Change runtime check to compiletime check
TauTheLepton Feb 12, 2025
4f5a0c2
Fix copyright notice date
TauTheLepton Feb 12, 2025
ce817e2
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Feb 12, 2025
5e43d96
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
HansRobo Feb 13, 2025
bfd7c52
Trigger SonarCloud
TauTheLepton Feb 13, 2025
dbf0c03
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
TauTheLepton Feb 18, 2025
bcc35ae
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
TauTheLepton Feb 20, 2025
7688a48
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
dmoszynski Feb 27, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,8 @@ class LoadDoNothingPluginScenario : public cpp_mock_scenarios::CppScenarioNode
api_.resetBehaviorPlugin(
"pedestrian_spawn_with_behavior_tree",
traffic_simulator::entity::PedestrianEntity::BuiltinBehavior::doNothing());

/// @note After the reset, the Entity objects are invalidated, so we need to obtain new ones.
if (
api_.getEntity("vehicle_spawn_with_behavior_tree").getCurrentAction() != "do_nothing" ||
api_.getEntity("pedestrian_spawn_with_behavior_tree").getCurrentAction() != "do_nothing") {
Expand Down
6 changes: 2 additions & 4 deletions mock/cpp_mock_scenarios/src/collision/crashing_npc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,20 +51,18 @@ class CrashingNpcScenario : public cpp_mock_scenarios::CppScenarioNode
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(0.0);
ego_entity.requestSpeedChange(15, true);
traffic_simulator_msgs::msg::BehaviorParameter behavior_parameter;
behavior_parameter.see_around = false;
ego_entity.setBehaviorParameter(behavior_parameter);

api_.spawn(
auto & npc_entity = api_.spawn(
"npc", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 10.0, 0.0),
getVehicleParameters());
auto & npc_entity = api_.getEntity("npc");
npc_entity.setLinearVelocity(0.0);
npc_entity.requestSpeedChange(5, true);
}
Expand Down
6 changes: 2 additions & 4 deletions mock/cpp_mock_scenarios/src/collision/spawn_with_offset.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,17 +49,15 @@ class SpawnWithOffsetScenario : public cpp_mock_scenarios::CppScenarioNode

void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.2, 1.3),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(0);
ego_entity.requestSpeedChange(0, true);

api_.spawn(
auto & bob_entity = api_.spawn(
"bob", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.0, -0.874),
getPedestrianParameters());
auto & bob_entity = api_.getEntity("bob");
bob_entity.setLinearVelocity(0);
bob_entity.requestSpeedChange(0, true);
}
Expand Down
6 changes: 2 additions & 4 deletions mock/cpp_mock_scenarios/src/crosswalk/stop_at_crosswalk.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,20 +74,18 @@ class StopAtCrosswalkScenario : public cpp_mock_scenarios::CppScenarioNode

void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(120545, 0.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(8, true);
ego_entity.requestAssignRoute(std::vector<traffic_simulator::CanonicalizedLaneletPose>{
traffic_simulator::helper::constructCanonicalizedLaneletPose(34675, 0.0, 0.0),
traffic_simulator::helper::constructCanonicalizedLaneletPose(34690, 0.0, 0.0)});

api_.spawn(
auto & bob_entity = api_.spawn(
"bob", traffic_simulator::helper::constructCanonicalizedLaneletPose(34378, 0.0, 0.0),
getPedestrianParameters());
auto & bob_entity = api_.getEntity("bob");
bob_entity.setLinearVelocity(0);
bob_entity.requestSpeedChange(
1.0, traffic_simulator::speed_change::Transition::LINEAR,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,15 +57,14 @@ class AccelerateAndFollowScenario : public cpp_mock_scenarios::CppScenarioNode
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.0, 0.0),
getVehicleParameters());
api_.getEntity("ego").setLinearVelocity(3);
ego_entity.setLinearVelocity(3);

api_.spawn(
auto & npc_entity = api_.spawn(
"npc", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 10.0, 0.0),
getVehicleParameters());
auto & npc_entity = api_.getEntity("npc");
npc_entity.setLinearVelocity(10);
npc_entity.requestSpeedChange(10, true);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,15 +57,14 @@ class DecelerateAndFollowScenario : public cpp_mock_scenarios::CppScenarioNode
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.0, 0.0),
getVehicleParameters());
api_.getEntity("ego").setLinearVelocity(15);
ego_entity.setLinearVelocity(15);

api_.spawn(
auto & npc_entity = api_.spawn(
"npc", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 15.0, 0.0),
getVehicleParameters());
auto & npc_entity = api_.getEntity("npc");
npc_entity.setLinearVelocity(10);
npc_entity.requestSpeedChange(10, true);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,9 @@ class AcquirePositionInWorldFrameScenario : public cpp_mock_scenarios::CppScenar
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 10.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setStatus(
traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 0.0, 0.0),
traffic_simulator::helper::constructActionStatus(10));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,9 @@ class AcquireRouteInWorldFrameScenario : public cpp_mock_scenarios::CppScenarioN
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 0.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
std::vector<geometry_msgs::msg::Pose> goal_poses;
Expand Down
3 changes: 1 addition & 2 deletions mock/cpp_mock_scenarios/src/follow_lane/cancel_request.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,9 @@ class CancelRequestScenario : public cpp_mock_scenarios::CppScenarioNode
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 0.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(7);
ego_entity.requestSpeedChange(7, true);
const geometry_msgs::msg::Pose goal_pose = traffic_simulator::pose::toMapPose(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,10 +50,9 @@ class FollowLaneWithOffsetScenario : public cpp_mock_scenarios::CppScenarioNode
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 0.0, 3.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -97,10 +97,9 @@ class FollowPolylineTrajectoryWithDoNothingPluginScenario
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", spawn_pose, getVehicleParameters(),
traffic_simulator::entity::VehicleEntity::BuiltinBehavior::doNothing());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
ego_entity.requestFollowTrajectory(
Expand Down
3 changes: 1 addition & 2 deletions mock/cpp_mock_scenarios/src/lane_change/lanechange_left.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,10 +50,9 @@ class LaneChangeLeftScenario : public cpp_mock_scenarios::CppScenarioNode
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
ego_entity.requestLaneChange(traffic_simulator::lane_change::Direction::LEFT);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,10 +50,9 @@ class LaneChangeLeftWithIdScenario : public cpp_mock_scenarios::CppScenarioNode
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
ego_entity.requestLaneChange(34513);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,10 +55,9 @@ class LaneChangeLinearScenario : public cpp_mock_scenarios::CppScenarioNode
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
ego_entity.requestLaneChange(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,10 +59,9 @@ class LaneChangeLinearLateralVelocityScenario : public cpp_mock_scenarios::CppSc
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
ego_entity.requestLaneChange(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,10 +60,9 @@ class LaneChangeLinearTimeScenario : public cpp_mock_scenarios::CppScenarioNode
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
ego_entity.requestLaneChange(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,9 @@ class LaneChangeLongitudinalDistanceScenario : public cpp_mock_scenarios::CppSce
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(1);
ego_entity.requestSpeedChange(1, true);
ego_entity.requestLaneChange(
Expand Down
3 changes: 1 addition & 2 deletions mock/cpp_mock_scenarios/src/lane_change/lanechange_right.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,10 +50,9 @@ class LaneChangeRightScenario : public cpp_mock_scenarios::CppScenarioNode
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 10.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
ego_entity.requestLaneChange(traffic_simulator::lane_change::Direction::RIGHT);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,10 +50,9 @@ class LaneChangeRightWithIdScenario : public cpp_mock_scenarios::CppScenarioNode
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 10.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
ego_entity.requestLaneChange(34462);
Expand Down
3 changes: 1 addition & 2 deletions mock/cpp_mock_scenarios/src/lane_change/lanechange_time.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,10 +60,9 @@ class LaneChangeTimeScenario : public cpp_mock_scenarios::CppScenarioNode
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
ego_entity.requestLaneChange(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,24 +137,21 @@ class GetDistanceInLaneCoordinateScenario : public cpp_mock_scenarios::CppScenar
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 5.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(3, true);

api_.spawn(
auto & front_entity = api_.spawn(
"front", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 10.0, 1.0),
getVehicleParameters());
auto & front_entity = api_.getEntity("front");
front_entity.setLinearVelocity(10);
front_entity.requestSpeedChange(3, true);

api_.spawn(
auto & behind_entity = api_.spawn(
"behind", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 0.0, -1.0),
getVehicleParameters());
auto & behind_entity = api_.getEntity("behind");
behind_entity.setLinearVelocity(10);
behind_entity.requestSpeedChange(3, true);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,10 +55,9 @@ class GetDistanceToLaneBoundScenario : public cpp_mock_scenarios::CppScenarioNod
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 5.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(3, true);
}
Expand Down
7 changes: 3 additions & 4 deletions mock/cpp_mock_scenarios/src/merge/merge_left.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,18 +53,17 @@ class MergeLeftScenario : public cpp_mock_scenarios::CppScenarioNode
}
void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 15.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(5);
ego_entity.requestSpeedChange(5, true);
ego_entity.requestLaneChange(34513);

api_.spawn(
auto & npc_entity = api_.spawn(
"npc", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 0.0, 0.0),
getVehicleParameters());
api_.getEntity("npc").setLinearVelocity(10);
npc_entity.setLinearVelocity(10);
}
};
} // namespace cpp_mock_scenarios
Expand Down
3 changes: 1 addition & 2 deletions mock/cpp_mock_scenarios/src/metrics/traveled_distance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,10 +59,9 @@ class TraveledDistanceScenario : public cpp_mock_scenarios::CppScenarioNode

void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(3);
ego_entity.requestSpeedChange(3, true);
}
Expand Down
3 changes: 1 addition & 2 deletions mock/cpp_mock_scenarios/src/move_backward/move_backward.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,10 +50,9 @@ class MoveBackwardScenario : public cpp_mock_scenarios::CppScenarioNode

void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(-3);
ego_entity.requestSpeedChange(-3, true);
}
Expand Down
6 changes: 2 additions & 4 deletions mock/cpp_mock_scenarios/src/pedestrian/walk_straight.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,19 +69,17 @@ class WalkStraightScenario : public cpp_mock_scenarios::CppScenarioNode

void onInitialize() override
{
api_.spawn(
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(120545, 0.0, 0.0),
getVehicleParameters());
auto & ego_entity = api_.getEntity("ego");
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(8, true);
ego_entity.requestAssignRoute(std::vector<traffic_simulator::CanonicalizedLaneletPose>{
traffic_simulator::helper::constructCanonicalizedLaneletPose(34675, 0.0, 0.0),
traffic_simulator::helper::constructCanonicalizedLaneletPose(34690, 0.0, 0.0)});
api_.spawn(
auto & bob_entity = api_.spawn(
"bob", traffic_simulator::helper::constructCanonicalizedLaneletPose(34378, 0.0, 0.0),
getPedestrianParameters());
auto & bob_entity = api_.getEntity("bob");
bob_entity.setLinearVelocity(0);
bob_entity.requestWalkStraight();
bob_entity.requestSpeedChange(
Expand Down
Loading
Loading