Browse Source

AP_TECS: use baro singleton

master
Peter Barker 7 years ago committed by Lucas De Marchi
parent
commit
ffcb9ce945
  1. 2
      libraries/AP_TECS/AP_TECS.cpp

2
libraries/AP_TECS/AP_TECS.cpp

@ -296,7 +296,7 @@ void AP_TECS::update_50hz(void) @@ -296,7 +296,7 @@ void AP_TECS::update_50hz(void)
use a complimentary filter to calculate climb_rate. This is
designed to minimise lag
*/
float baro_alt = _ahrs.get_baro().get_altitude();
const float baro_alt = AP::baro().get_altitude();
// Get height acceleration
float hgt_ddot_mea = -(_ahrs.get_accel_ef().z + GRAVITY_MSS);
// Perform filter calculation using backwards Euler integration

Loading…
Cancel
Save