mirror of https://github.com/ArduPilot/ardupilot
AntennaTracker: create and use INTERNAL_ERROR macro so we get line numbers
This commit is contained in:
parent
81454c7a40
commit
19f298e04c
|
@ -13,14 +13,14 @@ public:
|
||||||
// return GCS link at offset ofs
|
// return GCS link at offset ofs
|
||||||
GCS_MAVLINK_Tracker *chan(const uint8_t ofs) override {
|
GCS_MAVLINK_Tracker *chan(const uint8_t ofs) override {
|
||||||
if (ofs > _num_gcs) {
|
if (ofs > _num_gcs) {
|
||||||
AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
|
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
return (GCS_MAVLINK_Tracker*)_chan[ofs];
|
return (GCS_MAVLINK_Tracker*)_chan[ofs];
|
||||||
}
|
}
|
||||||
const GCS_MAVLINK_Tracker *chan(const uint8_t ofs) const override {
|
const GCS_MAVLINK_Tracker *chan(const uint8_t ofs) const override {
|
||||||
if (ofs > _num_gcs) {
|
if (ofs > _num_gcs) {
|
||||||
AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
|
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
return (GCS_MAVLINK_Tracker*)_chan[ofs];
|
return (GCS_MAVLINK_Tracker*)_chan[ofs];
|
||||||
|
|
Loading…
Reference in New Issue