diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 0c915ec42a..1b72dad3fb 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -54,6 +54,8 @@ #include #include +#include + #include #include "mavlink_receiver.h" #include "mavlink_main.h" @@ -2321,11 +2323,15 @@ Mavlink::task_main(int argc, char *argv[]) !_transmitting_enabled_commanded && _first_heartbeat_sent) { _transmitting_enabled = false; - mavlink_log_info(&_mavlink_log_pub, "Disable transmitting with IRIDIUM mavlink on device %s", _device_name); + mavlink_log_info(&_mavlink_log_pub, "Disable transmitting with IRIDIUM mavlink on device %s\t", _device_name); + events::send(events::ID("mavlink_iridium_disable"), events::Log::Info, + "Disabling transmitting with IRIDIUM mavlink on instance {1}", _instance_id); } else if (!_transmitting_enabled && !vehicle_status.high_latency_data_link_lost) { _transmitting_enabled = true; - mavlink_log_info(&_mavlink_log_pub, "Enable transmitting with IRIDIUM mavlink on device %s", _device_name); + mavlink_log_info(&_mavlink_log_pub, "Enable transmitting with IRIDIUM mavlink on device %s\t", _device_name); + events::send(events::ID("mavlink_iridium_enable"), events::Log::Info, + "Enabling transmitting with IRIDIUM mavlink on instance {1}", _instance_id); } } } @@ -2348,8 +2354,10 @@ Mavlink::task_main(int argc, char *argv[]) if (vehicle_cmd.param1 > 0.5f) { if (!_transmitting_enabled) { - mavlink_log_info(&_mavlink_log_pub, "Enable transmitting with IRIDIUM mavlink on device %s by command", + mavlink_log_info(&_mavlink_log_pub, "Enable transmitting with IRIDIUM mavlink on device %s by command\t", _device_name); + events::send(events::ID("mavlink_iridium_enable_cmd"), events::Log::Info, + "Enabling transmitting with IRIDIUM mavlink on instance {1} by command", _instance_id); } _transmitting_enabled = true; @@ -2357,8 +2365,10 @@ Mavlink::task_main(int argc, char *argv[]) } else { if (_transmitting_enabled) { - mavlink_log_info(&_mavlink_log_pub, "Disable transmitting with IRIDIUM mavlink on device %s by command", + mavlink_log_info(&_mavlink_log_pub, "Disable transmitting with IRIDIUM mavlink on device %s by command\t", _device_name); + events::send(events::ID("mavlink_iridium_disable_cmd"), events::Log::Info, + "Disabling transmitting with IRIDIUM mavlink on instance {1} by command", _instance_id); } _transmitting_enabled = false; diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index e1eb750ebf..b4b2ab0b73 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -47,6 +47,7 @@ #include #include #include +#include #include #include #include @@ -188,7 +189,9 @@ MavlinkMissionManager::update_active_mission(dm_item_t dataman_id, uint16_t coun PX4_ERR("WPM: can't save mission state"); if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) { - _mavlink->send_statustext_critical("Mission storage: Unable to write to microSD"); + _mavlink->send_statustext_critical("Mission storage: Unable to write to microSD\t"); + events::send(events::ID("mavlink_mission_storage_write_failure"), events::Log::Critical, + "Mission: Unable to write to storage"); } return PX4_ERROR; @@ -210,7 +213,9 @@ MavlinkMissionManager::update_geofence_count(unsigned count) } else { if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) { - _mavlink->send_statustext_critical("Mission storage: Unable to write to microSD"); + _mavlink->send_statustext_critical("Mission storage: Unable to write to microSD\t"); + events::send(events::ID("mavlink_mission_storage_write_failure2"), events::Log::Critical, + "Mission: Unable to write to storage"); } return PX4_ERROR; @@ -235,7 +240,9 @@ MavlinkMissionManager::update_safepoint_count(unsigned count) } else { if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) { - _mavlink->send_statustext_critical("Mission storage: Unable to write to microSD"); + _mavlink->send_statustext_critical("Mission storage: Unable to write to microSD\t"); + events::send(events::ID("mavlink_mission_storage_write_failure3"), events::Log::Critical, + "Mission: Unable to write to storage"); } return PX4_ERROR; @@ -275,7 +282,9 @@ MavlinkMissionManager::send_mission_current(int32_t seq) } else { PX4_DEBUG("WPM: Send MISSION_CURRENT ERROR: seq %d out of bounds", seq); - _mavlink->send_statustext_critical("ERROR: wp index out of bounds"); + _mavlink->send_statustext_critical("ERROR: wp index out of bounds\t"); + events::send(events::ID("mavlink_mission_wp_index_out_of_bounds"), events::Log::Error, + "Waypoint index out of bounds ({1} \\< {2})", seq, item_count); } } @@ -344,7 +353,9 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t break; default: - _mavlink->send_statustext_critical("Received unknown mission type, abort."); + _mavlink->send_statustext_critical("Received unknown mission type, abort.\t"); + events::send(events::ID("mavlink_mission_recv_unknown_mis_type"), events::Log::Error, + "Received unknown mission type, abort"); break; } @@ -382,7 +393,9 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) { - _mavlink->send_statustext_critical("Mission storage: Unable to read from microSD"); + _mavlink->send_statustext_critical("Mission storage: Unable to read from microSD\t"); + events::send(events::ID("mavlink_mission_storage_read_failure"), events::Log::Error, + "Mission: Unable to read from storage"); } PX4_DEBUG("WPM: Send MISSION_ITEM ERROR: could not read seq %u from dataman ID %i", seq, _dataman_id); @@ -441,7 +454,9 @@ MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint1 } } else { - _mavlink->send_statustext_critical("ERROR: Waypoint index exceeds list capacity"); + _mavlink->send_statustext_critical("ERROR: Waypoint index exceeds list capacity\t"); + events::send(events::ID("mavlink_mission_wp_index_exceeds_list"), events::Log::Error, + "Waypoint index eceeds list capacity (maximum: {1})", current_max_item_count()); PX4_DEBUG("WPM: Send MISSION_REQUEST ERROR: seq %u exceeds list capacity", seq); } @@ -522,7 +537,9 @@ MavlinkMissionManager::send() } else if (_state != MAVLINK_WPM_STATE_IDLE && (_time_last_recv > 0) && hrt_elapsed_time(&_time_last_recv) > MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT) { - _mavlink->send_statustext_critical("Operation timeout"); + _mavlink->send_statustext_critical("Operation timeout\t"); + events::send(events::ID("mavlink_mission_op_timeout"), events::Log::Error, + "Operation timeout, aborting transfer"); PX4_DEBUG("WPM: Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _state); @@ -633,7 +650,9 @@ MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg) } } else { - _mavlink->send_statustext_critical("REJ. WP CMD: partner id mismatch"); + _mavlink->send_statustext_critical("REJ. WP CMD: partner id mismatch\t"); + events::send(events::ID("mavlink_mission_partner_id_mismatch"), events::Log::Error, + "Rejecting waypoint command, component or system ID mismatch"); PX4_DEBUG("WPM: MISSION_ACK ERR: ID mismatch"); } @@ -657,19 +676,25 @@ MavlinkMissionManager::handle_mission_set_current(const mavlink_message_t *msg) } else { PX4_DEBUG("WPM: MISSION_SET_CURRENT seq=%d ERROR", wpc.seq); - _mavlink->send_statustext_critical("WPM: WP CURR CMD: Error setting ID"); + _mavlink->send_statustext_critical("WPM: WP CURR CMD: Error setting ID\t"); + events::send(events::ID("mavlink_mission_err_id"), events::Log::Error, + "Failed to write current mission ID to storage"); } } else { PX4_ERR("WPM: MISSION_SET_CURRENT seq=%d ERROR: not in list", wpc.seq); - _mavlink->send_statustext_critical("WPM: WP CURR CMD: Not in list"); + _mavlink->send_statustext_critical("WPM: WP CURR CMD: Not in list\t"); + events::send(events::ID("mavlink_mission_seq_out_of_bounds"), events::Log::Error, + "New mission waypoint sequence out of bounds"); } } else { PX4_DEBUG("WPM: MISSION_SET_CURRENT ERROR: busy"); - _mavlink->send_statustext_critical("WPM: IGN WP CURR CMD: Busy"); + _mavlink->send_statustext_critical("WPM: IGN WP CURR CMD: Busy\t"); + events::send(events::ID("mavlink_mission_state_busy"), events::Log::Error, + "Mission manager currently busy, ignoring new waypoint index"); } } } @@ -728,7 +753,9 @@ MavlinkMissionManager::handle_mission_request_list(const mavlink_message_t *msg) } else { PX4_DEBUG("WPM: MISSION_REQUEST_LIST ERROR: busy"); - _mavlink->send_statustext_info("Mission download request ignored, already active"); + _mavlink->send_statustext_info("Mission download request ignored, already active\t"); + events::send(events::ID("mavlink_mission_req_ignored"), events::Log::Warning, + "Mission download request ignored, already active"); } } } @@ -801,7 +828,9 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg) switch_to_idle_state(); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); - _mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected"); + _mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected\t"); + events::send(events::ID("mavlink_mission_wp_unexpected"), events::Log::Error, + "Unexpected waypoint index, aborting transfer"); return; } @@ -816,7 +845,9 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg) switch_to_idle_state(); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); - _mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected"); + _mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected\t"); + events::send(events::ID("mavlink_mission_wp_unexpected2"), events::Log::Error, + "Unexpected waypoint index, aborting mission transfer"); } } else if (_state == MAVLINK_WPM_STATE_IDLE) { @@ -828,11 +859,15 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg) } else { PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: busy (state %d).", _state); - _mavlink->send_statustext_critical("WPM: REJ. CMD: Busy"); + _mavlink->send_statustext_critical("WPM: REJ. CMD: Busy\t"); + events::send(events::ID("mavlink_mission_mis_req_ignored_busy"), events::Log::Error, + "Ignoring mission request, currently busy"); } } else { - _mavlink->send_statustext_critical("WPM: REJ. CMD: partner id mismatch"); + _mavlink->send_statustext_critical("WPM: REJ. CMD: partner id mismatch\t"); + events::send(events::ID("mavlink_mission_partner_id_mismatch2"), events::Log::Error, + "Rejecting mission request command, component or system ID mismatch"); PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: rejected, partner ID mismatch"); } @@ -937,7 +972,9 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg) } else { PX4_DEBUG("WPM: MISSION_COUNT ERROR: busy, already receiving seq %u", _transfer_seq); - _mavlink->send_statustext_critical("WPM: REJ. CMD: Busy"); + _mavlink->send_statustext_critical("WPM: REJ. CMD: Busy\t"); + events::send(events::ID("mavlink_mission_getlist_busy"), events::Log::Error, + "Mission upload busy, already receiving waypoint"); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); return; @@ -946,7 +983,9 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg) } else { PX4_DEBUG("WPM: MISSION_COUNT ERROR: busy, state %i", _state); - _mavlink->send_statustext_critical("WPM: IGN MISSION_COUNT: Busy"); + _mavlink->send_statustext_critical("WPM: IGN MISSION_COUNT: Busy\t"); + events::send(events::ID("mavlink_mission_ignore_mis_count"), events::Log::Error, + "Mission upload busy, ignoring MISSION_COUNT"); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); return; } @@ -1030,7 +1069,9 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) } else { PX4_DEBUG("WPM: MISSION_ITEM ERROR: no transfer"); - _mavlink->send_statustext_critical("IGN MISSION_ITEM: No transfer"); + _mavlink->send_statustext_critical("IGN MISSION_ITEM: No transfer\t"); + events::send(events::ID("mavlink_mission_no_transfer"), events::Log::Error, + "Ignoring mission item, no transfer in progress"); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); } @@ -1039,7 +1080,9 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) } else { PX4_DEBUG("WPM: MISSION_ITEM ERROR: busy, state %i", _state); - _mavlink->send_statustext_critical("IGN MISSION_ITEM: Busy"); + _mavlink->send_statustext_critical("IGN MISSION_ITEM: Busy\t"); + events::send(events::ID("mavlink_mission_mis_item_busy"), events::Log::Error, + "Ignoring mission item, busy"); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); return; } @@ -1051,7 +1094,9 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) if (ret != PX4_OK) { PX4_DEBUG("WPM: MISSION_ITEM ERROR: seq %u invalid item", wp.seq); - _mavlink->send_statustext_critical("IGN MISSION_ITEM: Invalid item"); + _mavlink->send_statustext_critical("IGN MISSION_ITEM: Invalid item\t"); + events::send(events::ID("mavlink_mission_mis_item_invalid"), events::Log::Error, + "Ignoring mission item, invalid item"); send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, ret); switch_to_idle_state(); @@ -1133,7 +1178,9 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) break; default: - _mavlink->send_statustext_critical("Received unknown mission type, abort."); + _mavlink->send_statustext_critical("Received unknown mission type, abort.\t"); + events::send(events::ID("mavlink_mission_unknown_mis_type"), events::Log::Error, + "Received unknown mission type, abort"); break; } @@ -1143,7 +1190,9 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); if (write_failed) { - _mavlink->send_statustext_critical("Unable to write on micro SD"); + _mavlink->send_statustext_critical("Unable to write on micro SD\t"); + events::send(events::ID("mavlink_mission_storage_failure"), events::Log::Error, + "Mission: unable to write to storage"); } switch_to_idle_state(); @@ -1257,7 +1306,9 @@ MavlinkMissionManager::handle_mission_clear_all(const mavlink_message_t *msg) } } else { - _mavlink->send_statustext_critical("WPM: IGN CLEAR CMD: Busy"); + _mavlink->send_statustext_critical("WPM: IGN CLEAR CMD: Busy\t"); + events::send(events::ID("mavlink_mission_ignore_clear"), events::Log::Error, + "Ignoring mission clear command, busy"); PX4_DEBUG("WPM: CLEAR_ALL IGNORED: busy"); } diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index e777b30115..4574ccb912 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -120,15 +120,11 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) param_t param = param_find_no_notification(name); if (param == PARAM_INVALID) { - char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; - sprintf(buf, "[pm] unknown param: %s", name); - _mavlink->send_statustext_info(buf); + PX4_ERR("unknown param: %s", name); } else if (!((param_type(param) == PARAM_TYPE_INT32 && set.param_type == MAV_PARAM_TYPE_INT32) || (param_type(param) == PARAM_TYPE_FLOAT && set.param_type == MAV_PARAM_TYPE_REAL32))) { - char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; - sprintf(buf, "[pm] param types mismatch param: %s", name); - _mavlink->send_statustext_info(buf); + PX4_ERR("param types mismatch param: %s", name); } else { // According to the mavlink spec we should always acknowledge a write operation. @@ -204,14 +200,10 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) int ret = send_param(param_for_used_index(req_read.param_index)); if (ret == 1) { - char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; - sprintf(buf, "[pm] unknown param ID: %u", req_read.param_index); - _mavlink->send_statustext_info(buf); + PX4_ERR("unknown param ID: %i", req_read.param_index); } else if (ret == 2) { - char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; - sprintf(buf, "[pm] failed loading param from storage ID: %u", req_read.param_index); - _mavlink->send_statustext_info(buf); + PX4_ERR("failed loading param from storage ID: %i", req_read.param_index); } } } @@ -248,7 +240,9 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) size_t i = map_rc.parameter_rc_channel_index; if (i >= sizeof(_rc_param_map.param_index) / sizeof(_rc_param_map.param_index[0])) { - mavlink_log_warning(_mavlink->get_mavlink_log_pub(), "parameter_rc_channel_index out of bounds"); + mavlink_log_warning(_mavlink->get_mavlink_log_pub(), "parameter_rc_channel_index out of bounds\t"); + events::send(events::ID("mavlink_param_rc_chan_out_of_bounds"), events::Log::Warning, + "parameter_rc_channel_index out of bounds"); break; } diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index c59852a05f..022d8002eb 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -585,7 +585,9 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const if (_mavlink->get_data_rate() < 5000) { send_ack = true; result = vehicle_command_ack_s::VEHICLE_RESULT_DENIED; - _mavlink->send_statustext_critical("Not enough bandwidth to enable log streaming"); + _mavlink->send_statustext_critical("Not enough bandwidth to enable log streaming\t"); + events::send(events::ID("mavlink_log_not_enough_bw"), events::Log::Error, + "Not enough bandwidth to enable log streaming ({1} \\< 5000)", _mavlink->get_data_rate()); } else { // we already instanciate the streaming object, because at this point we know on which @@ -957,8 +959,10 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t setpoint.z = NAN; } else { - mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_LOCAL_NED coordinate frame %" PRIu8 " unsupported", + mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_LOCAL_NED coordinate frame %" PRIu8 " unsupported\t", target_local_ned.coordinate_frame); + events::send(events::ID("mavlink_rcv_sp_target_unsup_coord"), events::Log::Error, + "SET_POSITION_TARGET_LOCAL_NED: coordinate frame {1} unsupported", target_local_ned.coordinate_frame); return; } @@ -977,7 +981,9 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t || PX4_ISFINITE(setpoint.acceleration[2]); if (ocm.acceleration && (type_mask & POSITION_TARGET_TYPEMASK_FORCE_SET)) { - mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_LOCAL_NED force not supported"); + mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_LOCAL_NED force not supported\t"); + events::send(events::ID("mavlink_rcv_sp_target_unsup_force"), events::Log::Error, + "SET_POSITION_TARGET_LOCAL_NED: FORCE is not supported"); return; } @@ -996,7 +1002,9 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t } } else { - mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_LOCAL_NED invalid"); + mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_LOCAL_NED invalid\t"); + events::send(events::ID("mavlink_rcv_sp_target_invalid"), events::Log::Error, + "SET_POSITION_TARGET_LOCAL_NED: invalid, missing position, velocity or acceleration"); } } } @@ -1065,8 +1073,10 @@ MavlinkReceiver::handle_message_set_position_target_global_int(mavlink_message_t } } else { - mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_GLOBAL_INT invalid coordinate frame %" PRIu8, + mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_GLOBAL_INT invalid coordinate frame %" PRIu8 "\t", target_global_int.coordinate_frame); + events::send(events::ID("mavlink_rcv_sp_target_gl_invalid_coord"), events::Log::Error, + "SET_POSITION_TARGET_GLOBAL_INT invalid coordinate frame {1}", target_global_int.coordinate_frame); return; } @@ -1101,7 +1111,9 @@ MavlinkReceiver::handle_message_set_position_target_global_int(mavlink_message_t || PX4_ISFINITE(setpoint.acceleration[2]); if (ocm.acceleration && (type_mask & POSITION_TARGET_TYPEMASK_FORCE_SET)) { - mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_LOCAL_NED force not supported"); + mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_GLOBAL_INT force not supported\t"); + events::send(events::ID("mavlink_rcv_sp_target_gl_unsup_force"), events::Log::Error, + "SET_POSITION_TARGET_GLOBAL_INT: FORCE is not supported"); return; } @@ -2399,8 +2411,10 @@ MavlinkReceiver::handle_message_landing_target(mavlink_message_t *msg) } else if (landing_target.position_valid) { // We only support MAV_FRAME_LOCAL_NED. In this case, the frame was unsupported. - mavlink_log_critical(&_mavlink_log_pub, "landing target: coordinate frame %" PRIu8 " unsupported", + mavlink_log_critical(&_mavlink_log_pub, "landing target: coordinate frame %" PRIu8 " unsupported\t", landing_target.frame); + events::send(events::ID("mavlink_rcv_lnd_target_unsup_coord"), events::Log::Error, + "landing target: unsupported coordinate frame {1}", landing_target.frame); } else { irlock_report_s irlock_report{};