From 81454c7a4012a4e00d7936cfba3f086931656363 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 30 Apr 2020 10:40:46 +1000 Subject: [PATCH] GCS_MAVLink: create and use INTERNAL_ERROR macro so we get line numbers --- libraries/GCS_MAVLink/GCS_Dummy.h | 4 ++-- libraries/GCS_MAVLink/MissionItemProtocol.cpp | 8 ++++---- libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp | 4 ++-- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Dummy.h b/libraries/GCS_MAVLink/GCS_Dummy.h index 3dfc3329a7..2762c6ff18 100644 --- a/libraries/GCS_MAVLink/GCS_Dummy.h +++ b/libraries/GCS_MAVLink/GCS_Dummy.h @@ -74,14 +74,14 @@ protected: private: GCS_MAVLINK_Dummy *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_Dummy *)_chan[ofs]; }; const GCS_MAVLINK_Dummy *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_Dummy *)_chan[ofs]; diff --git a/libraries/GCS_MAVLink/MissionItemProtocol.cpp b/libraries/GCS_MAVLink/MissionItemProtocol.cpp index a8633f84f7..6df6e6d95b 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol.cpp @@ -214,7 +214,7 @@ void MissionItemProtocol::handle_mission_write_partial_list(GCS_MAVLINK &_link, void MissionItemProtocol::handle_mission_item(const mavlink_message_t &msg, const mavlink_mission_item_int_t &cmd) { if (link == nullptr) { - AP::internalerror().error(AP_InternalError::error_t::gcs_bad_missionprotocol_link); + INTERNAL_ERROR(AP_InternalError::error_t::gcs_bad_missionprotocol_link); return; } @@ -283,7 +283,7 @@ void MissionItemProtocol::send_mission_ack(const mavlink_message_t &msg, MAV_MISSION_RESULT result) const { if (link == nullptr) { - AP::internalerror().error(AP_InternalError::error_t::gcs_bad_missionprotocol_link); + INTERNAL_ERROR(AP_InternalError::error_t::gcs_bad_missionprotocol_link); return; } send_mission_ack(*link, msg, result); @@ -312,7 +312,7 @@ void MissionItemProtocol::queued_request_send() return; } if (link == nullptr) { - AP::internalerror().error(AP_InternalError::error_t::gcs_bad_missionprotocol_link); + INTERNAL_ERROR(AP_InternalError::error_t::gcs_bad_missionprotocol_link); return; } mavlink_msg_mission_request_send( @@ -331,7 +331,7 @@ void MissionItemProtocol::update() return; } if (link == nullptr) { - AP::internalerror().error(AP_InternalError::error_t::gcs_bad_missionprotocol_link); + INTERNAL_ERROR(AP_InternalError::error_t::gcs_bad_missionprotocol_link); return; } // stop waypoint receiving if timeout diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp index c7b261155a..dd824505af 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp @@ -103,7 +103,7 @@ static MAV_MISSION_RESULT convert_MISSION_ITEM_INT_to_AC_PolyFenceItem(const mav MAV_MISSION_RESULT MissionItemProtocol_Fence::replace_item(const mavlink_mission_item_int_t &mission_item_int) { if (_new_items == nullptr) { - AP::internalerror().error(AP_InternalError::error_t::flow_of_control); + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); return MAV_MISSION_ERROR; } if (mission_item_int.seq >= _new_items_count) { @@ -180,7 +180,7 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::allocate_receive_resources(const u if (_new_items != nullptr) { // this is an error - the base class should have called // free_upload_resources first - AP::internalerror().error(AP_InternalError::error_t::flow_of_control); + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); return MAV_MISSION_ERROR; }