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

[tmp] RJD-1057 (5/5): Remove non-API member functions: Improve responsibility simulator core api #1337

Draft
wants to merge 23 commits into
base: RJD-1057-remove-functions-forwarded-to-entity-base-refactor
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
23 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
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 @@ -48,8 +48,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,28 +70,20 @@ class LoadDoNothingPluginScenario : public cpp_mock_scenarios::CppScenarioNode
void onInitialize() override
{
api_.spawn(
"ego",
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 0.0, 0.0, api_.getHdmapUtils()),
"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, api_.getHdmapUtils()),
"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, api_.getHdmapUtils()),
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, api_.getHdmapUtils()),
getPedestrianParameters(),
traffic_simulator::helper::constructLaneletPose(34741, 3.0, 0.0), getPedestrianParameters(),
traffic_simulator::entity::PedestrianEntity::BuiltinBehavior::behaviorTree());
}
};
Expand Down
8 changes: 2 additions & 6 deletions mock/cpp_mock_scenarios/src/collision/crashing_npc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,9 +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, api_.getHdmapUtils()),
"ego", traffic_simulator::helper::constructLaneletPose(34741, 0.0, 0.0),
getVehicleParameters());
ego_entity->setLinearVelocity(0.0);
ego_entity->requestSpeedChange(15, true);
Expand All @@ -63,9 +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, api_.getHdmapUtils()),
"npc", traffic_simulator::helper::constructLaneletPose(34741, 10.0, 0.0),
getVehicleParameters());
npc_entity->setLinearVelocity(0.0);
npc_entity->requestSpeedChange(5, true);
Expand Down
8 changes: 2 additions & 6 deletions mock/cpp_mock_scenarios/src/collision/spawn_with_offset.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,17 +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, api_.getHdmapUtils()),
"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, api_.getHdmapUtils()),
"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 @@ -97,8 +97,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
16 changes: 5 additions & 11 deletions mock/cpp_mock_scenarios/src/crosswalk/stop_at_crosswalk.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,22 +74,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, api_.getHdmapUtils()),
"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, api_.getHdmapUtils()),
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34690, 0.0, 0.0, api_.getHdmapUtils())});
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, api_.getHdmapUtils()),
"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 @@ -59,16 +59,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, api_.getHdmapUtils()),
"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, api_.getHdmapUtils()),
"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 @@ -59,16 +59,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, api_.getHdmapUtils()),
"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, api_.getHdmapUtils()),
"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,18 +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, api_.getHdmapUtils()),
"ego", traffic_simulator::helper::constructLaneletPose(34741, 10.0, 0.0),
getVehicleParameters());
ego_entity->setStatus(
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34513, 0.0, 0.0, api_.getHdmapUtils()),
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, api_.getHdmapUtils()));
traffic_simulator::helper::constructLaneletPose(34408, 1.0, 0.0), api_.getHdmapUtils());
ego_entity->requestAcquirePosition(goal_pose);
}
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,19 +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, api_.getHdmapUtils()),
"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, api_.getHdmapUtils())));
traffic_simulator::helper::constructLaneletPose(34408, 1.0, 0.0), api_.getHdmapUtils()));
goal_poses.emplace_back(traffic_simulator::pose::toMapPose(
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34408, 10, 0.0, api_.getHdmapUtils())));
traffic_simulator::helper::constructLaneletPose(34408, 10, 0.0), api_.getHdmapUtils()));
ego_entity->requestAssignRoute(goal_poses);
}
};
Expand Down
8 changes: 2 additions & 6 deletions mock/cpp_mock_scenarios/src/follow_lane/cancel_request.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,7 @@ class CancelRequestScenario : public cpp_mock_scenarios::CppScenarioNode
{
const auto ego_entity = api_.getEntity("ego");
if (ego_entity->isInPosition(
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34513, 30, 0, api_.getHdmapUtils()),
3.0)) {
traffic_simulator::helper::constructLaneletPose(34513, 30, 0), 3.0)) {
ego_entity->cancelRequest();
canceled = true;
}
Expand All @@ -54,9 +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, api_.getHdmapUtils()),
"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 @@ -43,8 +43,7 @@ class FollowLaneWithOffsetScenario : public cpp_mock_scenarios::CppScenarioNode
const auto ego_entity = api_.getEntity("ego");
if (const auto lanelet_pose = ego_entity->getCanonicalizedLaneletPose(); not lanelet_pose) {
stop(cpp_mock_scenarios::Result::FAILURE);
} else if (traffic_simulator::pose::isInLanelet(
lanelet_pose.value(), 34507, 0.1, api_.getHdmapUtils())) {
} else if (ego_entity->isInLanelet(34507, 0.1)) {
stop(cpp_mock_scenarios::Result::SUCCESS);
} else if (
std::abs(static_cast<traffic_simulator::LaneletPose>(lanelet_pose.value()).offset) <= 2.8) {
Expand All @@ -54,9 +53,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, api_.getHdmapUtils()),
"ego", traffic_simulator::helper::constructLaneletPose(34513, 0.0, 3.0),
getVehicleParameters());
ego_entity->setLinearVelocity(10);
ego_entity->requestSpeedChange(10, true);
Expand Down
4 changes: 1 addition & 3 deletions mock/cpp_mock_scenarios/src/lane_change/lanechange_left.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,9 +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, api_.getHdmapUtils()),
"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,9 +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, api_.getHdmapUtils()),
"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,9 +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, api_.getHdmapUtils()),
"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,9 +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, api_.getHdmapUtils()),
"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,9 +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, api_.getHdmapUtils()),
"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,9 +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, api_.getHdmapUtils()),
"ego", traffic_simulator::helper::constructLaneletPose(34462, 10.0, 0.0),
getVehicleParameters());
ego_entity->setLinearVelocity(1);
ego_entity->requestSpeedChange(1, true);
Expand Down
4 changes: 1 addition & 3 deletions mock/cpp_mock_scenarios/src/lane_change/lanechange_right.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,9 +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, api_.getHdmapUtils()),
"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,9 +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, api_.getHdmapUtils()),
"ego", traffic_simulator::helper::constructLaneletPose(34513, 10.0, 0.0),
getVehicleParameters());
ego_entity->setLinearVelocity(10);
ego_entity->requestSpeedChange(10, true);
Expand Down
4 changes: 1 addition & 3 deletions mock/cpp_mock_scenarios/src/lane_change/lanechange_time.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,9 +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, api_.getHdmapUtils()),
"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 @@ -136,25 +136,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, api_.getHdmapUtils()),
"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, api_.getHdmapUtils()),
"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, api_.getHdmapUtils()),
"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 @@ -57,9 +57,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, api_.getHdmapUtils()),
"ego", traffic_simulator::helper::constructLaneletPose(34513, 5.0, 0.0),
getVehicleParameters());
ego_entity->setLinearVelocity(10);
ego_entity->requestSpeedChange(3, true);
Expand Down
Loading
Loading