mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_AHRS: get_relative_position_D_home: don't use home until set
This commit is contained in:
parent
341d66800a
commit
3854e4a99d
@ -1773,6 +1773,13 @@ bool AP_AHRS::get_relative_position_D_origin(float &posD) const
|
||||
// will use the barometer if the EKF isn't available
|
||||
void AP_AHRS::get_relative_position_D_home(float &posD) const
|
||||
{
|
||||
if (!_home_is_set) {
|
||||
// fall back to an altitude derived from barometric pressure
|
||||
// differences vs a calibrated ground pressure:
|
||||
posD = -AP::baro().get_altitude();
|
||||
return;
|
||||
}
|
||||
|
||||
Location originLLH;
|
||||
float originD;
|
||||
if (!get_relative_position_D_origin(originD) ||
|
||||
|
Loading…
Reference in New Issue
Block a user