mirror of https://github.com/ArduPilot/ardupilot
AC_PosControl: fix typo in D-filter definition
This commit is contained in:
parent
7e3213edbf
commit
2b0f142a17
|
@ -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
|
||||
|
|
|
@ -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
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue