mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: add sanity check when fetching GCS_MAVLink instance
This commit is contained in:
parent
fab17ba3bf
commit
80c7449145
@ -13,12 +13,20 @@ public:
|
|||||||
uint8_t num_gcs() const override { return ARRAY_SIZE(_chan); };
|
uint8_t num_gcs() const override { return ARRAY_SIZE(_chan); };
|
||||||
|
|
||||||
// return GCS link at offset ofs
|
// return GCS link at offset ofs
|
||||||
GCS_MAVLINK_Plane &chan(const uint8_t ofs) override {
|
GCS_MAVLINK_Plane &chan(uint8_t ofs) override {
|
||||||
|
if (ofs >= num_gcs()) {
|
||||||
|
AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
|
||||||
|
ofs = 0;
|
||||||
|
}
|
||||||
return _chan[ofs];
|
return _chan[ofs];
|
||||||
};
|
}
|
||||||
const GCS_MAVLINK_Plane &chan(const uint8_t ofs) const override {
|
const GCS_MAVLINK_Plane &chan(uint8_t ofs) const override {
|
||||||
|
if (ofs >= num_gcs()) {
|
||||||
|
AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
|
||||||
|
ofs = 0;
|
||||||
|
}
|
||||||
return _chan[ofs];
|
return _chan[ofs];
|
||||||
};
|
}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user