ardupilot/ArduCopter/precision_landing.cpp
Peter Barker 2da88263e6 Copter: tidy invocation of precland.update
Setting the altitude to home-relative is misleading/wasteful in this method as
the alt is unused in precland unless it is marked as "OK" with the
second parameter
2021-09-11 14:17:24 +10:00

21 lines
407 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()
{
// alt will be unused if we pass false through as the second parameter:
return precland.update(rangefinder_state.alt_cm_glitch_protected,
rangefinder_alt_ok());
}
#endif