mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AC_PosControl: Use blended accelerometer measurement in altitude control
This commit is contained in:
parent
9261dfdefb
commit
bfe71fea82
@ -353,7 +353,7 @@ void AC_PosControl::accel_to_throttle(float accel_target_z)
|
||||
int32_t p,i,d; // used to capture pid values for logging
|
||||
|
||||
// Calculate Earth Frame Z acceleration
|
||||
z_accel_meas = -(_ahrs.get_accel_ef().z + GRAVITY_MSS) * 100.0f;
|
||||
z_accel_meas = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
|
||||
|
||||
// reset target altitude if this controller has just been engaged
|
||||
if (_flags.reset_accel_to_throttle) {
|
||||
|
Loading…
Reference in New Issue
Block a user