ardupilot/ArduCopter/precision_landing.cpp

30 lines
741 B
C++

//
// functions to support precision landing
//
#include "Copter.h"
#if PRECISION_LANDING == ENABLED
void Copter::init_precland()
{
copter.precland.init();
}
void Copter::update_precland()
{
int32_t height_above_ground_cm = current_loc.alt;
// use range finder altitude if it is valid, else try to get terrain alt
if (rangefinder_alt_ok()) {
height_above_ground_cm = rangefinder_state.alt_cm;
} else if (terrain_use()) {
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, rangefinder_alt_ok());
}
#endif