Copter: land vertical control uses current_loc.alt instead of get_alt_cm

This resolves a warning from Covarity that we were not checking the return
value of Location_Class::get_alt_cm.  It was not actually a problem.
No functional change
This commit is contained in:
Randy Mackay 2016-08-08 12:27:18 +09:00
parent 3be76743bf
commit 542677f1d5

View File

@ -164,7 +164,7 @@ void Copter::land_run_vertical_control(bool pause_descent)
alt_above_ground = rangefinder_state.alt_cm_filt.get();
} else {
if (!navigating || !current_loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, alt_above_ground)) {
current_loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_HOME, alt_above_ground);
alt_above_ground = current_loc.alt;
}
}