Skip to content

Commit

Permalink
change pid wrt design
Browse files Browse the repository at this point in the history
  • Loading branch information
brkay54 committed Sep 18, 2023
1 parent e7292cd commit e4c7de9
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -29,14 +29,15 @@ class PIDController
/**
* @brief calculate the output of this PID
* @param [in] error previous error
* @param [in] error_filtered filtered error
* @param [in] dt time step [s]
* @param [in] is_integrated if true, will use the integral component for calculation
* @param [out] pid_contributions values of the proportional, integral, and derivative components
* @return PID output
* @throw std::runtime_error if gains or limits have not been set
*/
double calculate(
const double error, const double dt, const bool is_integrated,
const double error, const double error_filtered, const double dt, const bool is_integrated,
std::vector<double> & pid_contributions);
/**
* @brief set the coefficients for the P (proportional) I (integral) D (derivative) terms
Expand Down
6 changes: 3 additions & 3 deletions control/pid_longitudinal_controller/src/pid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ PIDController::PIDController()
}

double PIDController::calculate(
const double error, const double dt, const bool enable_integration,
const double error, const double filtered_error, const double dt, const bool enable_integration,
std::vector<double> & pid_contributions)
{
if (!m_is_gains_set || !m_is_limits_set) {
Expand All @@ -55,12 +55,12 @@ double PIDController::calculate(
error_differential = 0;
m_is_first_time = false;
} else {
error_differential = (error - m_prev_error) / dt;
error_differential = (filtered_error - m_prev_error) / dt;
}
double ret_d = p.kd * error_differential;
ret_d = std::min(std::max(ret_d, p.min_ret_d), p.max_ret_d);

m_prev_error = error;
m_prev_error = filtered_error;

pid_contributions.resize(3);
pid_contributions.at(0) = ret_p;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -977,11 +977,11 @@ 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_filtered = m_lpf_vel_error->filter(target_vel_abs - vel_after_delay_abs);

const double error_vel = abs(target_vel_abs - vel_after_delay_abs);
const double error_vel_filtered = m_lpf_vel_error->filter(error_vel);
std::vector<double> pid_contributions(3);
const double pid_acc =
m_pid_vel.calculate(error_vel_filtered, control_data.dt, enable_integration, pid_contributions);
const double pid_acc = m_pid_vel.calculate(
error_vel, error_vel_filtered, control_data.dt, enable_integration, pid_contributions);

// Feedforward scaling:
// This is for the coordinate conversion where feedforward is applied, from Time to Arclength.
Expand Down

0 comments on commit e4c7de9

Please sign in to comment.