mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
GCS_MAVLink: tidy valid-channel check in set_message_interval
rely on chan returning nullptr on invalid channel
This commit is contained in:
parent
80b781634d
commit
ccb56e573a
@ -2708,11 +2708,11 @@ MAV_RESULT GCS::set_message_interval(uint8_t port_num, uint32_t msg_id, int32_t
|
||||
{
|
||||
uint8_t channel = get_channel_from_port_number(port_num);
|
||||
|
||||
if ((channel < MAVLINK_COMM_NUM_BUFFERS) && (chan(channel) != nullptr)) {
|
||||
return chan(channel)->set_message_interval(msg_id, interval_us);
|
||||
GCS_MAVLINK *link = chan(channel);
|
||||
if (link == nullptr) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
|
||||
return MAV_RESULT_FAILED;
|
||||
return link->set_message_interval(msg_id, interval_us);
|
||||
}
|
||||
|
||||
uint8_t GCS::get_channel_from_port_number(uint8_t port_num)
|
||||
|
Loading…
Reference in New Issue
Block a user