Skip to content

Commit

Permalink
Update control/pid_longitudinal_controller/src/pid_longitudinal_contr…
Browse files Browse the repository at this point in the history
…oller.cpp

Co-authored-by: Takamasa Horibe <[email protected]>
  • Loading branch information
danielsanchezaran and TakaHoribe authored Nov 24, 2023
1 parent ac377da commit f02b710
Showing 1 changed file with 2 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -974,11 +974,9 @@ double PidLongitudinalController::applyVelocityFeedback(
const bool vehicle_is_moving = std::abs(current_vel) > m_current_vel_threshold_pid_integrate;
const double time_under_control = getTimeUnderControl();
const bool vehicle_is_stuck =
m_enable_integration_at_low_speed
? !vehicle_is_moving && time_under_control > m_time_threshold_before_pid_integrate
: false;
!vehicle_is_moving && time_under_control > m_time_threshold_before_pid_integrate;

const bool enable_integration = (vehicle_is_moving || vehicle_is_stuck) && is_under_control;
const bool enable_integration = (vehicle_is_moving || (m_enable_integration_at_low_speed && vehicle_is_stuck)) && is_under_control;
const double error_vel_filtered = m_lpf_vel_error->filter(diff_vel);

std::vector<double> pid_contributions(3);
Expand Down

0 comments on commit f02b710

Please sign in to comment.