Browse Source

Copter: precland checks get_alt_cm return value

This makes it easier for Covarity to recognise that we don't have an error by checking the return value of get_alt_cm
No functional change
master
Randy Mackay 9 years ago
parent
commit
3be76743bf
  1. 4
      ArduCopter/precision_landing.cpp

4
ArduCopter/precision_landing.cpp

@ -21,7 +21,9 @@ void Copter::update_precland()
if (rangefinder_alt_ok()) { if (rangefinder_alt_ok()) {
height_above_ground_cm = rangefinder_state.alt_cm; height_above_ground_cm = rangefinder_state.alt_cm;
} else if (terrain_use()) { } else if (terrain_use()) {
current_loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, height_above_ground_cm); if (!current_loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, height_above_ground_cm)) {
height_above_ground_cm = current_loc.alt;
}
} }
copter.precland.update(height_above_ground_cm); copter.precland.update(height_above_ground_cm);

Loading…
Cancel
Save