From a4ef2cdada30a6a2eca3bf08bb88d2a725fb000e Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 2 Feb 2024 15:02:51 +0900 Subject: [PATCH] refactor(ego_entity_simulation): rename flag name for considering slope in ego entity simulation Signed-off-by: Kotaro Yoshimoto --- .../vehicle_simulation/ego_entity_simulation.hpp | 2 +- .../src/vehicle_simulation/ego_entity_simulation.cpp | 5 +++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp index 4cc63686d8c..2c53e1369a9 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp @@ -60,7 +60,7 @@ class EgoEntitySimulation traffic_simulator_msgs::msg::EntityStatus status_; - bool consider_road_slope_ = false; + const bool consider_acceleration_by_road_slope_; public: const std::shared_ptr hdmap_utils_ptr_; diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index 628416da5a9..fc92eade932 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -39,7 +39,8 @@ EgoEntitySimulation::EgoEntitySimulation( vehicle_model_type_(getVehicleModelType()), vehicle_model_ptr_(makeSimulationModel(vehicle_model_type_, step_time, parameters)), hdmap_utils_ptr_(hdmap_utils), - consider_road_slope_(getParameter("consider_road_slope", false)) + consider_acceleration_by_road_slope_( + getParameter("consider_acceleration_by_road_slope", false)) { } @@ -264,7 +265,7 @@ void EgoEntitySimulation::update( } else { auto input = Eigen::VectorXd(vehicle_model_ptr_->getDimU()); - auto acceleration_by_slope = not consider_road_slope_ ? 0.0 : [this]() { + auto acceleration_by_slope = not consider_acceleration_by_road_slope_ ? 0.0 : [this]() { // calculate longitudinal acceleration by slope constexpr double gravity_acceleration = -9.81; const double ego_pitch_angle = calculateEgoPitch();