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
This commit is contained in:
Peter Barker 2021-04-14 14:02:18 +10:00 committed by Peter Barker
parent 3ec53e2aec
commit 2da88263e6
1 changed files with 3 additions and 8 deletions

View File

@ -13,13 +13,8 @@ void Copter::init_precland()
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_glitch_protected;
}
precland.update(height_above_ground_cm, rangefinder_alt_ok());
// 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