mirror of https://github.com/ArduPilot/ardupilot
26 lines
503 B
C++
26 lines
503 B
C++
//
|
|
// functions to support precision landing
|
|
//
|
|
|
|
#include "Copter.h"
|
|
|
|
#if PRECISION_LANDING == ENABLED
|
|
|
|
void Copter::init_precland()
|
|
{
|
|
copter.precland.init(400);
|
|
}
|
|
|
|
void Copter::update_precland()
|
|
{
|
|
int32_t height_above_ground_cm = current_loc.alt;
|
|
|
|
// use range finder altitude if it is valid, otherwise use home alt
|
|
if (rangefinder_alt_ok()) {
|
|
height_above_ground_cm = rangefinder_state.alt_cm;
|
|
}
|
|
|
|
precland.update(height_above_ground_cm, rangefinder_alt_ok());
|
|
}
|
|
#endif
|