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 (3/5): Remove non-API member functions: EntityManager’s member functions forwarded to EntityBase (1/2) #1473

Open
wants to merge 65 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
65 commits
Select commit Hold shift + click to select a range
7ff6248
Add getEntityOrThrow function to mimic forwarding functionality where…
TauTheLepton Jun 19, 2024
aacd0b3
Remove forwarding of getEntityType in EntityManager
TauTheLepton Jun 19, 2024
b972a16
Forward getEntityOrThrow from API to EntityManager
TauTheLepton Jun 19, 2024
38d9552
Remove forwarding of getEntityStatus in EntityManager and API
TauTheLepton Jun 19, 2024
26ce1d1
Add const
TauTheLepton Jun 19, 2024
cb0fbb2
Remove forwarding of getEntityStatusBeforeUpdate in EntityManager and…
TauTheLepton Jun 19, 2024
9c60bb3
Remove forwarding of getBehaviorParameter in EntityManager and API
TauTheLepton Jun 19, 2024
1a0c2be
Remove forwarding of getCurrentTwist in EntityManager and API
TauTheLepton Jun 19, 2024
421a18e
Clean unused template
TauTheLepton Jun 19, 2024
d3e83a3
Remove forwarding of getCurrentAccel in EntityManager and API
TauTheLepton Jun 19, 2024
89ef194
Remove forwarding of getLinearJerk in EntityManager and API
TauTheLepton Jun 19, 2024
24e7321
Remove forwarding of getBoundingBox in EntityManager and API
TauTheLepton Jun 19, 2024
be319aa
Remove forwarding of get2DPolygon in EntityManager
TauTheLepton Jun 19, 2024
9d942f9
Remove forwarding of getStandStillDuration in EntityManager and API
TauTheLepton Jun 19, 2024
9953d8c
feat(cpp_mock, traffic_simulator): change getEntity, use getEntityOrN…
dmoszynski Jun 26, 2024
3921d57
Merge remote-tracking branch 'origin/RJD-1056-remove-current-time-ste…
dmoszynski Jun 26, 2024
2c78d59
Merge remote-tracking branch 'origin/RJD-1056-remove-npc-logic-starte…
dmoszynski Jun 26, 2024
e7091e5
feat(entity_base, traffic_simulator, cpp_mock): move isInLanelet to E…
dmoszynski Jun 26, 2024
ecb46de
feat(entity_base, traffic_simulator): move reachPosition as isInPosit…
dmoszynski Jun 26, 2024
0ed40a3
feat(entity_base, traffic_simulator): rename laneMatchingSucceed to i…
dmoszynski Jun 26, 2024
249ec7d
feat(entity_base, traffic_simulator): remove forwarding setters to En…
dmoszynski Jun 27, 2024
9233cf8
feat(entity_base, traffic_simulator): move isStopping to EntityBase, …
dmoszynski Jun 27, 2024
e3bc5f9
feat(entity_base, traffic_simulator, simulator_core): remove forwardi…
dmoszynski Jun 27, 2024
6dbf3ac
feat(entity_base, traffic_simulator, simulator_core): remove forwardi…
dmoszynski Jun 27, 2024
f952a11
feat(entity_manager, behavior_tree, cpp_mock): remove getCurrentActio…
dmoszynski Jun 27, 2024
f142c10
feat(entity_manager, simulator_core): remove activateOutOfRangeJob fo…
dmoszynski Jun 27, 2024
f057e68
feat(api, entity_manager, cpp_mock): rename entityExist to isEntitySp…
dmoszynski Jun 27, 2024
d287360
feat(ego_entity, sumulator_core): remove asFieldOperatorApplication, …
dmoszynski Jun 28, 2024
daa67d1
Merge branch 'RJD-1057-remove-traffic-lights-from-entity-manager' int…
dmoszynski Jun 28, 2024
0fcc813
feat(api, simulator_core): emove getTimeHeadway from API, use directl…
dmoszynski Jun 28, 2024
52b44ca
feat(simulator_core, api, entity_base, cpp_mock): move setEntityStatu…
dmoszynski Jun 28, 2024
8b478db
Fix mock scenario with invalid entity
TauTheLepton Jun 28, 2024
56ca207
Restore previous scenario condition
TauTheLepton Jun 28, 2024
8cf8c3a
Fix concealer local address returning
TauTheLepton Jul 1, 2024
07aae15
feat(entity_base, entity_status): improve ::setStatus
dmoszynski Jul 1, 2024
9ca9eed
Fix random_test_runner
TauTheLepton Jul 30, 2024
ce9b59a
Merge remote-tracking branch 'tier4/RJD-1057-remove-traffic-lights-fr…
TauTheLepton Jul 31, 2024
1869aa1
Merge remote-tracking branch 'tier4/RJD-1057-traffic-lights-tests' in…
TauTheLepton Jul 31, 2024
8940b3e
Adjust mock scenarios to new API
TauTheLepton Jul 31, 2024
f438056
Merge branch 'RJD-1057-traffic-lights-tests' into RJD-1057-remove-fun…
TauTheLepton Oct 3, 2024
4681b25
Merge remote-tracking branch 'origin/RJD-1057-traffic-lights-tests' i…
dmoszynski Oct 14, 2024
fec8821
fix(cpp_mock_scenarios): merge changes in random001
dmoszynski Oct 14, 2024
f559200
ref(cpp_mock_scenarios): ref random001
dmoszynski Oct 14, 2024
18daa8b
ref(behavior_tree,traffic_simulator): improve code by basing on sonar…
dmoszynski Oct 15, 2024
4eef0ec
ref(cpp_mock_scenarios): improve overall
dmoszynski Oct 15, 2024
1d771b2
ref(cpp_mock_scenarios): improve move_backward
dmoszynski Oct 15, 2024
ace3bc8
ref(traffic_simulator, simulator_core): improve overall
dmoszynski Oct 15, 2024
a2d095f
ref(traffic_simulator): improve requestLaneChange, getEgoName
dmoszynski Oct 16, 2024
8d210d7
Merge remote-tracking branch 'origin/RJD-1057-traffic-lights-tests' i…
dmoszynski Nov 8, 2024
74b99df
ref(traffic_simulator): add const to LongitudinalSpeedPlanner::isTarg…
dmoszynski Nov 8, 2024
9ff87c5
Merge branch 'RJD-1057-traffic-lights-tests' into RJD-1057-remove-fun…
dmoszynski Nov 13, 2024
bf61c9a
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
dmoszynski Dec 4, 2024
59e12f2
ref(traffic_simulator): improve requestClearRoute call for ego_entity
dmoszynski Dec 4, 2024
f794dff
Merge branch 'RJD-1057-remove-functions-forwarded-to-entity-base-midd…
dmoszynski Dec 4, 2024
926c712
ref(traffic_simulator): tiny formatting change
dmoszynski Dec 4, 2024
ca2223c
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
dmoszynski Dec 5, 2024
a0a0cb5
Merge remote-tracking branch 'origin/master' into RJD-1057-remove-fun…
dmoszynski Dec 9, 2024
f1166ed
Merge remote-tracking branch 'origin/master' into RJD-1057-remove-fun…
dmoszynski Dec 11, 2024
4e0c479
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
dmoszynski Dec 11, 2024
153e7b1
ref(traffic_simulator): rename isEntitySpawned to isEntityExist
dmoszynski Dec 12, 2024
7af86bb
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
dmoszynski Dec 12, 2024
27efbd5
ref(behavior_tree_plugin): rename default value of current_action_: "…
dmoszynski Dec 16, 2024
40ff422
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
dmoszynski Dec 16, 2024
73c5223
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
dmoszynski Dec 16, 2024
f2b2dfc
Merge branch 'master' into RJD-1057-remove-functions-forwarded-to-ent…
dmoszynski Dec 17, 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
5 changes: 3 additions & 2 deletions docs/developer_guide/TrafficSimulator.md
Original file line number Diff line number Diff line change
Expand Up @@ -79,14 +79,15 @@ public:
private:
void update()
{
if (api_.reachPosition("ego",
const auto entity = getEntity("ego");
if (entity->isInPosition(
traffic_simulator::helper::constructLaneletPose(34615, 10.0), 5))
{
api_.requestAcquirePosition("ego",
traffic_simulator::helper::constructLaneletPose(35026, 0.0) );
api_.setTargetSpeed("npc2", 13, true);
}
if (api_.reachPosition("ego",
if (entity->isInPosition(
traffic_simulator::helper::constructLaneletPose(34579, 0.0), 5))
{
api_.setTargetSpeed("npc2", 3, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,14 +40,15 @@ class LoadDoNothingPluginScenario : public cpp_mock_scenarios::CppScenarioNode
void onUpdate() override
{
/// @note When using the do_nothing plugin, the return value of the `getCurrentAction` function is always do_nothing.

if (
api_.getCurrentAction("ego") != "do_nothing" ||
api_.getCurrentAction("pedestrian") != "do_nothing") {
api_.getEntity("ego")->getCurrentAction() != "do_nothing" ||
api_.getEntity("pedestrian")->getCurrentAction() != "do_nothing") {
stop(cpp_mock_scenarios::Result::FAILURE);
}
if (
api_.getCurrentAction("vehicle_spawn_with_behavior_tree") == "do_nothing" ||
api_.getCurrentAction("pedestrian_spawn_with_behavior_tree") == "do_nothing") {
api_.getEntity("vehicle_spawn_with_behavior_tree")->getCurrentAction() == "do_nothing" ||
api_.getEntity("pedestrian_spawn_with_behavior_tree")->getCurrentAction() == "do_nothing") {
stop(cpp_mock_scenarios::Result::FAILURE);
}
api_.resetBehaviorPlugin(
Expand All @@ -57,8 +58,8 @@ class LoadDoNothingPluginScenario : public cpp_mock_scenarios::CppScenarioNode
"pedestrian_spawn_with_behavior_tree",
traffic_simulator::entity::PedestrianEntity::BuiltinBehavior::doNothing());
if (
api_.getCurrentAction("vehicle_spawn_with_behavior_tree") != "do_nothing" ||
api_.getCurrentAction("pedestrian_spawn_with_behavior_tree") != "do_nothing") {
api_.getEntity("vehicle_spawn_with_behavior_tree")->getCurrentAction() != "do_nothing" ||
api_.getEntity("pedestrian_spawn_with_behavior_tree")->getCurrentAction() != "do_nothing") {
stop(cpp_mock_scenarios::Result::FAILURE);
}

Expand Down
12 changes: 7 additions & 5 deletions mock/cpp_mock_scenarios/src/collision/crashing_npc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,19 +56,21 @@ class CrashingNpcScenario : public cpp_mock_scenarios::CppScenarioNode
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 0.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
api_.setLinearVelocity("ego", 0.0);
api_.requestSpeedChange("ego", 15, true);
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;
api_.setBehaviorParameter("ego", behavior_parameter);
ego_entity->setBehaviorParameter(behavior_parameter);

api_.spawn(
"npc",
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 10.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
api_.setLinearVelocity("npc", 0.0);
api_.requestSpeedChange("npc", 5, true);
auto npc_entity = api_.getEntity("npc");
npc_entity->setLinearVelocity(0.0);
npc_entity->requestSpeedChange(5, true);
}
};
} // namespace cpp_mock_scenarios
Expand Down
10 changes: 6 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 @@ -54,16 +54,18 @@ class SpawnWithOffsetScenario : public cpp_mock_scenarios::CppScenarioNode
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 0.2, 1.3, api_.getHdmapUtils()),
getVehicleParameters());
api_.setLinearVelocity("ego", 0);
api_.requestSpeedChange("ego", 0, true);
auto ego_entity = api_.getEntity("ego");
ego_entity->setLinearVelocity(0);
ego_entity->requestSpeedChange(0, true);

api_.spawn(
"bob",
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 0.0, -0.874, api_.getHdmapUtils()),
getPedestrianParameters());
api_.setLinearVelocity("bob", 0);
api_.requestSpeedChange("bob", 0, true);
auto bob_entity = api_.getEntity("bob");
bob_entity->setLinearVelocity(0);
bob_entity->requestSpeedChange(0, true);
}
};
} // namespace cpp_mock_scenarios
Expand Down
11 changes: 6 additions & 5 deletions mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,8 @@ void CppScenarioNode::spawnEgoEntity(
api_.updateFrame();
std::this_thread::sleep_for(std::chrono::duration<double>(1.0 / 20.0));
api_.spawn("ego", spawn_lanelet_pose, parameters, traffic_simulator::VehicleBehavior::autoware());
api_.asFieldOperatorApplication("ego").declare_parameter<bool>("allow_goal_modification", true);
auto ego_entity = api_.getEgoEntity("ego");
ego_entity->setParameter<bool>("allow_goal_modification", true);
api_.attachLidarSensor("ego", 0.0);

api_.attachDetectionSensor("ego", 200.0, true, 0.0, 0, 0.0, 0.0);
Expand All @@ -123,12 +124,12 @@ void CppScenarioNode::spawnEgoEntity(
// clang-format on
return configuration;
}());
api_.requestAssignRoute("ego", goal_lanelet_poses);
ego_entity->requestAssignRoute(goal_lanelet_poses);

using namespace std::chrono_literals;
while (!api_.asFieldOperatorApplication("ego").engaged()) {
if (api_.asFieldOperatorApplication("ego").engageable()) {
api_.asFieldOperatorApplication("ego").engage();
while (!ego_entity->isEngaged()) {
if (ego_entity->isEngageable()) {
ego_entity->engage();
}
api_.updateFrame();
std::this_thread::sleep_for(std::chrono::duration<double>(1.0 / 20.0));
Expand Down
32 changes: 17 additions & 15 deletions mock/cpp_mock_scenarios/src/crosswalk/stop_at_crosswalk.cpp
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_.entityExists("bob") && api_.checkCollision("ego", "bob")) {
if (api_.isEntityExist("bob") && api_.checkCollision("ego", "bob")) {
stop(cpp_mock_scenarios::Result::FAILURE);
}
/**
Expand All @@ -50,17 +50,18 @@ class StopAtCrosswalkScenario : public cpp_mock_scenarios::CppScenarioNode
* @sa https://wandbox.org/permlink/dSNRX7K2bQiqSI7P
*/
if (t == 1.0) {
if (t != api_.getCurrentTwist("bob").linear.x) {
if (t != api_.getEntity("bob")->getCurrentTwist().linear.x) {
stop(cpp_mock_scenarios::Result::FAILURE);
}
}
const auto ego_linear_velocity = api_.getEntity("ego")->getCurrentTwist().linear.x;
if (t >= 6.6) {
if (7.5 >= t) {
if (std::fabs(0.1) <= api_.getCurrentTwist("ego").linear.x) {
if (std::fabs(0.1) <= ego_linear_velocity) {
stop(cpp_mock_scenarios::Result::FAILURE);
}
} else {
if (0.1 >= api_.getCurrentTwist("ego").linear.x) {
if (0.1 >= ego_linear_velocity) {
stop(cpp_mock_scenarios::Result::FAILURE);
}
}
Expand All @@ -78,23 +79,24 @@ class StopAtCrosswalkScenario : public cpp_mock_scenarios::CppScenarioNode
traffic_simulator::helper::constructCanonicalizedLaneletPose(
120545, 0.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
api_.setLinearVelocity("ego", 10);
api_.requestSpeedChange("ego", 8, true);
api_.requestAssignRoute(
"ego", 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())});
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, api_.getHdmapUtils()),
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34690, 0.0, 0.0, api_.getHdmapUtils())});

api_.spawn(
"bob",
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34378, 0.0, 0.0, api_.getHdmapUtils()),
getPedestrianParameters());
api_.setLinearVelocity("bob", 0);
api_.requestSpeedChange(
"bob", 1.0, traffic_simulator::speed_change::Transition::LINEAR,
auto bob_entity = api_.getEntity("bob");
bob_entity->setLinearVelocity(0);
bob_entity->requestSpeedChange(
1.0, traffic_simulator::speed_change::Transition::LINEAR,
traffic_simulator::speed_change::Constraint(
traffic_simulator::speed_change::Constraint::Type::LONGITUDINAL_ACCELERATION, 1.0),
true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,13 @@ class AccelerateAndFollowScenario : public cpp_mock_scenarios::CppScenarioNode
private:
void onUpdate() override
{
double ego_accel = api_.getCurrentAccel("ego").linear.x;
double ego_twist = api_.getCurrentTwist("ego").linear.x;
// double npc_accel = static_cast<EntityStatus>(api_.getEntityStatus("npc")).action_status.accel.linear.x;
double npc_twist = api_.getCurrentTwist("npc").linear.x;
;
double ego_linear_acceleration = api_.getEntity("ego")->getCurrentAccel().linear.x;
double ego_linear_velocity = api_.getEntity("ego")->getCurrentTwist().linear.x;
// double npc_linear_acceleration = api_.getEntity("npc")->getCurrentAccel().linear.x;
double npc_linear_velocity = api_.getEntity("npc")->getCurrentTwist().linear.x;

// LCOV_EXCL_START
if (npc_twist > (ego_twist + 1) && ego_accel < 0) {
if (npc_linear_velocity > (ego_linear_velocity + 1) && ego_linear_acceleration < 0) {
stop(cpp_mock_scenarios::Result::FAILURE);
}
if (api_.checkCollision("ego", "npc")) {
Expand All @@ -63,15 +63,16 @@ class AccelerateAndFollowScenario : public cpp_mock_scenarios::CppScenarioNode
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 0.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
api_.setLinearVelocity("ego", 3);
api_.getEntity("ego")->setLinearVelocity(3);

api_.spawn(
"npc",
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 10.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
api_.setLinearVelocity("npc", 10);
api_.requestSpeedChange("npc", 10, true);
auto npc_entity = api_.getEntity("npc");
npc_entity->setLinearVelocity(10);
npc_entity->requestSpeedChange(10, true);
}
};
} // namespace cpp_mock_scenarios
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,13 @@ class DecelerateAndFollowScenario : public cpp_mock_scenarios::CppScenarioNode
private:
void onUpdate() override
{
double ego_accel = api_.getCurrentAccel("ego").linear.x;
double ego_twist = api_.getCurrentTwist("ego").linear.x;
// double npc_accel = static_cast<EntityStatus>(api_.getEntityStatus("npc")).action_status.accel.linear.x;
double npc_twist = api_.getCurrentTwist("npc").linear.x;
;
double ego_linear_acceleration = api_.getEntity("ego")->getCurrentAccel().linear.x;
double ego_linear_velocity = api_.getEntity("ego")->getCurrentTwist().linear.x;
// double npc_linear_acceleration = api_.getEntity("npc")->getCurrentAccel().linear.x;
double npc_linear_velocity = api_.getEntity("npc")->getCurrentTwist().linear.x;

// LCOV_EXCL_START
if (ego_twist > (npc_twist + 1) && ego_accel > 0) {
if (ego_linear_velocity > (npc_linear_velocity + 1) && ego_linear_acceleration > 0) {
stop(cpp_mock_scenarios::Result::FAILURE);
}
if (api_.checkCollision("ego", "npc")) {
Expand All @@ -63,15 +63,16 @@ class DecelerateAndFollowScenario : public cpp_mock_scenarios::CppScenarioNode
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 0.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
api_.setLinearVelocity("ego", 15);
api_.getEntity("ego")->setLinearVelocity(15);

api_.spawn(
"npc",
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 15.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
api_.setLinearVelocity("npc", 10);
api_.requestSpeedChange("npc", 10, true);
auto npc_entity = api_.getEntity("npc");
npc_entity->setLinearVelocity(10);
npc_entity->requestSpeedChange(10, true);
}
};
} // namespace cpp_mock_scenarios
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ class AcquirePositionInWorldFrameScenario : public cpp_mock_scenarios::CppScenar
bool requested = false;
void onUpdate() override
{
if (api_.isInLanelet("ego", 34408, 0.1)) {
if (api_.getEntity("ego")->isInLanelet(34408, 0.1)) {
stop(cpp_mock_scenarios::Result::SUCCESS);
}
}
Expand All @@ -51,16 +51,16 @@ class AcquirePositionInWorldFrameScenario : public cpp_mock_scenarios::CppScenar
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 10.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
api_.setEntityStatus(
"ego",
auto ego_entity = api_.getEntity("ego");
ego_entity->setStatus(
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34513, 0.0, 0.0, api_.getHdmapUtils()),
traffic_simulator::helper::constructActionStatus(10));
api_.requestSpeedChange("ego", 10, true);
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()));
api_.requestAcquirePosition("ego", goal_pose);
ego_entity->requestAcquirePosition(goal_pose);
}
};
} // namespace cpp_mock_scenarios
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ class AcquireRouteInWorldFrameScenario : public cpp_mock_scenarios::CppScenarioN
bool requested = false;
void onUpdate() override
{
if (api_.isInLanelet("ego", 34630, 0.1)) {
if (api_.getEntity("ego")->isInLanelet(34630, 0.1)) {
stop(cpp_mock_scenarios::Result::SUCCESS);
}
}
Expand All @@ -51,16 +51,17 @@ class AcquireRouteInWorldFrameScenario : public cpp_mock_scenarios::CppScenarioN
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34513, 0.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
api_.setLinearVelocity("ego", 10);
api_.requestSpeedChange("ego", 10, true);
auto ego_entity = api_.getEntity("ego");
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())));
goal_poses.emplace_back(traffic_simulator::pose::toMapPose(
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34408, 10, 0.0, api_.getHdmapUtils())));
api_.requestAssignRoute("ego", goal_poses);
ego_entity->requestAssignRoute(goal_poses);
}
};
} // namespace cpp_mock_scenarios
Expand Down
15 changes: 8 additions & 7 deletions mock/cpp_mock_scenarios/src/follow_lane/cancel_request.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,15 +39,15 @@ class CancelRequestScenario : public cpp_mock_scenarios::CppScenarioNode
bool canceled = false;
void onUpdate() override
{
if (api_.reachPosition(
"ego",
const auto ego_entity = api_.getEntity("ego");
if (ego_entity->isInPosition(
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34513, 30, 0, api_.getHdmapUtils()),
3.0)) {
api_.cancelRequest("ego");
ego_entity->cancelRequest();
canceled = true;
}
if (api_.isInLanelet("ego", 34507, 0.1)) {
if (ego_entity->isInLanelet(34507, 0.1)) {
stop(cpp_mock_scenarios::Result::SUCCESS);
}
}
Expand All @@ -58,11 +58,12 @@ class CancelRequestScenario : public cpp_mock_scenarios::CppScenarioNode
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34513, 0.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
api_.setLinearVelocity("ego", 7);
api_.requestSpeedChange("ego", 7, true);
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(
traffic_simulator::helper::constructLaneletPose(34408, 0.0, 0.0), api_.getHdmapUtils());
api_.requestAcquirePosition("ego", goal_pose);
ego_entity->requestAcquirePosition(goal_pose);
}
};
} // namespace cpp_mock_scenarios
Expand Down
Loading
Loading