AC_PosControl: fix typo in D-filter definition

This commit is contained in:
Randy Mackay 2014-05-29 17:50:13 +09:00
parent 7e3213edbf
commit 2b0f142a17
2 changed files with 2 additions and 2 deletions

View File

@ -80,7 +80,7 @@ void AC_PosControl::set_dt(float delta_sec)
_dt = delta_sec;
// update rate controller's d filter
_pid_alt_accel.set_d_lpf_alpha(POSCONTROOL_ACCEL_Z_DTERM_FILTER, _dt);
_pid_alt_accel.set_d_lpf_alpha(POSCONTROL_ACCEL_Z_DTERM_FILTER, _dt);
}
/// set_speed_z - sets maximum climb and descent rates

View File

@ -36,7 +36,7 @@
#define POSCONTROL_ACTIVE_TIMEOUT_MS 200 // position controller is considered active if it has been called within the past 200ms (0.2 seconds)
#define POSCONTROOL_ACCEL_Z_DTERM_FILTER 20 // Z axis accel controller's D term filter (in hz)
#define POSCONTROL_ACCEL_Z_DTERM_FILTER 20 // Z axis accel controller's D term filter (in hz)
class AC_PosControl
{