mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: remove internal error from chan(), correct bounds check
It's been argued that callers should always be checking for nullptr anyway. This is the method which is best qualified to work out whether the channel actually corresponds to a link, so it makes sense for the check to be here
This commit is contained in:
parent
55f31d628a
commit
14d1a075db
@ -92,16 +92,14 @@ bool check_payload_size(mavlink_channel_t chan, uint16_t max_payload_len);
|
||||
// then call its own specific methods on
|
||||
#define GCS_MAVLINK_CHAN_METHOD_DEFINITIONS(subclass_name) \
|
||||
subclass_name *chan(const uint8_t ofs) override { \
|
||||
if (ofs > _num_gcs) { \
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset); \
|
||||
if (ofs >= _num_gcs) { \
|
||||
return nullptr; \
|
||||
} \
|
||||
return (subclass_name *)_chan[ofs]; \
|
||||
} \
|
||||
\
|
||||
const subclass_name *chan(const uint8_t ofs) const override { \
|
||||
if (ofs > _num_gcs) { \
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset); \
|
||||
if (ofs >= _num_gcs) { \
|
||||
return nullptr; \
|
||||
} \
|
||||
return (subclass_name *)_chan[ofs]; \
|
||||
|
Loading…
Reference in New Issue
Block a user