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

This commit is contained in:
Peter Barker 2020-04-30 10:40:46 +10:00 committed by Peter Barker
parent 58a8e54d83
commit 81454c7a40
3 changed files with 8 additions and 8 deletions

View File

@ -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];

View File

@ -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

View File

@ -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;
}