Browse Source

Copter: use terrain alt for precland if rangefinder is unavailable

mission-4.1.18
Jonathan Challinger 9 years ago committed by Randy Mackay
parent
commit
e311139a21
  1. 10
      ArduCopter/precision_landing.cpp

10
ArduCopter/precision_landing.cpp

@ -15,13 +15,15 @@ void Copter::init_precland() @@ -15,13 +15,15 @@ void Copter::init_precland()
void Copter::update_precland()
{
float final_alt = current_loc.alt;
int32_t height_above_ground_cm = current_loc.alt;
// use range finder altitude if it is valid
// use range finder altitude if it is valid, else try to get terrain alt
if (rangefinder_alt_ok()) {
final_alt = rangefinder_state.alt_cm;
height_above_ground_cm = rangefinder_state.alt_cm;
} else if (terrain_use()) {
current_loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, height_above_ground_cm);
}
copter.precland.update(final_alt);
copter.precland.update(height_above_ground_cm);
}
#endif

Loading…
Cancel
Save