mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 14:13:42 -04:00
2da88263e6
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
21 lines
407 B
C++
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
|