AP_AHRS: supply missing get_relative_position_D_home

Simply returns the baro altitude (like EKF does if it lacks
position)
This commit is contained in:
Peter Barker 2017-02-23 17:48:15 +11:00 committed by Andrew Tridgell
parent 24647fb2b0
commit 4ed7fb154f
2 changed files with 8 additions and 0 deletions

View File

@ -1003,6 +1003,12 @@ void AP_AHRS_DCM::set_home(const Location &loc)
_home.options = 0;
}
// a relative ground position to home in meters, Down
void AP_AHRS_DCM::get_relative_position_D_home(float &posD) const
{
posD = -_baro.get_altitude();
}
/*
check if the AHRS subsystem is healthy
*/

View File

@ -100,6 +100,8 @@ public:
return _wind;
}
void get_relative_position_D_home(float &posD) const override;
// return an airspeed estimate if available. return true
// if we have an estimate
bool airspeed_estimate(float *airspeed_ret) const;