mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AC_PosControl: init accel_last_z_cms
This commit is contained in:
parent
b8e3fe8f26
commit
11fee21f06
@ -46,6 +46,7 @@ AC_PosControl::AC_PosControl(const AP_AHRS& ahrs, const AP_InertialNav& inav,
|
||||
_speed_up_cms(POSCONTROL_SPEED_UP),
|
||||
_speed_cms(POSCONTROL_SPEED),
|
||||
_accel_z_cms(POSCONTROL_ACCEL_Z),
|
||||
_accel_last_z_cms(0.0f),
|
||||
_accel_cms(POSCONTROL_ACCEL_XY),
|
||||
_leash(POSCONTROL_LEASH_LENGTH_MIN),
|
||||
_leash_down_z(POSCONTROL_LEASH_LENGTH_MIN),
|
||||
|
Loading…
Reference in New Issue
Block a user