mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_TECS: Update for AHRS NED changes
This commit is contained in:
parent
95edf6ab66
commit
666c63da9f
@ -272,12 +272,8 @@ void AP_TECS::update_50hz(void)
|
|||||||
if we have a vertical position estimate from the EKF then use
|
if we have a vertical position estimate from the EKF then use
|
||||||
it, otherwise use barometric altitude
|
it, otherwise use barometric altitude
|
||||||
*/
|
*/
|
||||||
Vector3f posned;
|
_ahrs.get_relative_position_D_home(_height);
|
||||||
if (_ahrs.get_relative_position_NED(posned)) {
|
_height *= -1.0f;
|
||||||
_height = - posned.z;
|
|
||||||
} else {
|
|
||||||
_height = _ahrs.get_baro().get_altitude();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Calculate time in seconds since last update
|
// Calculate time in seconds since last update
|
||||||
uint64_t now = AP_HAL::micros64();
|
uint64_t now = AP_HAL::micros64();
|
||||||
|
Loading…
Reference in New Issue
Block a user