Rover: add sanity check when fetching GCS_MAVLink instance

This commit is contained in:
Peter Barker 2019-06-25 12:56:48 +10:00 committed by Andrew Tridgell
parent 54ba686855
commit a50004baff
1 changed files with 14 additions and 2 deletions

View File

@ -13,9 +13,21 @@ public:
uint8_t num_gcs() const override { return ARRAY_SIZE(_chan); };
// return GCS link at offset ofs
GCS_MAVLINK_Rover &chan(const uint8_t ofs) override { return _chan[ofs]; };
GCS_MAVLINK_Rover &chan(uint8_t ofs) override {
if (ofs >= num_gcs()) {
AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
ofs = 0;
}
return _chan[ofs];
}
// return GCS link at offset ofs
const GCS_MAVLINK_Rover &chan(const uint8_t ofs) const override { return _chan[ofs]; };
const GCS_MAVLINK_Rover &chan(uint8_t ofs) const override {
if (ofs >= num_gcs()) {
AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
ofs = 0;
}
return _chan[ofs];
}
uint32_t custom_mode() const override;
MAV_TYPE frame_type() const override;