mirror of https://github.com/ArduPilot/ardupilot
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:
parent
74978ac577
commit
80b781634d
|
@ -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();
|
||||
|
|
Loading…
Reference in New Issue