diff --git a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 94ad3c648b571..d845e1bb18304 100644 --- a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -977,7 +977,7 @@ double PidLongitudinalController::applyVelocityFeedback(const ControlData & cont const bool is_under_control = m_current_operation_mode.mode == OperationModeState::AUTONOMOUS; const bool enable_integration = (vel_after_delay_abs > m_current_vel_threshold_pid_integrate) && is_under_control; - const double error_vel = abs(target_vel_abs - vel_after_delay_abs); + const double error_vel = target_vel_abs - vel_after_delay_abs; const double error_vel_filtered = m_lpf_vel_error->filter(error_vel); std::vector pid_contributions(3); const double pid_acc = m_pid_vel.calculate(