mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: create and use INTERNAL_ERROR macro so we get line numbers
This commit is contained in:
parent
ba5bbcdea7
commit
86c765d8c9
|
@ -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];
|
||||
|
|
Loading…
Reference in New Issue