Skip to content

RJD-1057 (5/5): Remove non-API member functions: Improve responsibility simulator_core<->api #1337

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

Closed
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
89 commits
Select commit Hold shift + click to select a range
e6ffb81
feat(api, simulator_core): move features from simulator_core to api
dmoszynski Jul 3, 2024
9477f52
feat(simulator_core,openscenario_interpreter): develop develop specia…
dmoszynski Jul 3, 2024
b2fe246
feat(simulator_core): tidy up, remove unnecessary forwarding
dmoszynski Jul 24, 2024
b6d939d
feat(simulator_core, api, entity_base): init use LaneletPose as API i…
dmoszynski Jul 25, 2024
19d2638
Merge remote-tracking branch 'origin/RJD-1057-remove-functions-forwar…
dmoszynski Jul 25, 2024
2e00403
feat(simulator_core, api, cpp_mock_scenarios): use LaneletPose in spa…
dmoszynski Aug 1, 2024
3c08660
Merge remote-tracking branch 'origin/RJD-1057-remove-functions-forwar…
dmoszynski Aug 1, 2024
8946193
ref(simulator_core): refresh class division, tidy up
dmoszynski Aug 1, 2024
233deb3
ref(openscenario_interpeter): simplify distance_condition, reach_posi…
dmoszynski Aug 1, 2024
6618d05
ref(entity_status): move getLaneletRelativeYaw definition to cpp
dmoszynski Aug 1, 2024
506529e
Fix compile error
TauTheLepton Aug 2, 2024
d284fc6
Fix test_executor test
TauTheLepton Aug 2, 2024
9bf5312
ref(simulator_core, api): little global improve
dmoszynski Aug 5, 2024
043bf37
ref(api): use CanonicalizedLaneletPose as API output
dmoszynski Aug 5, 2024
c07e90c
ref(entity_base): reformat requestSynchronize
dmoszynski Aug 5, 2024
bac624d
feat(lanelet_pose, canonicalization): remove optional from canonicali…
dmoszynski Aug 5, 2024
260683a
Merge branch 'ref/RJD-1057-improve-responsibility-simulator-core-api'…
dmoszynski Aug 5, 2024
3bed78a
feat(api): add missing from_entity_name != to_entity_name checks
dmoszynski Aug 6, 2024
9e323cb
fix(entity_base): fix rclcpp warn logs
dmoszynski Aug 6, 2024
98c1866
fix(simulator_core, api): change relativeLaneletPose to laneletDistan…
dmoszynski Aug 8, 2024
6fe1268
Merge remote-tracking branch 'origin/RJD-1057-remove-functions-forwar…
dmoszynski Oct 14, 2024
3868f03
fix(openscenario_interpreter, traffic_simulator): fix after merge
dmoszynski Oct 14, 2024
e4b96cb
Merge remote-tracking branch 'origin/RJD-1057-remove-functions-forwar…
dmoszynski Oct 14, 2024
9fc7baf
ref(traffic_simulator): rename isEntitySpawned to isEntityExist
dmoszynski Dec 12, 2024
fde5680
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
dmoszynski Dec 16, 2024
31d4f11
ref(traffic_simulator): remove redundant traffic_simulator:: ns, add …
dmoszynski Dec 16, 2024
f7d75ec
ref(traffic_simulator): simple improvements
dmoszynski Dec 16, 2024
25a088b
Fix typo
TauTheLepton Dec 18, 2024
7ba7a6f
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Jan 7, 2025
fea2a83
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Jan 15, 2025
7021fce
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Jan 16, 2025
af1985f
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Jan 20, 2025
4280bf8
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Jan 30, 2025
5fa164f
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Jan 31, 2025
5de606a
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Jan 31, 2025
4e1edba
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Feb 5, 2025
ef1b005
Fix typo
TauTheLepton Feb 6, 2025
53a3680
Implement Sonar suggestions
TauTheLepton Feb 6, 2025
b5b6756
Clean code - use SimulatorCore position type aliases
TauTheLepton Feb 6, 2025
875a9e2
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Feb 6, 2025
e41ed88
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Feb 11, 2025
d7312e0
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Feb 11, 2025
096f906
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Feb 12, 2025
b4cb89c
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Feb 12, 2025
659c294
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Feb 13, 2025
bf9b99f
Fix non existing Entity issue
TauTheLepton Feb 13, 2025
6c8d04b
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Feb 19, 2025
28f3177
Bring back compile time check for `PoseType` in `EntityManager::spawn…
TauTheLepton Feb 19, 2025
0350572
Change compile time check for `ParamsType` in `API::spawn`
TauTheLepton Feb 19, 2025
f1cb1c2
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Feb 20, 2025
31ce87b
Transfer improvements from branch before in the chain
TauTheLepton Feb 20, 2025
f66fd5b
Style change
TauTheLepton Feb 20, 2025
e5f3ce9
Refactor(entity_base): Find the target entity status only once
TauTheLepton Feb 20, 2025
f4350a8
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Mar 6, 2025
446c1f2
Unify distance to lane bound functions
TauTheLepton Mar 6, 2025
616f36b
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Mar 11, 2025
1be3d6a
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Mar 12, 2025
dc5f804
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Mar 13, 2025
91da60b
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Mar 19, 2025
ee58e09
Remove unused template parameters
TauTheLepton Mar 19, 2025
c3bee60
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Mar 19, 2025
e5b88f4
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Mar 25, 2025
31d08c5
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Mar 26, 2025
87e77ca
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Mar 27, 2025
e3c28bb
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Apr 1, 2025
9133e07
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Apr 2, 2025
60909df
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Apr 8, 2025
516108b
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Apr 9, 2025
436e567
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Apr 10, 2025
e8ba3f9
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Apr 15, 2025
d30c122
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-refa…
TauTheLepton Apr 16, 2025
4541f54
Merge remote-tracking branch 'tier4/RJD-1057-remove-functions-forward…
TauTheLepton Apr 16, 2025
94d69b0
Merge branch 'master' into ref/RJD-1057-improve-responsibility-simula…
HansRobo Apr 17, 2025
2ae5150
Merge branch 'master' into ref/RJD-1057-improve-responsibility-simula…
TauTheLepton Apr 22, 2025
4984397
Merge remote-tracking branch 'tier4/master' into ref/RJD-1057-improve…
TauTheLepton May 6, 2025
c71e44c
Cleanup
TauTheLepton May 6, 2025
9ea336f
Merge branch 'master' into ref/RJD-1057-improve-responsibility-simula…
TauTheLepton May 12, 2025
97b2e00
Merge remote-tracking branch 'tier4/master' into ref/RJD-1057-improve…
TauTheLepton May 13, 2025
d3d6944
Merge branch 'master' into ref/RJD-1057-improve-responsibility-simula…
TauTheLepton May 14, 2025
b7b89fa
Merge remote-tracking branch 'tier4/master' into ref/RJD-1057-improve…
TauTheLepton May 15, 2025
1a45c95
Rename name arguments to entity_name as is in other functions
TauTheLepton May 15, 2025
eeddf18
Merge branch 'master' into ref/RJD-1057-improve-responsibility-simula…
TauTheLepton May 20, 2025
0fa2401
Merge remote-tracking branch 'tier4/master' into ref/RJD-1057-improve…
TauTheLepton May 28, 2025
f7e4696
Restore removed const and argument names
TauTheLepton May 29, 2025
b50e433
Normalize how Ego RouteOption is obtained in requestAssignRoute to be…
TauTheLepton May 29, 2025
84dbca3
Improve how lanelet pose is canonicalized in entity member functions
TauTheLepton May 29, 2025
206b83f
Bring back perfect forwarding for SimulatorCore functions arguments
TauTheLepton May 29, 2025
5a2dae1
Merge remote-tracking branch 'tier4/master' into ref/RJD-1057-improve…
TauTheLepton Jun 9, 2025
8ecd226
Add various API relative pose functions and use them in SimulatorCore
TauTheLepton Jun 4, 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 @@ -49,8 +49,8 @@ class CppScenarioNode : public rclcpp::Node
return false;
}
void spawnEgoEntity(
const traffic_simulator::CanonicalizedLaneletPose & spawn_lanelet_pose,
const std::vector<traffic_simulator::CanonicalizedLaneletPose> & goal_lanelet_pose,
const traffic_simulator::LaneletPose & spawn_lanelet_pose,
const std::vector<traffic_simulator::LaneletPose> & goal_lanelet_pose,
const traffic_simulator_msgs::msg::VehicleParameters & parameters);

auto isVehicle(const std::string & name) const -> bool;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,22 +70,20 @@ class LoadDoNothingPluginScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34741, 0.0, 0.0),
getVehicleParameters(),
traffic_simulator::entity::VehicleEntity::BuiltinBehavior::doNothing());
api_.spawn(
"pedestrian", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 3.0, 0.0),
"pedestrian", traffic_simulator::helper::constructLaneletPose(34741, 3.0, 0.0),
getPedestrianParameters(),
traffic_simulator::entity::PedestrianEntity::BuiltinBehavior::doNothing());
api_.spawn(
"vehicle_spawn_with_behavior_tree",
traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 2.0, 0.0),
getVehicleParameters(),
traffic_simulator::helper::constructLaneletPose(34741, 2.0, 0.0), getVehicleParameters(),
traffic_simulator::entity::VehicleEntity::BuiltinBehavior::behaviorTree());
api_.spawn(
"pedestrian_spawn_with_behavior_tree",
traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 3.0, 0.0),
getPedestrianParameters(),
traffic_simulator::helper::constructLaneletPose(34741, 3.0, 0.0), getPedestrianParameters(),
traffic_simulator::entity::PedestrianEntity::BuiltinBehavior::behaviorTree());
}
};
Expand Down
4 changes: 2 additions & 2 deletions mock/cpp_mock_scenarios/src/collision/crashing_npc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class CrashingNpcScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34741, 0.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(0.0);
ego_entity.requestSpeedChange(15, true);
Expand All @@ -61,7 +61,7 @@ class CrashingNpcScenario : public cpp_mock_scenarios::CppScenarioNode
ego_entity.setBehaviorParameter(behavior_parameter);

auto & npc_entity = api_.spawn(
"npc", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 10.0, 0.0),
"npc", traffic_simulator::helper::constructLaneletPose(34741, 10.0, 0.0),
getVehicleParameters());
npc_entity.setLinearVelocity(0.0);
npc_entity.requestSpeedChange(5, true);
Expand Down
4 changes: 2 additions & 2 deletions mock/cpp_mock_scenarios/src/collision/spawn_with_offset.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,13 +50,13 @@ class SpawnWithOffsetScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.2, 1.3),
"ego", traffic_simulator::helper::constructLaneletPose(34741, 0.2, 1.3),
getVehicleParameters());
ego_entity.setLinearVelocity(0);
ego_entity.requestSpeedChange(0, true);

auto & bob_entity = api_.spawn(
"bob", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.0, -0.874),
"bob", traffic_simulator::helper::constructLaneletPose(34741, 0.0, -0.874),
getPedestrianParameters());
bob_entity.setLinearVelocity(0);
bob_entity.requestSpeedChange(0, true);
Expand Down
4 changes: 2 additions & 2 deletions mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,8 +99,8 @@ void CppScenarioNode::stop(Result result, const std::string & description)
}

void CppScenarioNode::spawnEgoEntity(
const traffic_simulator::CanonicalizedLaneletPose & spawn_lanelet_pose,
const std::vector<traffic_simulator::CanonicalizedLaneletPose> & goal_lanelet_poses,
const traffic_simulator::LaneletPose & spawn_lanelet_pose,
const std::vector<traffic_simulator::LaneletPose> & goal_lanelet_poses,
const traffic_simulator_msgs::msg::VehicleParameters & parameters)
{
api_.updateFrame();
Expand Down
10 changes: 5 additions & 5 deletions mock/cpp_mock_scenarios/src/crosswalk/stop_at_crosswalk.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,16 +75,16 @@ class StopAtCrosswalkScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(120545, 0.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(120545, 0.0, 0.0),
getVehicleParameters());
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)});
ego_entity.requestAssignRoute(
{traffic_simulator::helper::constructLaneletPose(34675, 0.0, 0.0),
traffic_simulator::helper::constructLaneletPose(34690, 0.0, 0.0)});

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

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

auto & npc_entity = api_.spawn(
"npc", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 15.0, 0.0),
"npc", traffic_simulator::helper::constructLaneletPose(34741, 15.0, 0.0),
getVehicleParameters());
npc_entity.setLinearVelocity(10);
npc_entity.requestSpeedChange(10, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,14 +47,14 @@ class AcquirePositionInWorldFrameScenario : public cpp_mock_scenarios::CppScenar
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 10.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34741, 10.0, 0.0),
getVehicleParameters());
ego_entity.setStatus(
traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 0.0, 0.0),
traffic_simulator::helper::constructLaneletPose(34513, 0.0, 0.0),
traffic_simulator::helper::constructActionStatus(10));
ego_entity.requestSpeedChange(10, true);
const geometry_msgs::msg::Pose goal_pose = traffic_simulator::pose::toMapPose(
traffic_simulator::helper::constructCanonicalizedLaneletPose(34408, 1.0, 0.0));
traffic_simulator::helper::constructLaneletPose(34408, 1.0, 0.0));
ego_entity.requestAcquirePosition(goal_pose);
}
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,15 +47,15 @@ class AcquireRouteInWorldFrameScenario : public cpp_mock_scenarios::CppScenarioN
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 0.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34513, 0.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
std::vector<geometry_msgs::msg::Pose> goal_poses;
goal_poses.emplace_back(traffic_simulator::pose::toMapPose(
traffic_simulator::helper::constructCanonicalizedLaneletPose(34408, 1.0, 0.0)));
traffic_simulator::helper::constructLaneletPose(34408, 1.0, 0.0)));
goal_poses.emplace_back(traffic_simulator::pose::toMapPose(
traffic_simulator::helper::constructCanonicalizedLaneletPose(34408, 10, 0.0)));
traffic_simulator::helper::constructLaneletPose(34408, 10, 0.0)));
ego_entity.requestAssignRoute(goal_poses);
}
};
Expand Down
4 changes: 2 additions & 2 deletions mock/cpp_mock_scenarios/src/follow_lane/cancel_request.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ class CancelRequestScenario : public cpp_mock_scenarios::CppScenarioNode
{
auto & ego_entity = api_.getEntity("ego");
if (ego_entity.isNearbyPosition(
traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 30, 0), 3.0)) {
traffic_simulator::helper::constructLaneletPose(34513, 30, 0), 3.0)) {
ego_entity.cancelRequest();
canceled = true;
}
Expand All @@ -52,7 +52,7 @@ class CancelRequestScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 0.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34513, 0.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(7);
ego_entity.requestSpeedChange(7, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class FollowLaneWithOffsetScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 0.0, 3.0),
"ego", traffic_simulator::helper::constructLaneletPose(34513, 0.0, 3.0),
getVehicleParameters());
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class LaneChangeLeftScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class LaneChangeLeftWithIdScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class LaneChangeLinearScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class LaneChangeLinearLateralVelocityScenario : public cpp_mock_scenarios::CppSc
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ class LaneChangeLinearTimeScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ class LaneChangeLongitudinalDistanceScenario : public cpp_mock_scenarios::CppSce
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(1);
ego_entity.requestSpeedChange(1, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class LaneChangeRightScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 10.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34513, 10.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class LaneChangeRightWithIdScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 10.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34513, 10.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ class LaneChangeTimeScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34462, 10.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(10, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,19 +137,19 @@ class GetDistanceInLaneCoordinateScenario : public cpp_mock_scenarios::CppScenar
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 5.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34513, 5.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(10);
ego_entity.requestSpeedChange(3, true);

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

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

auto & npc_entity = api_.spawn(
"npc", traffic_simulator::helper::constructCanonicalizedLaneletPose(34513, 0.0, 0.0),
"npc", traffic_simulator::helper::constructLaneletPose(34513, 0.0, 0.0),
getVehicleParameters());
npc_entity.setLinearVelocity(10);
}
Expand Down
2 changes: 1 addition & 1 deletion mock/cpp_mock_scenarios/src/metrics/traveled_distance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class TraveledDistanceScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34741, 0.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(3);
ego_entity.requestSpeedChange(3, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class MoveBackwardScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(34741, 0.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(34741, 0.0, 0.0),
getVehicleParameters());
ego_entity.setLinearVelocity(-3);
ego_entity.requestSpeedChange(-3, true);
Expand Down
10 changes: 5 additions & 5 deletions mock/cpp_mock_scenarios/src/pedestrian/walk_straight.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,15 +70,15 @@ class WalkStraightScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
auto & ego_entity = api_.spawn(
"ego", traffic_simulator::helper::constructCanonicalizedLaneletPose(120545, 0.0, 0.0),
"ego", traffic_simulator::helper::constructLaneletPose(120545, 0.0, 0.0),
getVehicleParameters());
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)});
ego_entity.requestAssignRoute(
{traffic_simulator::helper::constructLaneletPose(34675, 0.0, 0.0),
traffic_simulator::helper::constructLaneletPose(34690, 0.0, 0.0)});
auto & bob_entity = api_.spawn(
"bob", traffic_simulator::helper::constructCanonicalizedLaneletPose(34378, 0.0, 0.0),
"bob", traffic_simulator::helper::constructLaneletPose(34378, 0.0, 0.0),
getPedestrianParameters());
bob_entity.setLinearVelocity(0);
bob_entity.requestWalkStraight();
Expand Down
Loading
Loading