ArduPlane: create and use INTERNAL_ERROR macro so we get line numbers

This commit is contained in:
Peter Barker 2020-04-30 10:40:47 +10:00 committed by Peter Barker
parent ba5bbcdea7
commit 86c765d8c9
1 changed files with 2 additions and 2 deletions

View File

@ -12,14 +12,14 @@ public:
// return GCS link at offset ofs
GCS_MAVLINK_Plane *chan(const uint8_t ofs) override {
if (ofs > _num_gcs) {
AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
return nullptr;
}
return (GCS_MAVLINK_Plane *)_chan[ofs];
}
const GCS_MAVLINK_Plane *chan(const uint8_t ofs) const override {
if (ofs > _num_gcs) {
AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
return nullptr;
}
return (GCS_MAVLINK_Plane *)_chan[ofs];