mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
GCS_MAVLink: tidy valid-channel check in install_alternative_protocol
- stop getting link multiple times - rely on chan() returning nullptr rather than explicitly checking num_gcs
This commit is contained in:
parent
14d1a075db
commit
26d714e9a9
@ -131,15 +131,16 @@ void GCS::enable_high_latency_connections(bool enabled)
|
||||
*/
|
||||
bool GCS::install_alternative_protocol(mavlink_channel_t c, GCS_MAVLINK::protocol_handler_fn_t handler)
|
||||
{
|
||||
if (c >= num_gcs()) {
|
||||
GCS_MAVLINK *link = chan(c);
|
||||
if (link == nullptr) {
|
||||
return false;
|
||||
}
|
||||
if (chan(c)->alternative.handler && handler) {
|
||||
if (link->alternative.handler && handler) {
|
||||
// already have one installed - we may need to add support for
|
||||
// multiple alternative handlers
|
||||
return false;
|
||||
}
|
||||
chan(c)->alternative.handler = handler;
|
||||
link->alternative.handler = handler;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user