diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 9599d24bfa2b9..3f92bbe8e92a1 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -321,9 +321,9 @@ void SimplePlanningSimulator::on_timer() } // calculate longitudinal acceleration by slope - const double ego_pitch_angle = calculate_ego_pitch(); - const double acc_by_slope = - enable_road_slope_simulation_ ? -9.81 * std::sin(ego_pitch_angle) : 0.0; + constexpr double gravity_acceleration = -9.81; + const double ego_pitch_angle = enable_road_slope_simulation_ ? calculate_ego_pitch() : 0.0; + const double acc_by_slope = gravity_acceleration * std::sin(ego_pitch_angle); // update vehicle dynamics {