From 14d1a075dbe949789e449c4591f7f045a498c696 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 15 Dec 2022 16:13:46 +1100 Subject: [PATCH] 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 --- libraries/GCS_MAVLink/GCS.h | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 237949fa37..04ed42f463 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -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]; \