mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
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:
parent
3be76743bf
commit
542677f1d5
@ -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;
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user