diff --git a/mock/cpp_mock_scenarios/src/behavior_plugin/load_do_nothing_plugin.cpp b/mock/cpp_mock_scenarios/src/behavior_plugin/load_do_nothing_plugin.cpp index 2fb23334578..91c66da9697 100644 --- a/mock/cpp_mock_scenarios/src/behavior_plugin/load_do_nothing_plugin.cpp +++ b/mock/cpp_mock_scenarios/src/behavior_plugin/load_do_nothing_plugin.cpp @@ -42,13 +42,13 @@ class LoadDoNothingPluginScenario : public cpp_mock_scenarios::CppScenarioNode /// @note When using the do_nothing plugin, the return value of the `getCurrentAction` function is always do_nothing. if ( - api_.getEntity("ego")->getCurrentAction() != "do_nothing" || - api_.getEntity("pedestrian")->getCurrentAction() != "do_nothing") { + api_.getEntity("ego").getCurrentAction() != "do_nothing" || + api_.getEntity("pedestrian").getCurrentAction() != "do_nothing") { stop(cpp_mock_scenarios::Result::FAILURE); } if ( - api_.getEntity("vehicle_spawn_with_behavior_tree")->getCurrentAction() == "do_nothing" || - api_.getEntity("pedestrian_spawn_with_behavior_tree")->getCurrentAction() == "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( @@ -58,8 +58,8 @@ class LoadDoNothingPluginScenario : public cpp_mock_scenarios::CppScenarioNode "pedestrian_spawn_with_behavior_tree", traffic_simulator::entity::PedestrianEntity::BuiltinBehavior::doNothing()); if ( - api_.getEntity("vehicle_spawn_with_behavior_tree")->getCurrentAction() != "do_nothing" || - api_.getEntity("pedestrian_spawn_with_behavior_tree")->getCurrentAction() != "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); } diff --git a/mock/cpp_mock_scenarios/src/collision/crashing_npc.cpp b/mock/cpp_mock_scenarios/src/collision/crashing_npc.cpp index d7e7ea1e11c..c2d6ed15468 100644 --- a/mock/cpp_mock_scenarios/src/collision/crashing_npc.cpp +++ b/mock/cpp_mock_scenarios/src/collision/crashing_npc.cpp @@ -56,21 +56,21 @@ class CrashingNpcScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0.0); - ego_entity->requestSpeedChange(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; - ego_entity->setBehaviorParameter(behavior_parameter); + ego_entity.setBehaviorParameter(behavior_parameter); api_.spawn( "npc", traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto npc_entity = api_.getEntity("npc"); - npc_entity->setLinearVelocity(0.0); - npc_entity->requestSpeedChange(5, true); + auto & npc_entity = api_.getEntity("npc"); + npc_entity.setLinearVelocity(0.0); + npc_entity.requestSpeedChange(5, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/collision/spawn_with_offset.cpp b/mock/cpp_mock_scenarios/src/collision/spawn_with_offset.cpp index 59cb53f753d..66e141e15dd 100644 --- a/mock/cpp_mock_scenarios/src/collision/spawn_with_offset.cpp +++ b/mock/cpp_mock_scenarios/src/collision/spawn_with_offset.cpp @@ -54,18 +54,18 @@ class SpawnWithOffsetScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.2, 1.3, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0); - ego_entity->requestSpeedChange(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()); - auto bob_entity = api_.getEntity("bob"); - bob_entity->setLinearVelocity(0); - bob_entity->requestSpeedChange(0, true); + auto & bob_entity = api_.getEntity("bob"); + bob_entity.setLinearVelocity(0); + bob_entity.requestSpeedChange(0, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp b/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp index a6443c234c1..f4b27729b4c 100644 --- a/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp +++ b/mock/cpp_mock_scenarios/src/cpp_scenario_node.cpp @@ -106,8 +106,8 @@ void CppScenarioNode::spawnEgoEntity( api_.updateFrame(); std::this_thread::sleep_for(std::chrono::duration(1.0 / 20.0)); api_.spawn("ego", spawn_lanelet_pose, parameters, traffic_simulator::VehicleBehavior::autoware()); - auto ego_entity = api_.getEgoEntity("ego"); - ego_entity->setParameter("allow_goal_modification", true); + auto & ego_entity = api_.getEgoEntity("ego"); + ego_entity.setParameter("allow_goal_modification", true); api_.attachLidarSensor("ego", 0.0); api_.attachDetectionSensor("ego", 200.0, true, 0.0, 0, 0.0, 0.0); @@ -126,12 +126,12 @@ void CppScenarioNode::spawnEgoEntity( // clang-format on return configuration; }()); - ego_entity->requestAssignRoute(goal_lanelet_poses); + ego_entity.requestAssignRoute(goal_lanelet_poses); using namespace std::chrono_literals; - while (!ego_entity->isEngaged()) { - if (ego_entity->isEngageable()) { - ego_entity->engage(); + while (!ego_entity.isEngaged()) { + if (ego_entity.isEngageable()) { + ego_entity.engage(); } api_.updateFrame(); std::this_thread::sleep_for(std::chrono::duration(1.0 / 20.0)); @@ -140,13 +140,13 @@ void CppScenarioNode::spawnEgoEntity( auto CppScenarioNode::isVehicle(const std::string & name) const -> bool { - return api_.getEntity(name)->getEntityType().type == + return api_.getEntity(name).getEntityType().type == traffic_simulator_msgs::msg::EntityType::VEHICLE; } auto CppScenarioNode::isPedestrian(const std::string & name) const -> bool { - return api_.getEntity(name)->getEntityType().type == + return api_.getEntity(name).getEntityType().type == traffic_simulator_msgs::msg::EntityType::PEDESTRIAN; } diff --git a/mock/cpp_mock_scenarios/src/crosswalk/stop_at_crosswalk.cpp b/mock/cpp_mock_scenarios/src/crosswalk/stop_at_crosswalk.cpp index 90cecc4d835..dbc827005be 100644 --- a/mock/cpp_mock_scenarios/src/crosswalk/stop_at_crosswalk.cpp +++ b/mock/cpp_mock_scenarios/src/crosswalk/stop_at_crosswalk.cpp @@ -50,11 +50,11 @@ class StopAtCrosswalkScenario : public cpp_mock_scenarios::CppScenarioNode * @sa https://wandbox.org/permlink/dSNRX7K2bQiqSI7P */ if (t == 1.0) { - if (t != api_.getEntity("bob")->getCurrentTwist().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; + const auto ego_linear_velocity = api_.getEntity("ego").getCurrentTwist().linear.x; if (t >= 6.6) { if (7.5 >= t) { if (std::fabs(0.1) <= ego_linear_velocity) { @@ -79,10 +79,10 @@ class StopAtCrosswalkScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 120545, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(10); - ego_entity->requestSpeedChange(8, true); - ego_entity->requestAssignRoute(std::vector{ + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(8, true); + ego_entity.requestAssignRoute(std::vector{ traffic_simulator::helper::constructCanonicalizedLaneletPose( 34675, 0.0, 0.0, api_.getHdmapUtils()), traffic_simulator::helper::constructCanonicalizedLaneletPose( @@ -93,9 +93,9 @@ class StopAtCrosswalkScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34378, 0.0, 0.0, api_.getHdmapUtils()), getPedestrianParameters()); - auto bob_entity = api_.getEntity("bob"); - bob_entity->setLinearVelocity(0); - bob_entity->requestSpeedChange( + 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), diff --git a/mock/cpp_mock_scenarios/src/follow_front_entity/accelerate_and_follow.cpp b/mock/cpp_mock_scenarios/src/follow_front_entity/accelerate_and_follow.cpp index e3ef445909a..1cc1bc21cec 100644 --- a/mock/cpp_mock_scenarios/src/follow_front_entity/accelerate_and_follow.cpp +++ b/mock/cpp_mock_scenarios/src/follow_front_entity/accelerate_and_follow.cpp @@ -39,10 +39,9 @@ class AccelerateAndFollowScenario : public cpp_mock_scenarios::CppScenarioNode private: void onUpdate() override { - 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; + const double ego_linear_acceleration = api_.getEntity("ego").getCurrentAccel().linear.x; + const double ego_linear_velocity = api_.getEntity("ego").getCurrentTwist().linear.x; + const double npc_linear_velocity = api_.getEntity("npc").getCurrentTwist().linear.x; // LCOV_EXCL_START if (npc_linear_velocity > (ego_linear_velocity + 1) && ego_linear_acceleration < 0) { @@ -63,16 +62,16 @@ class AccelerateAndFollowScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - api_.getEntity("ego")->setLinearVelocity(3); + api_.getEntity("ego").setLinearVelocity(3); api_.spawn( "npc", traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto npc_entity = api_.getEntity("npc"); - npc_entity->setLinearVelocity(10); - npc_entity->requestSpeedChange(10, true); + auto & npc_entity = api_.getEntity("npc"); + npc_entity.setLinearVelocity(10); + npc_entity.requestSpeedChange(10, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/follow_front_entity/decelerate_and_follow.cpp b/mock/cpp_mock_scenarios/src/follow_front_entity/decelerate_and_follow.cpp index 25d23f49941..12a92fb5656 100644 --- a/mock/cpp_mock_scenarios/src/follow_front_entity/decelerate_and_follow.cpp +++ b/mock/cpp_mock_scenarios/src/follow_front_entity/decelerate_and_follow.cpp @@ -39,10 +39,9 @@ class DecelerateAndFollowScenario : public cpp_mock_scenarios::CppScenarioNode private: void onUpdate() override { - 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; + const double ego_linear_acceleration = api_.getEntity("ego").getCurrentAccel().linear.x; + const double ego_linear_velocity = api_.getEntity("ego").getCurrentTwist().linear.x; + const double npc_linear_velocity = api_.getEntity("npc").getCurrentTwist().linear.x; // LCOV_EXCL_START if (ego_linear_velocity > (npc_linear_velocity + 1) && ego_linear_acceleration > 0) { @@ -63,16 +62,16 @@ class DecelerateAndFollowScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - api_.getEntity("ego")->setLinearVelocity(15); + api_.getEntity("ego").setLinearVelocity(15); api_.spawn( "npc", traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 15.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto npc_entity = api_.getEntity("npc"); - npc_entity->setLinearVelocity(10); - npc_entity->requestSpeedChange(10, true); + auto & npc_entity = api_.getEntity("npc"); + npc_entity.setLinearVelocity(10); + npc_entity.requestSpeedChange(10, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/follow_lane/acquire_position_in_world_frame.cpp b/mock/cpp_mock_scenarios/src/follow_lane/acquire_position_in_world_frame.cpp index 4912db96ea2..6c8149044bc 100644 --- a/mock/cpp_mock_scenarios/src/follow_lane/acquire_position_in_world_frame.cpp +++ b/mock/cpp_mock_scenarios/src/follow_lane/acquire_position_in_world_frame.cpp @@ -40,7 +40,7 @@ class AcquirePositionInWorldFrameScenario : public cpp_mock_scenarios::CppScenar bool requested = false; void onUpdate() override { - if (api_.getEntity("ego")->isInLanelet(34408, 0.1)) { + if (api_.getEntity("ego").isInLanelet(34408, 0.1)) { stop(cpp_mock_scenarios::Result::SUCCESS); } } @@ -51,16 +51,16 @@ class AcquirePositionInWorldFrameScenario : public cpp_mock_scenarios::CppScenar traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setStatus( + 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)); - ego_entity->requestSpeedChange(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())); - ego_entity->requestAcquirePosition(goal_pose); + ego_entity.requestAcquirePosition(goal_pose); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/follow_lane/assign_route_in_world_frame.cpp b/mock/cpp_mock_scenarios/src/follow_lane/assign_route_in_world_frame.cpp index 41360172631..360c168c02c 100644 --- a/mock/cpp_mock_scenarios/src/follow_lane/assign_route_in_world_frame.cpp +++ b/mock/cpp_mock_scenarios/src/follow_lane/assign_route_in_world_frame.cpp @@ -40,7 +40,7 @@ class AcquireRouteInWorldFrameScenario : public cpp_mock_scenarios::CppScenarioN bool requested = false; void onUpdate() override { - if (api_.getEntity("ego")->isInLanelet(34630, 0.1)) { + if (api_.getEntity("ego").isInLanelet(34630, 0.1)) { stop(cpp_mock_scenarios::Result::SUCCESS); } } @@ -51,9 +51,9 @@ class AcquireRouteInWorldFrameScenario : public cpp_mock_scenarios::CppScenarioN traffic_simulator::helper::constructCanonicalizedLaneletPose( 34513, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(10); - ego_entity->requestSpeedChange(10, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(10, true); std::vector goal_poses; goal_poses.emplace_back(traffic_simulator::pose::toMapPose( traffic_simulator::helper::constructCanonicalizedLaneletPose( @@ -61,7 +61,7 @@ class AcquireRouteInWorldFrameScenario : public cpp_mock_scenarios::CppScenarioN goal_poses.emplace_back(traffic_simulator::pose::toMapPose( traffic_simulator::helper::constructCanonicalizedLaneletPose( 34408, 10, 0.0, api_.getHdmapUtils()))); - ego_entity->requestAssignRoute(goal_poses); + ego_entity.requestAssignRoute(goal_poses); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/follow_lane/cancel_request.cpp b/mock/cpp_mock_scenarios/src/follow_lane/cancel_request.cpp index 54c59f313fd..94e48b0f3a0 100644 --- a/mock/cpp_mock_scenarios/src/follow_lane/cancel_request.cpp +++ b/mock/cpp_mock_scenarios/src/follow_lane/cancel_request.cpp @@ -39,15 +39,15 @@ class CancelRequestScenario : public cpp_mock_scenarios::CppScenarioNode bool canceled = false; void onUpdate() override { - const auto ego_entity = api_.getEntity("ego"); - if (ego_entity->isInPosition( + auto & ego_entity = api_.getEntity("ego"); + if (ego_entity.isInPosition( traffic_simulator::helper::constructCanonicalizedLaneletPose( 34513, 30, 0, api_.getHdmapUtils()), 3.0)) { - ego_entity->cancelRequest(); + ego_entity.cancelRequest(); canceled = true; } - if (ego_entity->isInLanelet(34507, 0.1)) { + if (ego_entity.isInLanelet(34507, 0.1)) { stop(cpp_mock_scenarios::Result::SUCCESS); } } @@ -58,12 +58,12 @@ class CancelRequestScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34513, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(7); - ego_entity->requestSpeedChange(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()); - ego_entity->requestAcquirePosition(goal_pose); + ego_entity.requestAcquirePosition(goal_pose); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/follow_lane/follow_with_offset.cpp b/mock/cpp_mock_scenarios/src/follow_lane/follow_with_offset.cpp index da8c60d40e6..b2003ae8677 100644 --- a/mock/cpp_mock_scenarios/src/follow_lane/follow_with_offset.cpp +++ b/mock/cpp_mock_scenarios/src/follow_lane/follow_with_offset.cpp @@ -40,11 +40,11 @@ class FollowLaneWithOffsetScenario : public cpp_mock_scenarios::CppScenarioNode bool requested = false; void onUpdate() override { - if (const auto ego_entity = api_.getEntity("ego"); !ego_entity->isInLanelet()) { + if (const auto & ego_entity = api_.getEntity("ego"); !ego_entity.isInLanelet()) { stop(cpp_mock_scenarios::Result::FAILURE); - } else if (ego_entity->isInLanelet(34507, 0.1)) { + } else if (ego_entity.isInLanelet(34507, 0.1)) { stop(cpp_mock_scenarios::Result::SUCCESS); - } else if (std::abs(ego_entity->getCanonicalizedStatus().getLaneletPose().offset) <= 2.8) { + } else if (std::abs(ego_entity.getCanonicalizedStatus().getLaneletPose().offset) <= 2.8) { stop(cpp_mock_scenarios::Result::FAILURE); } } @@ -55,9 +55,9 @@ class FollowLaneWithOffsetScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34513, 0.0, 3.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(10); - ego_entity->requestSpeedChange(10, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(10, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/follow_trajectory/follow_polyline_trajectory_with_do_nothing_plugin.cpp b/mock/cpp_mock_scenarios/src/follow_trajectory/follow_polyline_trajectory_with_do_nothing_plugin.cpp index 18a062c731a..f10d2194d02 100644 --- a/mock/cpp_mock_scenarios/src/follow_trajectory/follow_polyline_trajectory_with_do_nothing_plugin.cpp +++ b/mock/cpp_mock_scenarios/src/follow_trajectory/follow_polyline_trajectory_with_do_nothing_plugin.cpp @@ -63,32 +63,32 @@ class FollowPolylineTrajectoryWithDoNothingPluginScenario void onUpdate() override { - const auto ego_entity = api_.getEntity("ego"); + const auto & ego_entity = api_.getEntity("ego"); // LCOV_EXCL_START if (api_.getCurrentTime() >= 10.0) { stop(cpp_mock_scenarios::Result::FAILURE); } // LCOV_EXCL_STOP - if (equals(api_.getCurrentTime(), 0.0, 0.01) && !ego_entity->isInPosition(spawn_pose, 0.1)) { + if (equals(api_.getCurrentTime(), 0.0, 0.01) && !ego_entity.isInPosition(spawn_pose, 0.1)) { stop(cpp_mock_scenarios::Result::FAILURE); } if ( equals(api_.getCurrentTime(), 1.0, 0.01) && - !ego_entity->isInPosition(trajectory_start_pose, 0.1)) { + !ego_entity.isInPosition(trajectory_start_pose, 0.1)) { stop(cpp_mock_scenarios::Result::FAILURE); } if ( equals(api_.getCurrentTime(), 1.5, 0.01) && - !ego_entity->isInPosition(trajectory_waypoint_pose, 0.1)) { + !ego_entity.isInPosition(trajectory_waypoint_pose, 0.1)) { stop(cpp_mock_scenarios::Result::FAILURE); } if ( equals(api_.getCurrentTime(), 2.0, 0.01) && - !ego_entity->isInPosition(trajectory_goal_pose, 0.1)) { + !ego_entity.isInPosition(trajectory_goal_pose, 0.1)) { stop(cpp_mock_scenarios::Result::FAILURE); } if (equals(api_.getCurrentTime(), 2.5, 0.01)) { - if (ego_entity->isInPosition(trajectory_goal_pose, 0.1)) { + if (ego_entity.isInPosition(trajectory_goal_pose, 0.1)) { stop(cpp_mock_scenarios::Result::SUCCESS); } else { stop(cpp_mock_scenarios::Result::FAILURE); @@ -100,10 +100,10 @@ class FollowPolylineTrajectoryWithDoNothingPluginScenario 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( + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(10, true); + ego_entity.requestFollowTrajectory( std::make_shared( traffic_simulator_msgs::build() .initial_distance_offset(0.0) diff --git a/mock/cpp_mock_scenarios/src/lane_change/lanechange_left.cpp b/mock/cpp_mock_scenarios/src/lane_change/lanechange_left.cpp index f20d484c2d8..3c01dce454a 100644 --- a/mock/cpp_mock_scenarios/src/lane_change/lanechange_left.cpp +++ b/mock/cpp_mock_scenarios/src/lane_change/lanechange_left.cpp @@ -39,7 +39,7 @@ class LaneChangeLeftScenario : public cpp_mock_scenarios::CppScenarioNode bool requested = false; void onUpdate() override { - if (api_.getEntity("ego")->isInLanelet(34513, 0.1)) { + if (api_.getEntity("ego").isInLanelet(34513, 0.1)) { stop(cpp_mock_scenarios::Result::SUCCESS); } // LCOV_EXCL_START @@ -55,10 +55,10 @@ class LaneChangeLeftScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34462, 10.0, 0.0, api_.getHdmapUtils()), 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); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(10, true); + ego_entity.requestLaneChange(traffic_simulator::lane_change::Direction::LEFT); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/lane_change/lanechange_left_with_id.cpp b/mock/cpp_mock_scenarios/src/lane_change/lanechange_left_with_id.cpp index 3dc21831bd8..5c7fea9b2d5 100644 --- a/mock/cpp_mock_scenarios/src/lane_change/lanechange_left_with_id.cpp +++ b/mock/cpp_mock_scenarios/src/lane_change/lanechange_left_with_id.cpp @@ -39,7 +39,7 @@ class LaneChangeLeftWithIdScenario : public cpp_mock_scenarios::CppScenarioNode bool requested = false; void onUpdate() override { - if (api_.getEntity("ego")->isInLanelet(34513, 0.1)) { + if (api_.getEntity("ego").isInLanelet(34513, 0.1)) { stop(cpp_mock_scenarios::Result::SUCCESS); } // LCOV_EXCL_START @@ -55,10 +55,10 @@ class LaneChangeLeftWithIdScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34462, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(10); - ego_entity->requestSpeedChange(10, true); - ego_entity->requestLaneChange(34513); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(10, true); + ego_entity.requestLaneChange(34513); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/lane_change/lanechange_linear.cpp b/mock/cpp_mock_scenarios/src/lane_change/lanechange_linear.cpp index 466bac3ea24..771f42c6f9d 100644 --- a/mock/cpp_mock_scenarios/src/lane_change/lanechange_linear.cpp +++ b/mock/cpp_mock_scenarios/src/lane_change/lanechange_linear.cpp @@ -40,11 +40,11 @@ class LaneChangeLinearScenario : public cpp_mock_scenarios::CppScenarioNode bool lanechange_finished = false; void onUpdate() override { - const auto ego_entity = api_.getEntity("ego"); - if (ego_entity->isInLanelet(34513, 0.1)) { + const auto & ego_entity = api_.getEntity("ego"); + if (ego_entity.isInLanelet(34513, 0.1)) { lanechange_finished = true; } - if (lanechange_finished && ego_entity->isInLanelet(34510, 0.1)) { + if (lanechange_finished && ego_entity.isInLanelet(34510, 0.1)) { stop(cpp_mock_scenarios::Result::SUCCESS); } // LCOV_EXCL_START @@ -60,10 +60,10 @@ class LaneChangeLinearScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34462, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(10); - ego_entity->requestSpeedChange(10, true); - ego_entity->requestLaneChange( + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(10, true); + ego_entity.requestLaneChange( traffic_simulator::lane_change::RelativeTarget( "ego", traffic_simulator::lane_change::Direction::LEFT, 1, 0), traffic_simulator::lane_change::TrajectoryShape::LINEAR, diff --git a/mock/cpp_mock_scenarios/src/lane_change/lanechange_linear_lateral_velocity.cpp b/mock/cpp_mock_scenarios/src/lane_change/lanechange_linear_lateral_velocity.cpp index b268fae2ac0..1e3c2dbb1f7 100644 --- a/mock/cpp_mock_scenarios/src/lane_change/lanechange_linear_lateral_velocity.cpp +++ b/mock/cpp_mock_scenarios/src/lane_change/lanechange_linear_lateral_velocity.cpp @@ -39,11 +39,11 @@ class LaneChangeLinearLateralVelocityScenario : public cpp_mock_scenarios::CppSc int lanechange_frames = 0; void onUpdate() override { - const auto ego_entity = api_.getEntity("ego"); - if (ego_entity->getCurrentAction() == "lane_change") { + const auto & ego_entity = api_.getEntity("ego"); + if (ego_entity.getCurrentAction() == "lane_change") { lanechange_frames++; } - if (ego_entity->getCurrentAction() != "lane_change" && api_.getCurrentTime() >= 2.0) { + if (ego_entity.getCurrentAction() != "lane_change" && api_.getCurrentTime() >= 2.0) { double duration = static_cast(lanechange_frames) * 0.05; if (duration >= 3.05 && 3.1 >= duration) { stop(cpp_mock_scenarios::Result::SUCCESS); @@ -64,10 +64,10 @@ class LaneChangeLinearLateralVelocityScenario : public cpp_mock_scenarios::CppSc traffic_simulator::helper::constructCanonicalizedLaneletPose( 34462, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(10); - ego_entity->requestSpeedChange(10, true); - ego_entity->requestLaneChange( + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(10, true); + ego_entity.requestLaneChange( traffic_simulator::lane_change::RelativeTarget( "ego", traffic_simulator::lane_change::Direction::LEFT, 1, 0), traffic_simulator::lane_change::TrajectoryShape::LINEAR, diff --git a/mock/cpp_mock_scenarios/src/lane_change/lanechange_linear_time.cpp b/mock/cpp_mock_scenarios/src/lane_change/lanechange_linear_time.cpp index 910781c7ae9..62a69f31bfd 100644 --- a/mock/cpp_mock_scenarios/src/lane_change/lanechange_linear_time.cpp +++ b/mock/cpp_mock_scenarios/src/lane_change/lanechange_linear_time.cpp @@ -39,11 +39,11 @@ class LaneChangeLinearTimeScenario : public cpp_mock_scenarios::CppScenarioNode int lanechange_frames = 0; void onUpdate() override { - const auto ego_entity = api_.getEntity("ego"); - if (ego_entity->getCurrentAction() == "lane_change") { + const auto & ego_entity = api_.getEntity("ego"); + if (ego_entity.getCurrentAction() == "lane_change") { lanechange_frames++; } - if (ego_entity->getCurrentAction() != "lane_change" && api_.getCurrentTime() >= 10.0) { + if (ego_entity.getCurrentAction() != "lane_change" && api_.getCurrentTime() >= 10.0) { if (const double step_time = 50e-3, expected_time = 20.0, real_time = static_cast(lanechange_frames) * step_time; expected_time - step_time <= real_time && real_time <= expected_time + step_time) { @@ -65,10 +65,10 @@ class LaneChangeLinearTimeScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34462, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(10); - ego_entity->requestSpeedChange(10, true); - ego_entity->requestLaneChange( + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(10, true); + ego_entity.requestLaneChange( traffic_simulator::lane_change::RelativeTarget( "ego", traffic_simulator::lane_change::Direction::LEFT, 1, 0), traffic_simulator::lane_change::TrajectoryShape::LINEAR, diff --git a/mock/cpp_mock_scenarios/src/lane_change/lanechange_longitudinal_distance.cpp b/mock/cpp_mock_scenarios/src/lane_change/lanechange_longitudinal_distance.cpp index cedf85c2273..a3c39b78b60 100644 --- a/mock/cpp_mock_scenarios/src/lane_change/lanechange_longitudinal_distance.cpp +++ b/mock/cpp_mock_scenarios/src/lane_change/lanechange_longitudinal_distance.cpp @@ -40,7 +40,7 @@ class LaneChangeLongitudinalDistanceScenario : public cpp_mock_scenarios::CppSce bool lanechange_finished = false; void onUpdate() override { - if (api_.getEntity("ego")->isInLanelet(34513, 0.1)) { + if (api_.getEntity("ego").isInLanelet(34513, 0.1)) { stop(cpp_mock_scenarios::Result::SUCCESS); } } @@ -51,10 +51,10 @@ class LaneChangeLongitudinalDistanceScenario : public cpp_mock_scenarios::CppSce traffic_simulator::helper::constructCanonicalizedLaneletPose( 34462, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(1); - ego_entity->requestSpeedChange(1, true); - ego_entity->requestLaneChange( + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(1); + ego_entity.requestSpeedChange(1, true); + ego_entity.requestLaneChange( traffic_simulator::lane_change::RelativeTarget( "ego", traffic_simulator::lane_change::Direction::LEFT, 1, 0), traffic_simulator::lane_change::TrajectoryShape::CUBIC, diff --git a/mock/cpp_mock_scenarios/src/lane_change/lanechange_right.cpp b/mock/cpp_mock_scenarios/src/lane_change/lanechange_right.cpp index 1396b4ae61b..757e7f4e19c 100644 --- a/mock/cpp_mock_scenarios/src/lane_change/lanechange_right.cpp +++ b/mock/cpp_mock_scenarios/src/lane_change/lanechange_right.cpp @@ -39,7 +39,7 @@ class LaneChangeRightScenario : public cpp_mock_scenarios::CppScenarioNode bool requested = false; void onUpdate() override { - if (api_.getEntity("ego")->isInLanelet(34462, 0.1)) { + if (api_.getEntity("ego").isInLanelet(34462, 0.1)) { stop(cpp_mock_scenarios::Result::SUCCESS); } // LCOV_EXCL_START @@ -55,11 +55,10 @@ class LaneChangeRightScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34513, 10.0, 0.0, api_.getHdmapUtils()), 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); - // ego_entity->requestLaneChange(34462); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(10, true); + ego_entity.requestLaneChange(traffic_simulator::lane_change::Direction::RIGHT); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/lane_change/lanechange_right_with_id.cpp b/mock/cpp_mock_scenarios/src/lane_change/lanechange_right_with_id.cpp index 1d0d29db318..9d18184cbbd 100644 --- a/mock/cpp_mock_scenarios/src/lane_change/lanechange_right_with_id.cpp +++ b/mock/cpp_mock_scenarios/src/lane_change/lanechange_right_with_id.cpp @@ -39,7 +39,7 @@ class LaneChangeRightWithIdScenario : public cpp_mock_scenarios::CppScenarioNode bool requested = false; void onUpdate() override { - if (api_.getEntity("ego")->isInLanelet(34462, 0.1)) { + if (api_.getEntity("ego").isInLanelet(34462, 0.1)) { stop(cpp_mock_scenarios::Result::SUCCESS); } // LCOV_EXCL_START @@ -55,10 +55,10 @@ class LaneChangeRightWithIdScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34513, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(10); - ego_entity->requestSpeedChange(10, true); - ego_entity->requestLaneChange(34462); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(10, true); + ego_entity.requestLaneChange(34462); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/lane_change/lanechange_time.cpp b/mock/cpp_mock_scenarios/src/lane_change/lanechange_time.cpp index b49516c316c..a0176528c8b 100644 --- a/mock/cpp_mock_scenarios/src/lane_change/lanechange_time.cpp +++ b/mock/cpp_mock_scenarios/src/lane_change/lanechange_time.cpp @@ -39,11 +39,11 @@ class LaneChangeTimeScenario : public cpp_mock_scenarios::CppScenarioNode int lanechange_frames = 0; void onUpdate() override { - const auto ego_entity = api_.getEntity("ego"); - if (ego_entity->getCurrentAction() == "lane_change") { + const auto & ego_entity = api_.getEntity("ego"); + if (ego_entity.getCurrentAction() == "lane_change") { lanechange_frames++; } - if (ego_entity->getCurrentAction() != "lane_change" && api_.getCurrentTime() >= 10.0) { + if (ego_entity.getCurrentAction() != "lane_change" && api_.getCurrentTime() >= 10.0) { if (const double step_time = 50e-3, expected_time = 20.0, real_time = static_cast(lanechange_frames) * step_time; expected_time - step_time <= real_time && real_time <= expected_time + step_time) { @@ -65,10 +65,10 @@ class LaneChangeTimeScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34462, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(10); - ego_entity->requestSpeedChange(10, true); - ego_entity->requestLaneChange( + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(10, true); + ego_entity.requestLaneChange( traffic_simulator::lane_change::RelativeTarget( "ego", traffic_simulator::lane_change::Direction::LEFT, 1, 0), traffic_simulator::lane_change::TrajectoryShape::CUBIC, diff --git a/mock/cpp_mock_scenarios/src/measurement/get_distance_in_lane_coordinate_distance.cpp b/mock/cpp_mock_scenarios/src/measurement/get_distance_in_lane_coordinate_distance.cpp index 21131356179..c7c0360fc5a 100644 --- a/mock/cpp_mock_scenarios/src/measurement/get_distance_in_lane_coordinate_distance.cpp +++ b/mock/cpp_mock_scenarios/src/measurement/get_distance_in_lane_coordinate_distance.cpp @@ -44,12 +44,12 @@ class GetDistanceInLaneCoordinateScenario : public cpp_mock_scenarios::CppScenar auto lateralDistance(const std::string & from_entity_name, const std::string & to_entity_name) -> std::optional { - const auto from_entity = api_.getEntity(from_entity_name); - const auto to_entity = api_.getEntity(to_entity_name); - if (from_entity->isInLanelet() && to_entity->isInLanelet()) { + const auto & from_entity = api_.getEntity(from_entity_name); + const auto & to_entity = api_.getEntity(to_entity_name); + if (from_entity.isInLanelet() && to_entity.isInLanelet()) { return traffic_simulator::distance::lateralDistance( - from_entity->getCanonicalizedLaneletPose().value(), - to_entity->getCanonicalizedLaneletPose().value(), traffic_simulator::RoutingConfiguration(), + from_entity.getCanonicalizedLaneletPose().value(), + to_entity.getCanonicalizedLaneletPose().value(), traffic_simulator::RoutingConfiguration(), api_.getHdmapUtils()); } return std::nullopt; @@ -60,9 +60,9 @@ class GetDistanceInLaneCoordinateScenario : public cpp_mock_scenarios::CppScenar const double matching_distance) -> std::optional { const auto from_entity_lanelet_pose = - api_.getEntity(from_entity_name)->getCanonicalizedLaneletPose(matching_distance); + api_.getEntity(from_entity_name).getCanonicalizedLaneletPose(matching_distance); const auto to_entity_lanelet_pose = - api_.getEntity(to_entity_name)->getCanonicalizedLaneletPose(matching_distance); + api_.getEntity(to_entity_name).getCanonicalizedLaneletPose(matching_distance); if (from_entity_lanelet_pose && to_entity_lanelet_pose) { return traffic_simulator::distance::lateralDistance( from_entity_lanelet_pose.value(), to_entity_lanelet_pose.value(), @@ -75,12 +75,12 @@ class GetDistanceInLaneCoordinateScenario : public cpp_mock_scenarios::CppScenar const std::string & from_entity_name, const std::string & to_entity_name) -> std::optional { - const auto from_entity = api_.getEntity(from_entity_name); - const auto to_entity = api_.getEntity(to_entity_name); - if (from_entity->isInLanelet() && to_entity->isInLanelet()) { + const auto & from_entity = api_.getEntity(from_entity_name); + const auto & to_entity = api_.getEntity(to_entity_name); + if (from_entity.isInLanelet() && to_entity.isInLanelet()) { return traffic_simulator::distance::longitudinalDistance( - from_entity->getCanonicalizedLaneletPose().value(), - to_entity->getCanonicalizedLaneletPose().value(), false, false, + from_entity.getCanonicalizedLaneletPose().value(), + to_entity.getCanonicalizedLaneletPose().value(), false, false, traffic_simulator::RoutingConfiguration(), api_.getHdmapUtils()); } return std::nullopt; @@ -142,27 +142,27 @@ class GetDistanceInLaneCoordinateScenario : public cpp_mock_scenarios::CppScenar traffic_simulator::helper::constructCanonicalizedLaneletPose( 34513, 5.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(10); - ego_entity->requestSpeedChange(3, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(3, true); api_.spawn( "front", traffic_simulator::helper::constructCanonicalizedLaneletPose( 34513, 10.0, 1.0, api_.getHdmapUtils()), getVehicleParameters()); - auto front_entity = api_.getEntity("front"); - front_entity->setLinearVelocity(10); - front_entity->requestSpeedChange(3, true); + auto & front_entity = api_.getEntity("front"); + front_entity.setLinearVelocity(10); + front_entity.requestSpeedChange(3, true); api_.spawn( "behind", traffic_simulator::helper::constructCanonicalizedLaneletPose( 34513, 0.0, -1.0, api_.getHdmapUtils()), getVehicleParameters()); - auto behind_entity = api_.getEntity("behind"); - behind_entity->setLinearVelocity(10); - behind_entity->requestSpeedChange(3, true); + auto & behind_entity = api_.getEntity("behind"); + behind_entity.setLinearVelocity(10); + behind_entity.requestSpeedChange(3, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/measurement/get_distance_to_lane_bound.cpp b/mock/cpp_mock_scenarios/src/measurement/get_distance_to_lane_bound.cpp index a2384ba2e87..550ab1fac6b 100644 --- a/mock/cpp_mock_scenarios/src/measurement/get_distance_to_lane_bound.cpp +++ b/mock/cpp_mock_scenarios/src/measurement/get_distance_to_lane_bound.cpp @@ -44,9 +44,9 @@ class GetDistanceToLaneBoundScenario : public cpp_mock_scenarios::CppScenarioNod if (api_.getCurrentTime() >= 10.0) { stop(cpp_mock_scenarios::Result::SUCCESS); } - const auto ego_entity = api_.getEntity("ego"); + auto & ego_entity = api_.getEntity("ego"); const auto distance = traffic_simulator::distance::distanceToLaneBound( - ego_entity->getMapPose(), ego_entity->getBoundingBox(), ego_entity->getRouteLanelets(), + ego_entity.getMapPose(), ego_entity.getBoundingBox(), ego_entity.getRouteLanelets(), api_.getHdmapUtils()); // LCOV_EXCL_START if (distance <= 0.4 && distance >= 0.52) { @@ -61,9 +61,9 @@ class GetDistanceToLaneBoundScenario : public cpp_mock_scenarios::CppScenarioNod traffic_simulator::helper::constructCanonicalizedLaneletPose( 34513, 5.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(10); - ego_entity->requestSpeedChange(3, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(3, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/merge/merge_left.cpp b/mock/cpp_mock_scenarios/src/merge/merge_left.cpp index 9e87b6bf79e..bf1815e1a02 100644 --- a/mock/cpp_mock_scenarios/src/merge/merge_left.cpp +++ b/mock/cpp_mock_scenarios/src/merge/merge_left.cpp @@ -39,7 +39,7 @@ class MergeLeftScenario : public cpp_mock_scenarios::CppScenarioNode bool requested = false; void onUpdate() override { - if (api_.getEntity("ego")->isInLanelet(34510, 0.1)) { + if (api_.getEntity("ego").isInLanelet(34510, 0.1)) { stop(cpp_mock_scenarios::Result::SUCCESS); } // LCOV_EXCL_START @@ -58,17 +58,17 @@ class MergeLeftScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34462, 15.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(5); - ego_entity->requestSpeedChange(5, true); - ego_entity->requestLaneChange(34513); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(5); + ego_entity.requestSpeedChange(5, true); + ego_entity.requestLaneChange(34513); api_.spawn( "npc", traffic_simulator::helper::constructCanonicalizedLaneletPose( 34513, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - api_.getEntity("npc")->setLinearVelocity(10); + api_.getEntity("npc").setLinearVelocity(10); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/metrics/traveled_distance.cpp b/mock/cpp_mock_scenarios/src/metrics/traveled_distance.cpp index 223ea80ac8d..a1ce6f3fec8 100644 --- a/mock/cpp_mock_scenarios/src/metrics/traveled_distance.cpp +++ b/mock/cpp_mock_scenarios/src/metrics/traveled_distance.cpp @@ -44,11 +44,11 @@ class TraveledDistanceScenario : public cpp_mock_scenarios::CppScenarioNode void onUpdate() override { // LCOV_EXCL_START - if (const auto ego_entity = api_.getEntity("ego"); !ego_entity->isInLanelet()) { + if (const auto & ego_entity = api_.getEntity("ego"); !ego_entity.isInLanelet()) { stop(cpp_mock_scenarios::Result::FAILURE); } else if (const auto difference = std::abs( - ego_entity->getCanonicalizedStatus().getLaneletPose().s - - ego_entity->getTraveledDistance()); + ego_entity.getCanonicalizedStatus().getLaneletPose().s - + ego_entity.getTraveledDistance()); difference > std::numeric_limits::epsilon()) { stop(cpp_mock_scenarios::Result::FAILURE); } // LCOV_EXCL_STOP @@ -64,9 +64,9 @@ class TraveledDistanceScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(3); - ego_entity->requestSpeedChange(3, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(3); + ego_entity.requestSpeedChange(3, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/move_backward/move_backward.cpp b/mock/cpp_mock_scenarios/src/move_backward/move_backward.cpp index b3d1fe71e97..6fad55e4fe3 100644 --- a/mock/cpp_mock_scenarios/src/move_backward/move_backward.cpp +++ b/mock/cpp_mock_scenarios/src/move_backward/move_backward.cpp @@ -42,7 +42,7 @@ class MoveBackwardScenario : public cpp_mock_scenarios::CppScenarioNode stop(cpp_mock_scenarios::Result::SUCCESS); } // LCOV_EXCL_START - if (api_.getEntity("ego")->getCurrentTwist().linear.x >= -2.9) { + if (api_.getEntity("ego").getCurrentTwist().linear.x >= -2.9) { stop(cpp_mock_scenarios::Result::FAILURE); } // LCOV_EXCL_STOP @@ -55,9 +55,9 @@ class MoveBackwardScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(-3); - ego_entity->requestSpeedChange(-3, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(-3); + ego_entity.requestSpeedChange(-3, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/pedestrian/walk_straight.cpp b/mock/cpp_mock_scenarios/src/pedestrian/walk_straight.cpp index fb910e766c9..43d97ec231b 100644 --- a/mock/cpp_mock_scenarios/src/pedestrian/walk_straight.cpp +++ b/mock/cpp_mock_scenarios/src/pedestrian/walk_straight.cpp @@ -50,13 +50,13 @@ class WalkStraightScenario : public cpp_mock_scenarios::CppScenarioNode * @sa https://wandbox.org/permlink/dSNRX7K2bQiqSI7P */ if (t == 1.0) { - const auto vel = api_.getEntity("bob")->getCurrentTwist().linear.x; + const auto vel = api_.getEntity("bob").getCurrentTwist().linear.x; if (t != vel) { stop(cpp_mock_scenarios::Result::FAILURE); } } if (t >= 6.65 && 7.25 >= t) { - const auto vel = api_.getEntity("ego")->getCurrentTwist().linear.x; + const auto vel = api_.getEntity("ego").getCurrentTwist().linear.x; if (std::fabs(0.01) <= vel) { stop(cpp_mock_scenarios::Result::FAILURE); } @@ -74,10 +74,10 @@ class WalkStraightScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 120545, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(10); - ego_entity->requestSpeedChange(8, true); - ego_entity->requestAssignRoute(std::vector{ + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(8, true); + ego_entity.requestAssignRoute(std::vector{ traffic_simulator::helper::constructCanonicalizedLaneletPose( 34675, 0.0, 0.0, api_.getHdmapUtils()), traffic_simulator::helper::constructCanonicalizedLaneletPose( @@ -87,10 +87,10 @@ class WalkStraightScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34378, 0.0, 0.0, api_.getHdmapUtils()), getPedestrianParameters()); - auto bob_entity = api_.getEntity("bob"); - bob_entity->setLinearVelocity(0); - bob_entity->requestWalkStraight(); - bob_entity->requestSpeedChange( + auto & bob_entity = api_.getEntity("bob"); + bob_entity.setLinearVelocity(0); + bob_entity.requestWalkStraight(); + 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), diff --git a/mock/cpp_mock_scenarios/src/random_scenario/random001.cpp b/mock/cpp_mock_scenarios/src/random_scenario/random001.cpp index 620f1583bed..d1ae9ac7b2d 100644 --- a/mock/cpp_mock_scenarios/src/random_scenario/random001.cpp +++ b/mock/cpp_mock_scenarios/src/random_scenario/random001.cpp @@ -75,7 +75,7 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode offset, api_.getHdmapUtils()), getVehicleParameters( get_entity_subtype(params_.random_parameters.road_parking_vehicle.entity_type))); - api_.getEntity(entity_name)->requestSpeedChange(0, true); + api_.getEntity(entity_name).requestSpeedChange(0, true); }; std::uniform_real_distribution<> dist( params_.random_parameters.road_parking_vehicle.min_offset, @@ -106,7 +106,7 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode void onUpdate() override { - const auto ego_entity = api_.getEntity("ego"); + const auto & ego_entity = api_.getEntity("ego"); { if (param_listener_->is_old(params_)) { /// When the parameter was updated, clear entity before re-spawning entity. @@ -130,26 +130,26 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode params_.random_parameters.lane_following_vehicle.min_speed, params_.random_parameters.lane_following_vehicle.max_speed); const auto speed = speed_distribution(engine_); - auto entity = api_.getEntity(entity_name); - entity->requestSpeedChange(speed, true); - entity->setLinearVelocity(speed); + auto & entity = api_.getEntity(entity_name); + entity.requestSpeedChange(speed, true); + entity.setLinearVelocity(speed); std::uniform_real_distribution<> lane_change_position_distribution( 0.0, traffic_simulator::pose::laneletLength(34684, api_.getHdmapUtils())); lane_change_position = lane_change_position_distribution(engine_); lane_change_requested = false; } /// Checking the ego entity overs the lane change position. - if (ego_entity->isInLanelet()) { - const auto lanelet_pose = ego_entity->getCanonicalizedStatus().getLaneletPose(); + if (ego_entity.isInLanelet()) { + const auto lanelet_pose = ego_entity.getCanonicalizedStatus().getLaneletPose(); if (lanelet_pose.lanelet_id == 34684 && std::abs(lanelet_pose.s) >= lane_change_position) { api_.getEntity(entity_name) - ->requestLaneChange(traffic_simulator::lane_change::Direction::RIGHT); + .requestLaneChange(traffic_simulator::lane_change::Direction::RIGHT); lane_change_requested = true; } } }; - if (ego_entity->isInLanelet(34684, 0.1)) { + if (ego_entity.isInLanelet(34684, 0.1)) { spawn_and_change_lane("lane_following_0", 0.0); } @@ -159,7 +159,7 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode constexpr lanelet::Id lanelet_id = 34392; if ( !api_.isEntityExist(entity_name) && - !ego_entity->isInPosition( + !ego_entity.isInPosition( traffic_simulator::helper::constructCanonicalizedLaneletPose( 34576, 25.0, 0.0, api_.getHdmapUtils()), 5.0)) { @@ -174,13 +174,13 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode lanelet_id, 0.0, offset_distribution(engine_), api_.getHdmapUtils()), getPedestrianParameters()); const auto speed = speed_distribution(engine_); - auto entity = api_.getEntity(entity_name); - entity->requestSpeedChange(speed, true); - entity->setLinearVelocity(speed); + auto & entity = api_.getEntity(entity_name); + entity.requestSpeedChange(speed, true); + entity.setLinearVelocity(speed); } if ( api_.isEntityExist(entity_name) && - api_.getEntity(entity_name)->getStandStillDuration() >= 0.5) { + api_.getEntity(entity_name).getStandStillDuration() >= 0.5) { api_.despawn(entity_name); } }; @@ -191,11 +191,11 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode const auto trigger_position = traffic_simulator::helper::constructCanonicalizedLaneletPose( 34621, 10, 0.0, api_.getHdmapUtils()); constexpr auto entity_name = "spawn_nearby_ego"; - if (ego_entity->isInPosition(trigger_position, 20.0) && !api_.isEntityExist(entity_name)) { + if (ego_entity.isInPosition(trigger_position, 20.0) && !api_.isEntityExist(entity_name)) { api_.spawn( entity_name, traffic_simulator::pose::transformRelativePoseToGlobal( - ego_entity->getMapPose(), + ego_entity.getMapPose(), geometry_msgs::build() .position(geometry_msgs::build().x(10).y(-5).z(0)) .orientation(geometry_msgs::msg::Quaternion())), @@ -203,13 +203,13 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::entity::VehicleEntity::BuiltinBehavior::doNothing()); } - if (!ego_entity->isInPosition(trigger_position, 20.0) && api_.isEntityExist(entity_name)) { + if (!ego_entity.isInPosition(trigger_position, 20.0) && api_.isEntityExist(entity_name)) { api_.despawn(entity_name); } const auto ego_goal_position = traffic_simulator::helper::constructCanonicalizedLaneletPose( 34606, 0.0, 0.0, api_.getHdmapUtils()); - if (ego_entity->isInPosition(ego_goal_position, 1.0)) { + if (ego_entity.isInPosition(ego_goal_position, 1.0)) { api_.despawn("ego"); stop(cpp_mock_scenarios::Result::SUCCESS); } @@ -229,11 +229,11 @@ class RandomScenario : public cpp_mock_scenarios::CppScenarioNode {traffic_simulator::helper::constructCanonicalizedLaneletPose( 34606, 0.0, 0.0, api_.getHdmapUtils())}, getVehicleParameters()); - if (const auto ego = api_.getEntity("ego")) { + if (api_.isEntityExist("ego")) { api_.spawn( "parking_outside", traffic_simulator::pose::transformRelativePoseToGlobal( - ego->getMapPose(), + api_.getEntity("ego").getMapPose(), geometry_msgs::build() .position(geometry_msgs::build().x(10).y(15).z(0)) .orientation(geometry_msgs::msg::Quaternion())), diff --git a/mock/cpp_mock_scenarios/src/spawn/spawn_in_map_frame.cpp b/mock/cpp_mock_scenarios/src/spawn/spawn_in_map_frame.cpp index c34e8236e62..cbf68a114e0 100644 --- a/mock/cpp_mock_scenarios/src/spawn/spawn_in_map_frame.cpp +++ b/mock/cpp_mock_scenarios/src/spawn/spawn_in_map_frame.cpp @@ -41,7 +41,7 @@ class SpawnInMapFrameScenario : public cpp_mock_scenarios::CppScenarioNode const auto map_pose = traffic_simulator::pose::toMapPose( traffic_simulator::helper::constructCanonicalizedLaneletPose( 120545, 0.0, 0.0, api_.getHdmapUtils())); - if (api_.getEntity("ego")->isInPosition(map_pose, 0.1)) { + if (api_.getEntity("ego").isInPosition(map_pose, 0.1)) { stop(cpp_mock_scenarios::Result::SUCCESS); } else { stop(cpp_mock_scenarios::Result::FAILURE); diff --git a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change.cpp b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change.cpp index ce683734067..455a7101bb0 100644 --- a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change.cpp +++ b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change.cpp @@ -39,8 +39,8 @@ class RequestSpeedChangeScenario : public cpp_mock_scenarios::CppScenarioNode private: void onUpdate() override { - const auto ego_linear_velocity = api_.getEntity("ego")->getCurrentTwist().linear.x; - if (api_.getEntity("front")->getCurrentTwist().linear.x < 10.0) { + const auto ego_linear_velocity = api_.getEntity("ego").getCurrentTwist().linear.x; + if (api_.getEntity("front").getCurrentTwist().linear.x < 10.0) { stop(cpp_mock_scenarios::Result::FAILURE); } if (api_.getCurrentTime() <= 0.9 && ego_linear_velocity > 10.0) { @@ -58,9 +58,9 @@ class RequestSpeedChangeScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0); - ego_entity->requestSpeedChange( + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(0); + ego_entity.requestSpeedChange( 10.0, traffic_simulator::speed_change::Transition::LINEAR, traffic_simulator::speed_change::Constraint( traffic_simulator::speed_change::Constraint::Type::LONGITUDINAL_ACCELERATION, 10.0), @@ -71,9 +71,9 @@ class RequestSpeedChangeScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto front_entity = api_.getEntity("front"); - front_entity->setLinearVelocity(0); - front_entity->requestSpeedChange( + auto & front_entity = api_.getEntity("front"); + front_entity.setLinearVelocity(0); + front_entity.requestSpeedChange( 10.0, traffic_simulator::speed_change::Transition::STEP, traffic_simulator::speed_change::Constraint( traffic_simulator::speed_change::Constraint::Type::LONGITUDINAL_ACCELERATION, 10.0), diff --git a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_continuous_false.cpp b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_continuous_false.cpp index 917241b6ed8..29c1a41c876 100644 --- a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_continuous_false.cpp +++ b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_continuous_false.cpp @@ -43,7 +43,7 @@ class RequestSpeedChangeContinuousFalseScenario : public cpp_mock_scenarios::Cpp /** * @brief checking linear speed */ - const auto ego_linear_velocity = api_.getEntity("ego")->getCurrentTwist().linear.x; + const auto ego_linear_velocity = api_.getEntity("ego").getCurrentTwist().linear.x; if (api_.getCurrentTime() <= 0.95) { if (!equals(api_.getCurrentTime() * 10.0, ego_linear_velocity, 0.01)) { stop(cpp_mock_scenarios::Result::FAILURE); @@ -65,9 +65,9 @@ class RequestSpeedChangeContinuousFalseScenario : public cpp_mock_scenarios::Cpp traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0); - ego_entity->requestSpeedChange( + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(0); + ego_entity.requestSpeedChange( 10.0, traffic_simulator::speed_change::Transition::LINEAR, traffic_simulator::speed_change::Constraint( traffic_simulator::speed_change::Constraint::Type::LONGITUDINAL_ACCELERATION, 10.0), diff --git a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_relative.cpp b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_relative.cpp index 04f0661ee27..e891bc37182 100644 --- a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_relative.cpp +++ b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_relative.cpp @@ -45,11 +45,11 @@ class RequestSpeedChangeRelativeScenario : public cpp_mock_scenarios::CppScenari api_.updateFrame(); const double current_time = api_.getCurrentTime(); - auto front_entity = api_.getEntity("front"); + auto & front_entity = api_.getEntity("front"); if (current_time >= 0.0 and not request_sent) { request_sent = true; - front_entity->requestSpeedChange( + front_entity.requestSpeedChange( traffic_simulator::speed_change::RelativeTargetSpeed( "ego", traffic_simulator::speed_change::RelativeTargetSpeed::Type::DELTA, 2.0), traffic_simulator::speed_change::Transition::LINEAR, @@ -58,7 +58,7 @@ class RequestSpeedChangeRelativeScenario : public cpp_mock_scenarios::CppScenari true); } - const double current_speed = front_entity->getCurrentTwist().linear.x; + const double current_speed = front_entity.getCurrentTwist().linear.x; static constexpr double speed_tolerance = 0.05; if (current_time >= 0.0 and current_time < 2.0) { if (not equals(current_time + 3.0, current_speed, speed_tolerance)) { @@ -80,16 +80,16 @@ class RequestSpeedChangeRelativeScenario : public cpp_mock_scenarios::CppScenari traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(3); - ego_entity->requestSpeedChange(3.0, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(3); + ego_entity.requestSpeedChange(3.0, true); api_.spawn( "front", traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - api_.getEntity("front")->setLinearVelocity(3); + api_.getEntity("front").setLinearVelocity(3); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_step.cpp b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_step.cpp index 1b6f5e867b0..4c6169a59fb 100644 --- a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_step.cpp +++ b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_step.cpp @@ -41,8 +41,8 @@ class RequestSpeedChangeStepScenario : public cpp_mock_scenarios::CppScenarioNod { if ( api_.getCurrentTime() <= 0.999 && - !equals(api_.getEntity("ego")->getCurrentTwist().linear.x, 10.0, 0.01) && - !equals(api_.getEntity("front")->getCurrentTwist().linear.x, 10.0, 0.01)) { + !equals(api_.getEntity("ego").getCurrentTwist().linear.x, 10.0, 0.01) && + !equals(api_.getEntity("front").getCurrentTwist().linear.x, 10.0, 0.01)) { stop(cpp_mock_scenarios::Result::FAILURE); } if (api_.getCurrentTime() >= 1.0) { @@ -57,9 +57,9 @@ class RequestSpeedChangeStepScenario : public cpp_mock_scenarios::CppScenarioNod traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0); - ego_entity->requestSpeedChange( + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(0); + ego_entity.requestSpeedChange( 10.0, traffic_simulator::speed_change::Transition::STEP, traffic_simulator::speed_change::Constraint( traffic_simulator::speed_change::Constraint::Type::LONGITUDINAL_ACCELERATION, 10.0), @@ -70,9 +70,9 @@ class RequestSpeedChangeStepScenario : public cpp_mock_scenarios::CppScenarioNod traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto front_entity = api_.getEntity("front"); - front_entity->setLinearVelocity(0); - front_entity->requestSpeedChange( + auto & front_entity = api_.getEntity("front"); + front_entity.setLinearVelocity(0); + front_entity.requestSpeedChange( 10.0, traffic_simulator::speed_change::Transition::STEP, traffic_simulator::speed_change::Constraint( traffic_simulator::speed_change::Constraint::Type::TIME, 0.0), diff --git a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_limit.cpp b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_limit.cpp index 03a1b8f8df1..f2971f86d72 100644 --- a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_limit.cpp +++ b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_limit.cpp @@ -39,7 +39,7 @@ class RequestSpeedChangeWithLimitScenario : public cpp_mock_scenarios::CppScenar private: void onUpdate() override { - const auto ego_linear_velocity = api_.getEntity("ego")->getCurrentTwist().linear.x; + const auto ego_linear_velocity = api_.getEntity("ego").getCurrentTwist().linear.x; if (api_.getCurrentTime() <= 0.9 && ego_linear_velocity > 10.0) { stop(cpp_mock_scenarios::Result::FAILURE); } @@ -55,10 +55,10 @@ class RequestSpeedChangeWithLimitScenario : public cpp_mock_scenarios::CppScenar traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0); - ego_entity->setVelocityLimit(5.0); - ego_entity->requestSpeedChange( + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(0); + ego_entity.setVelocityLimit(5.0); + ego_entity.requestSpeedChange( 10.0, traffic_simulator::speed_change::Transition::LINEAR, traffic_simulator::speed_change::Constraint( traffic_simulator::speed_change::Constraint::Type::LONGITUDINAL_ACCELERATION, 10.0), diff --git a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_time_constraint.cpp b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_time_constraint.cpp index 6fc3217c9cd..7ed1339e527 100644 --- a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_time_constraint.cpp +++ b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_time_constraint.cpp @@ -39,7 +39,7 @@ class RequestSpeedChangeWithTimeConstraintScenario : public cpp_mock_scenarios:: private: void onUpdate() override { - const auto ego_linear_velocity = api_.getEntity("ego")->getCurrentTwist().linear.x; + const auto ego_linear_velocity = api_.getEntity("ego").getCurrentTwist().linear.x; if (api_.getCurrentTime() <= 3.9 && ego_linear_velocity > 10.0) { stop(cpp_mock_scenarios::Result::FAILURE); } @@ -59,9 +59,9 @@ class RequestSpeedChangeWithTimeConstraintScenario : public cpp_mock_scenarios:: traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0); - ego_entity->requestSpeedChange( + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(0); + ego_entity.requestSpeedChange( 10.0, traffic_simulator::speed_change::Transition::AUTO, traffic_simulator::speed_change::Constraint( traffic_simulator::speed_change::Constraint::Type::TIME, 4.0), @@ -72,9 +72,9 @@ class RequestSpeedChangeWithTimeConstraintScenario : public cpp_mock_scenarios:: traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto front_entity = api_.getEntity("front"); - front_entity->setLinearVelocity(10); - front_entity->requestSpeedChange( + auto & front_entity = api_.getEntity("front"); + front_entity.setLinearVelocity(10); + front_entity.requestSpeedChange( 10.0, traffic_simulator::speed_change::Transition::LINEAR, traffic_simulator::speed_change::Constraint( traffic_simulator::speed_change::Constraint::Type::LONGITUDINAL_ACCELERATION, 4.0), diff --git a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_time_constraint_linear.cpp b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_time_constraint_linear.cpp index 8a1623eee5e..43b1d60c731 100644 --- a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_time_constraint_linear.cpp +++ b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_time_constraint_linear.cpp @@ -42,7 +42,7 @@ class RequestSpeedChangeWithTimeConstraintLinearScenario { if (api_.getCurrentTime() <= 3.999) { if (!equals( - api_.getCurrentTime() * 2.5, api_.getEntity("ego")->getCurrentTwist().linear.x, 0.01)) { + api_.getCurrentTime() * 2.5, api_.getEntity("ego").getCurrentTwist().linear.x, 0.01)) { stop(cpp_mock_scenarios::Result::FAILURE); } } else if (api_.getCurrentTime() >= 4.0) { @@ -57,10 +57,10 @@ class RequestSpeedChangeWithTimeConstraintLinearScenario traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); + auto & ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0); - ego_entity->requestSpeedChange( + ego_entity.setLinearVelocity(0); + ego_entity.requestSpeedChange( 10.0, traffic_simulator::speed_change::Transition::LINEAR, traffic_simulator::speed_change::Constraint( traffic_simulator::speed_change::Constraint::Type::TIME, 4.0), diff --git a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_time_constraint_relative.cpp b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_time_constraint_relative.cpp index 5192be24fa8..d861b33d08c 100644 --- a/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_time_constraint_relative.cpp +++ b/mock/cpp_mock_scenarios/src/speed_planning/request_speed_change_with_time_constraint_relative.cpp @@ -40,7 +40,7 @@ class RequestSpeedChangeWithTimeConstraintRelativeScenario private: void onUpdate() override { - const auto ego_linear_velocity = api_.getEntity("ego")->getCurrentTwist().linear.x; + const auto ego_linear_velocity = api_.getEntity("ego").getCurrentTwist().linear.x; if (api_.getCurrentTime() <= 3.9 && ego_linear_velocity >= 3.0) { stop(cpp_mock_scenarios::Result::FAILURE); } @@ -60,9 +60,9 @@ class RequestSpeedChangeWithTimeConstraintRelativeScenario traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(1.0); - ego_entity->requestSpeedChange( + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(1.0); + ego_entity.requestSpeedChange( traffic_simulator::speed_change::RelativeTargetSpeed( "ego", traffic_simulator::speed_change::RelativeTargetSpeed::Type::DELTA, 2.0), traffic_simulator::speed_change::Transition::AUTO, @@ -75,9 +75,9 @@ class RequestSpeedChangeWithTimeConstraintRelativeScenario traffic_simulator::helper::constructCanonicalizedLaneletPose( 34741, 10.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto front_entity = api_.getEntity("front"); - front_entity->setLinearVelocity(10); - front_entity->requestSpeedChange( + auto & front_entity = api_.getEntity("front"); + front_entity.setLinearVelocity(10); + front_entity.requestSpeedChange( 10.0, traffic_simulator::speed_change::Transition::LINEAR, traffic_simulator::speed_change::Constraint( traffic_simulator::speed_change::Constraint::Type::LONGITUDINAL_ACCELERATION, 4.0), diff --git a/mock/cpp_mock_scenarios/src/synchronized_action/synchronized_action.cpp b/mock/cpp_mock_scenarios/src/synchronized_action/synchronized_action.cpp index 9db459e8b53..0d7c204dcf5 100644 --- a/mock/cpp_mock_scenarios/src/synchronized_action/synchronized_action.cpp +++ b/mock/cpp_mock_scenarios/src/synchronized_action/synchronized_action.cpp @@ -44,14 +44,14 @@ class SynchronizedAction : public cpp_mock_scenarios::CppScenarioNode void onUpdate() override { - auto npc = api_.getEntity("npc"); - auto ego = api_.getEntity("ego"); + auto & npc = api_.getEntity("npc"); + auto & ego = api_.getEntity("ego"); // SUCCESS if ( - npc->requestSynchronize("ego", ego_target, npc_target, 0, 0.5) && - ego->isInPosition(ego_target, 1.0) && npc->isInPosition(npc_target, 1.0) && - npc->getCurrentTwist().linear.x < 0.5) { + npc.requestSynchronize("ego", ego_target, npc_target, 0, 0.5) && + ego.isInPosition(ego_target, 1.0) && npc.isInPosition(npc_target, 1.0) && + npc.getCurrentTwist().linear.x < 0.5) { stop(cpp_mock_scenarios::Result::SUCCESS); } @@ -71,14 +71,14 @@ class SynchronizedAction : public cpp_mock_scenarios::CppScenarioNode 34976, 20, 0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego = api_.getEntity("ego"); - ego->setLinearVelocity(3); - ego->requestSpeedChange(3, true); + auto & ego = api_.getEntity("ego"); + ego.setLinearVelocity(3); + ego.requestSpeedChange(3, true); std::vector goal_poses; goal_poses.emplace_back(traffic_simulator::helper::constructCanonicalizedLaneletPose( 34579, 20, 0, api_.getHdmapUtils())); - ego->requestAssignRoute(goal_poses); + ego.requestAssignRoute(goal_poses); api_.spawn( "npc", @@ -86,13 +86,13 @@ class SynchronizedAction : public cpp_mock_scenarios::CppScenarioNode 34576, 0, 0, api_.getHdmapUtils()), getVehicleParameters()); - auto npc = api_.getEntity("npc"); + auto & npc = api_.getEntity("npc"); std::vector npc_goal_poses; npc_goal_poses.emplace_back(traffic_simulator::helper::constructCanonicalizedLaneletPose( 34564, 20, 0, api_.getHdmapUtils())); - npc->requestAssignRoute(npc_goal_poses); - npc->setLinearVelocity(6); + npc.requestAssignRoute(npc_goal_poses); + npc.setLinearVelocity(6); } auto getSampleLaneletPose(const traffic_simulator::LaneletPose & lanelet_pose) diff --git a/mock/cpp_mock_scenarios/src/synchronized_action/synchronized_action_with_speed.cpp b/mock/cpp_mock_scenarios/src/synchronized_action/synchronized_action_with_speed.cpp index a03ebadbbb2..385109742b7 100644 --- a/mock/cpp_mock_scenarios/src/synchronized_action/synchronized_action_with_speed.cpp +++ b/mock/cpp_mock_scenarios/src/synchronized_action/synchronized_action_with_speed.cpp @@ -44,14 +44,14 @@ class SynchronizedActionWithSpeed : public cpp_mock_scenarios::CppScenarioNode void onUpdate() override { - auto npc = api_.getEntity("npc"); - auto ego = api_.getEntity("ego"); + auto & npc = api_.getEntity("npc"); + auto & ego = api_.getEntity("ego"); // SUCCESS if ( - npc->requestSynchronize("ego", ego_target, npc_target, 2, 0.5) && - ego->isInPosition(ego_target, 1.0) && npc->isInPosition(npc_target, 1.0) && - npc->getCurrentTwist().linear.x < 2.5) { + npc.requestSynchronize("ego", ego_target, npc_target, 2, 0.5) && + ego.isInPosition(ego_target, 1.0) && npc.isInPosition(npc_target, 1.0) && + npc.getCurrentTwist().linear.x < 2.5) { stop(cpp_mock_scenarios::Result::SUCCESS); } @@ -71,14 +71,14 @@ class SynchronizedActionWithSpeed : public cpp_mock_scenarios::CppScenarioNode 34976, 20, 0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego = api_.getEntity("ego"); - ego->setLinearVelocity(3); - ego->requestSpeedChange(3, true); + auto & ego = api_.getEntity("ego"); + ego.setLinearVelocity(3); + ego.requestSpeedChange(3, true); std::vector goal_poses; goal_poses.emplace_back(traffic_simulator::helper::constructCanonicalizedLaneletPose( 34579, 20, 0, api_.getHdmapUtils())); - ego->requestAssignRoute(goal_poses); + ego.requestAssignRoute(goal_poses); api_.spawn( "npc", @@ -86,13 +86,13 @@ class SynchronizedActionWithSpeed : public cpp_mock_scenarios::CppScenarioNode 34576, 0, 0, api_.getHdmapUtils()), getVehicleParameters()); - auto npc = api_.getEntity("npc"); + auto & npc = api_.getEntity("npc"); std::vector npc_goal_poses; npc_goal_poses.emplace_back(traffic_simulator::helper::constructCanonicalizedLaneletPose( 34564, 20, 0, api_.getHdmapUtils())); - npc->requestAssignRoute(npc_goal_poses); - npc->setLinearVelocity(6); + npc.requestAssignRoute(npc_goal_poses); + npc.setLinearVelocity(6); } auto getSampleLaneletPose(const traffic_simulator::LaneletPose & lanelet_pose) diff --git a/mock/cpp_mock_scenarios/src/traffic_simulation_demo.cpp b/mock/cpp_mock_scenarios/src/traffic_simulation_demo.cpp index 6ca6d01363d..2e59e506ec6 100644 --- a/mock/cpp_mock_scenarios/src/traffic_simulation_demo.cpp +++ b/mock/cpp_mock_scenarios/src/traffic_simulation_demo.cpp @@ -47,7 +47,7 @@ class TrafficSimulationDemoScenario : public cpp_mock_scenarios::CppScenarioNode } if (api_.getCurrentTime() >= 4 && api_.isEntityExist("obstacle")) { api_.getEntity("obstacle") - ->setStatus( + .setStatus( traffic_simulator::helper::constructCanonicalizedLaneletPose( 120545, 0.0, 0.0, api_.getHdmapUtils()), traffic_simulator::helper::constructActionStatus(10)); @@ -55,38 +55,38 @@ class TrafficSimulationDemoScenario : public cpp_mock_scenarios::CppScenarioNode if (api_.getCurrentTime() >= 6 && api_.isEntityExist("obstacle")) { api_.despawn("obstacle"); } - const auto ego_entity = api_.getEntity("ego"); - const auto npc2_entity = api_.getEntity("npc2"); - if (ego_entity->isInPosition( + auto & ego_entity = api_.getEntity("ego"); + auto & npc2_entity = api_.getEntity("npc2"); + if (ego_entity.isInPosition( traffic_simulator::helper::constructCanonicalizedLaneletPose( 34615, 10.0, 0.0, api_.getHdmapUtils()), 5)) { - ego_entity->requestAcquirePosition( + ego_entity.requestAcquirePosition( traffic_simulator::helper::constructCanonicalizedLaneletPose( 35026, 0.0, 0.0, api_.getHdmapUtils())); if (api_.isEntityExist("npc2")) { - npc2_entity->requestSpeedChange(13, true); + npc2_entity.requestSpeedChange(13, true); } } - if (ego_entity->isInPosition( + if (ego_entity.isInPosition( traffic_simulator::helper::constructCanonicalizedLaneletPose( 34579, 0.0, 0.0, api_.getHdmapUtils()), 5)) { - ego_entity->requestAcquirePosition( + ego_entity.requestAcquirePosition( traffic_simulator::helper::constructCanonicalizedLaneletPose( 34675, 0.0, 0.0, api_.getHdmapUtils())); if (api_.isEntityExist("npc2")) { - npc2_entity->requestSpeedChange(3, true); + npc2_entity.requestSpeedChange(3, true); } } - if (npc2_entity->isInPosition( + if (npc2_entity.isInPosition( traffic_simulator::helper::constructCanonicalizedLaneletPose( 34513, 0.0, 0.0, api_.getHdmapUtils()), 5)) { - npc2_entity->requestAcquirePosition( + npc2_entity.requestAcquirePosition( traffic_simulator::helper::constructCanonicalizedLaneletPose( 34630, 0.0, 0.0, api_.getHdmapUtils())); - npc2_entity->requestSpeedChange(13, true); + npc2_entity.requestSpeedChange(13, true); } if (api_.getCurrentTime() > 10.0 && api_.isEntityExist("bob")) { api_.despawn("bob"); @@ -102,10 +102,10 @@ class TrafficSimulationDemoScenario : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 120545, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(10); - ego_entity->requestSpeedChange(8, true); - ego_entity->requestAssignRoute(std::vector{ + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(10); + ego_entity.requestSpeedChange(8, true); + ego_entity.requestAssignRoute(std::vector{ traffic_simulator::helper::constructCanonicalizedLaneletPose( 34675, 0.0, 0.0, api_.getHdmapUtils()), traffic_simulator::helper::constructCanonicalizedLaneletPose( @@ -114,57 +114,56 @@ class TrafficSimulationDemoScenario : public cpp_mock_scenarios::CppScenarioNode api_.spawn( "tom", traffic_simulator::helper::constructPose(10, 3, 0, 0, 0, -1.57), getPedestrianParameters()); - api_.getEntity("tom")->setStatus( - ego_entity->getMapPose(), traffic_simulator::helper::constructPose(10, 3, 0, 0, 0, -1.57), + api_.getEntity("tom").setStatus( + ego_entity.getMapPose(), traffic_simulator::helper::constructPose(10, 3, 0, 0, 0, -1.57), traffic_simulator::helper::constructActionStatus()); - auto tom_entity = api_.getEntity("tom"); - tom_entity->requestWalkStraight(); - tom_entity->requestSpeedChange(3, true); + auto & tom_entity = api_.getEntity("tom"); + tom_entity.requestWalkStraight(); + tom_entity.requestSpeedChange(3, true); api_.spawn( "bob", traffic_simulator::helper::constructCanonicalizedLaneletPose( 34378, 0.0, 0.0, api_.getHdmapUtils()), getPedestrianParameters()); - auto bob_entity = api_.getEntity("bob"); - bob_entity->setLinearVelocity(1.0); - bob_entity->requestSpeedChange(1, true); + auto & bob_entity = api_.getEntity("bob"); + bob_entity.setLinearVelocity(1.0); + bob_entity.requestSpeedChange(1, true); api_.spawn( "npc1", traffic_simulator::helper::constructCanonicalizedLaneletPose( 34579, 20.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto npc1_entity = api_.getEntity("npc1"); - npc1_entity->setLinearVelocity(5.0); - npc1_entity->requestSpeedChange(5, true); - npc1_entity->requestAcquirePosition( - traffic_simulator::helper::constructCanonicalizedLaneletPose( - 34675, 0.0, 0.0, api_.getHdmapUtils())); + auto & npc1_entity = api_.getEntity("npc1"); + npc1_entity.setLinearVelocity(5.0); + npc1_entity.requestSpeedChange(5, true); + npc1_entity.requestAcquirePosition(traffic_simulator::helper::constructCanonicalizedLaneletPose( + 34675, 0.0, 0.0, api_.getHdmapUtils())); api_.spawn( "npc2", traffic_simulator::helper::constructCanonicalizedLaneletPose( 34606, 20.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto npc2_entity = api_.getEntity("npc1"); - npc2_entity->setLinearVelocity(5); - npc2_entity->requestSpeedChange(0, true); + auto & npc2_entity = api_.getEntity("npc1"); + npc2_entity.setLinearVelocity(5); + npc2_entity.requestSpeedChange(0, true); api_.spawn( "npc3", traffic_simulator::helper::constructCanonicalizedLaneletPose( 34468, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto npc3_entity = api_.getEntity("npc3"); - npc3_entity->setLinearVelocity(10); + auto & npc3_entity = api_.getEntity("npc3"); + npc3_entity.setLinearVelocity(10); api_.spawn( "obstacle", traffic_simulator::helper::constructPose(10, 5, 0, 0, 0, -1.57), getMiscObjectParameters()); api_.getEntity("obstacle") - ->setStatus( - ego_entity->getMapPose(), traffic_simulator::helper::constructPose(10, 5, 0, 0, 0, -1.57), + .setStatus( + ego_entity.getMapPose(), traffic_simulator::helper::constructPose(10, 5, 0, 0, 0, -1.57), traffic_simulator::helper::constructActionStatus()); api_.getConventionalTrafficLights()->setTrafficLightsColor( diff --git a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_delay.cpp b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_delay.cpp index a6e7f503031..0bd12e7b30b 100644 --- a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_delay.cpp +++ b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_delay.cpp @@ -75,12 +75,12 @@ class DefineTrafficSourceDelay : public cpp_mock_scenarios::CppScenarioNode stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } for (const auto & name : names) { - const auto entity = api_.getEntity(name); - if (!entity->isInLanelet()) { + const auto & entity = api_.getEntity(name); + if (!entity.isInLanelet()) { stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } else { const bool valid_vehicle_lanelet = - entity->isInLanelet(34705, 50.0) || entity->isInLanelet(34696, 50.0); + entity.isInLanelet(34705, 50.0) || entity.isInLanelet(34696, 50.0); if (!valid_vehicle_lanelet || !isVehicle(name)) { stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } @@ -97,9 +97,9 @@ class DefineTrafficSourceDelay : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34570, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0.0); - ego_entity->requestSpeedChange(0.0, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(0.0); + ego_entity.requestSpeedChange(0.0, true); } bool traffic_source_added_ = false; diff --git a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_high_rate.cpp b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_high_rate.cpp index 81b12eee1bd..3ede3188860 100644 --- a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_high_rate.cpp +++ b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_high_rate.cpp @@ -52,12 +52,12 @@ class DefineTrafficSourceHighRate : public cpp_mock_scenarios::CppScenarioNode stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } for (const auto & name : names) { - const auto entity = api_.getEntity(name); - if (!entity->isInLanelet()) { + const auto & entity = api_.getEntity(name); + if (!entity.isInLanelet()) { stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } else { const bool valid_vehicle_lanelet = - entity->isInLanelet(34705, 50.0) || entity->isInLanelet(34696, 50.0); + entity.isInLanelet(34705, 50.0) || entity.isInLanelet(34696, 50.0); if (!valid_vehicle_lanelet || !isVehicle(name)) { stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } @@ -87,9 +87,9 @@ class DefineTrafficSourceHighRate : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34570, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0.0); - ego_entity->requestSpeedChange(0.0, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(0.0); + ego_entity.requestSpeedChange(0.0, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_large.cpp b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_large.cpp index 5c2233874e7..51c0b409101 100644 --- a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_large.cpp +++ b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_large.cpp @@ -52,9 +52,9 @@ class DefineTrafficSourceLarge : public cpp_mock_scenarios::CppScenarioNode stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } for (const auto & name : names) { - const auto entity = api_.getEntity(name); + const auto & entity = api_.getEntity(name); - if (!entity->isInLanelet() || !isVehicle(name)) { + if (!entity.isInLanelet() || !isVehicle(name)) { stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } } @@ -82,9 +82,9 @@ class DefineTrafficSourceLarge : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34570, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0.0); - ego_entity->requestSpeedChange(0.0, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(0.0); + ego_entity.requestSpeedChange(0.0, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_mixed.cpp b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_mixed.cpp index d6e1d7a5558..48d43386e3b 100644 --- a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_mixed.cpp +++ b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_mixed.cpp @@ -53,12 +53,12 @@ class DefineTrafficSourceMixed : public cpp_mock_scenarios::CppScenarioNode } unsigned int vehicle_count = 0u, pedestrian_count = 0u; for (const auto & name : names) { - const auto entity = api_.getEntity(name); - if (!entity->isInLanelet()) { + const auto & entity = api_.getEntity(name); + if (!entity.isInLanelet()) { stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } else { const bool valid_vehicle_lanelet = - entity->isInLanelet(34705, 50.0) || entity->isInLanelet(34696, 50.0); + entity.isInLanelet(34705, 50.0) || entity.isInLanelet(34696, 50.0); if (isVehicle(name)) { ++vehicle_count; } else if (isPedestrian(name)) { @@ -98,9 +98,9 @@ class DefineTrafficSourceMixed : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34570, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0.0); - ego_entity->requestSpeedChange(0.0, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(0.0); + ego_entity.requestSpeedChange(0.0, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_multiple.cpp b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_multiple.cpp index 783f524c4c7..7049fa27f40 100644 --- a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_multiple.cpp +++ b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_multiple.cpp @@ -53,13 +53,13 @@ class DefineTrafficSourceMultiple : public cpp_mock_scenarios::CppScenarioNode } unsigned int vehicle_count = 0u, pedestrian_count = 0u; for (const auto & name : names) { - const auto entity = api_.getEntity(name); - if (!entity->isInLanelet()) { + const auto & entity = api_.getEntity(name); + if (!entity.isInLanelet()) { stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } else { const bool valid_vehicle_lanelet = - entity->isInLanelet(34705, 50.0) || entity->isInLanelet(34696, 50.0); - const bool valid_pedestrian_lanelet = entity->isInLanelet(34385, 10.0); + entity.isInLanelet(34705, 50.0) || entity.isInLanelet(34696, 50.0); + const bool valid_pedestrian_lanelet = entity.isInLanelet(34385, 10.0); if (isVehicle(name)) { ++vehicle_count; } else if (isPedestrian(name)) { @@ -114,9 +114,9 @@ class DefineTrafficSourceMultiple : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34570, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0.0); - ego_entity->requestSpeedChange(0.0, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(0.0); + ego_entity.requestSpeedChange(0.0, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_outside_lane.cpp b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_outside_lane.cpp index 306b9e4668e..da1845d73a4 100644 --- a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_outside_lane.cpp +++ b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_outside_lane.cpp @@ -52,9 +52,9 @@ class DefineTrafficSourceOutsideLane : public cpp_mock_scenarios::CppScenarioNod stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } for (const auto & name : names) { - const auto entity = api_.getEntity(name); + const auto & entity = api_.getEntity(name); - if (entity->isInLanelet() || !isPedestrian(name)) { + if (entity.isInLanelet() || !isPedestrian(name)) { stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } stop(cpp_mock_scenarios::Result::SUCCESS); @@ -83,9 +83,9 @@ class DefineTrafficSourceOutsideLane : public cpp_mock_scenarios::CppScenarioNod traffic_simulator::helper::constructCanonicalizedLaneletPose( 34570, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0.0); - ego_entity->requestSpeedChange(0.0, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(0.0); + ego_entity.requestSpeedChange(0.0, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_pedestrian.cpp b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_pedestrian.cpp index 0469791afe9..85e712c222a 100644 --- a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_pedestrian.cpp +++ b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_pedestrian.cpp @@ -52,11 +52,11 @@ class DefineTrafficSourcePedestrian : public cpp_mock_scenarios::CppScenarioNode stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } for (const auto & name : names) { - const auto entity = api_.getEntity(name); - if (!entity->isInLanelet()) { + const auto & entity = api_.getEntity(name); + if (!entity.isInLanelet()) { stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } else { - const bool valid_pedestrian_lanelet = entity->isInLanelet(34385, 10.0); + const bool valid_pedestrian_lanelet = entity.isInLanelet(34385, 10.0); if (!valid_pedestrian_lanelet || !isPedestrian(name)) { stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } @@ -87,9 +87,9 @@ class DefineTrafficSourcePedestrian : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34570, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0.0); - ego_entity->requestSpeedChange(0.0, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(0.0); + ego_entity.requestSpeedChange(0.0, true); } }; } // namespace cpp_mock_scenarios diff --git a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_vehicle.cpp b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_vehicle.cpp index d470a0c3197..2ff2ca8f575 100644 --- a/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_vehicle.cpp +++ b/mock/cpp_mock_scenarios/src/traffic_source/define_traffic_source_vehicle.cpp @@ -52,12 +52,12 @@ class DefineTrafficSourceVehicle : public cpp_mock_scenarios::CppScenarioNode stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } for (const auto & name : names) { - const auto entity = api_.getEntity(name); - if (!entity->isInLanelet()) { + const auto & entity = api_.getEntity(name); + if (!entity.isInLanelet()) { stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } else { const bool valid_vehicle_lanelet = - entity->isInLanelet(34705, 50.0) || entity->isInLanelet(34696, 50.0); + entity.isInLanelet(34705, 50.0) || entity.isInLanelet(34696, 50.0); if (!valid_vehicle_lanelet || !isVehicle(name)) { stop(cpp_mock_scenarios::Result::FAILURE); // LCOV_EXCL_LINE } @@ -87,9 +87,9 @@ class DefineTrafficSourceVehicle : public cpp_mock_scenarios::CppScenarioNode traffic_simulator::helper::constructCanonicalizedLaneletPose( 34570, 0.0, 0.0, api_.getHdmapUtils()), getVehicleParameters()); - auto ego_entity = api_.getEntity("ego"); - ego_entity->setLinearVelocity(0.0); - ego_entity->requestSpeedChange(0.0, true); + auto & ego_entity = api_.getEntity("ego"); + ego_entity.setLinearVelocity(0.0); + ego_entity.requestSpeedChange(0.0, true); } }; } // namespace cpp_mock_scenarios