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 625a595ebd7..4cc63686d8c 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,6 +60,8 @@ class EgoEntitySimulation traffic_simulator_msgs::msg::EntityStatus status_; + bool consider_road_slope_ = false; + 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 3743e5002da..628416da5a9 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 @@ -38,7 +38,8 @@ EgoEntitySimulation::EgoEntitySimulation( : autoware(std::make_unique()), vehicle_model_type_(getVehicleModelType()), vehicle_model_ptr_(makeSimulationModel(vehicle_model_type_, step_time, parameters)), - hdmap_utils_ptr_(hdmap_utils) + hdmap_utils_ptr_(hdmap_utils), + consider_road_slope_(getParameter("consider_road_slope", false)) { }