Rover: ensure height calcs are using the same origin.

This commit is contained in:
Grant Morphett 2016-08-25 12:48:08 +10:00
parent ea7e62df17
commit 777af546e0
1 changed files with 9 additions and 1 deletions

View File

@ -97,7 +97,15 @@ void Rover::restart_nav()
void Rover::update_home()
{
if (home_is_set == HOME_SET_NOT_LOCKED) {
ahrs.set_home(gps.location());
Location loc = gps.location();
Location origin;
// if an EKF origin is available then we leave home equal to
// the height of that origin. This ensures that our relative
// height calculations are using the same origin
if (ahrs.get_origin(origin)) {
loc.alt = origin.alt;
}
ahrs.set_home(loc);
Log_Write_Home_And_Origin();
GCS_MAVLINK::send_home_all(gps.location());
}