Tools: Replay: cope with WARN_IF_UNUSED on AP_AHRS::set_home

This commit is contained in:
Peter Barker 2019-02-13 16:18:27 +11:00 committed by Peter Barker
parent 0c880a4c3e
commit bf9b8f41bf
1 changed files with 3 additions and 1 deletions

View File

@ -639,7 +639,9 @@ void Replay::read_sensors(const char *type)
loc.lng * 1.0e-7f, loc.lng * 1.0e-7f,
loc.alt * 0.01f, loc.alt * 0.01f,
AP_HAL::millis()*0.001f); AP_HAL::millis()*0.001f);
_vehicle.ahrs.set_home(loc); if (!_vehicle.ahrs.set_home(loc)) {
::printf("Failed to set home to that location!");
}
_vehicle.compass.set_initial_location(loc.lat, loc.lng); _vehicle.compass.set_initial_location(loc.lat, loc.lng);
done_home_init = true; done_home_init = true;
} }