GCS_MAVLink: tidy check of valid channel in get_vfr_hud_throttle

do a nullptr check rather than checking against num_gcs
This commit is contained in:
Peter Barker 2022-12-22 17:33:16 +11:00 committed by Andrew Tridgell
parent 74978ac577
commit 80b781634d
1 changed files with 7 additions and 1 deletions

View File

@ -1149,7 +1149,13 @@ public:
bool install_alternative_protocol(mavlink_channel_t chan, GCS_MAVLINK::protocol_handler_fn_t handler);
// get the VFR_HUD throttle
int16_t get_hud_throttle(void) const { return num_gcs()>0?chan(0)->vfr_hud_throttle():0; }
int16_t get_hud_throttle(void) const {
const GCS_MAVLINK *link = chan(0);
if (link == nullptr) {
return 0;
}
return link->vfr_hud_throttle();
}
// update uart pass-thru
void update_passthru();