Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Global: Align mavlink message level with event message level #23562

Open
wants to merge 16 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
16 commits
Select commit Hold shift + click to select a range
359c2c9
mavlink: Align MAVLINK message level with EVENT message level
muramura Aug 16, 2024
a7635d2
camera_capture: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
07880d9
pps_capture: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
f2dd125
sagetech_mxs: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
d3fabb0
collision_prevention: Align MAVLINK message level with EVENT message …
muramura Aug 17, 2024
0e5fa12
airspeed_selector: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
2da21fa
commander: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
0b219e6
checks: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
92c0cab
ekf2: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
816868a
Orbit: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
0e78558
logger: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
306b22b
manual_control: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
07ab372
mavlink: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
cccbffe
mc_pos_control: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
b1ad551
navigator: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
80a3139
MissionFeasibility: Align MAVLINK message level with EVENT message level
muramura Aug 17, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/drivers/camera_capture/camera_capture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,7 @@ CameraCapture::publish_trigger()
if (_trigger_rate_failure.load()) {
mavlink_log_warning(&_mavlink_log_pub, "Hardware fault: Camera capture disabled\t");
events::send(events::ID("camera_capture_trigger_rate_exceeded"),
events::Log::Error, "Hardware fault: Camera capture disabled");
events::Log::Warning, "Hardware fault: Camera capture disabled");
_trigger_rate_failure.store(false);
}

Expand Down
2 changes: 1 addition & 1 deletion src/drivers/pps_capture/PPSCapture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ void PPSCapture::Run()
if (_pps_rate_failure.load()) {
mavlink_log_warning(&_mavlink_log_pub, "Hardware fault: GPS PPS disabled\t");
events::send(events::ID("pps_capture_pps_rate_exceeded"),
events::Log::Error, "Hardware fault: GPS PPS disabled");
events::Log::Warning, "Hardware fault: GPS PPS disabled");
_pps_rate_failure.store(false);
}
}
Expand Down
4 changes: 2 additions & 2 deletions src/drivers/transponder/sagetech_mxs/SagetechMXS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -554,12 +554,12 @@ void SagetechMXS::handle_ack(const sg_ack_t ack)
// System health
if (ack.failXpdr && !last.failXpdr) {
mavlink_log_info(&_mavlink_log_pub, "Transponder Failure\t");
events::send(events::ID("mxs_xpdr_fail"), events::Log::Critical, "Transponder Failure");
events::send(events::ID("mxs_xpdr_fail"), events::Log::Info, "Transponder Failure");
}

if (ack.failSystem && !last.failSystem) {
mavlink_log_info(&_mavlink_log_pub, "Transponder System Failure\t");
events::send(events::ID("mxs_system_fail"), events::Log::Critical, "Transponder System Failure");
events::send(events::ID("mxs_system_fail"), events::Log::Info, "Transponder System Failure");
}

last.failXpdr = ack.failXpdr;
Expand Down
2 changes: 1 addition & 1 deletion src/lib/collision_prevention/CollisionPrevention.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,7 +160,7 @@ CollisionPrevention::_addObstacleSensorData(const obstacle_distance_s &obstacle,
} else {
mavlink_log_critical(&_mavlink_log_pub, "Obstacle message received in unsupported frame %i\t",
obstacle.frame);
events::send<uint8_t>(events::ID("col_prev_unsup_frame"), events::Log::Error,
events::send<uint8_t>(events::ID("col_prev_unsup_frame"), events::Log::Critical,
"Obstacle message received in unsupported frame {1}", obstacle.frame);
}
}
Expand Down
2 changes: 1 addition & 1 deletion src/modules/airspeed_selector/airspeed_selector_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -662,7 +662,7 @@ void AirspeedModule::select_airspeed_and_publish()

} else if (_prev_airspeed_index == 0 && _valid_airspeed_index == -1) {
mavlink_log_info(&_mavlink_log_pub, "Airspeed estimation invalid\t");
events::send(events::ID("airspeed_selector_estimation_invalid"), events::Log::Error,
events::send(events::ID("airspeed_selector_estimation_invalid"), events::Log::Info,
"Airspeed estimation invalid");

} else if (_prev_airspeed_index == -1 && _valid_airspeed_index == 0) {
Expand Down
10 changes: 5 additions & 5 deletions src/modules/commander/Commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -837,7 +837,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
default:
main_ret = TRANSITION_DENIED;
mavlink_log_critical(&_mavlink_log_pub, "Unsupported auto mode\t");
events::send(events::ID("commander_unsupported_auto_mode"), events::Log::Error,
events::send(events::ID("commander_unsupported_auto_mode"), events::Log::Critical,
"Unsupported auto mode");
break;
}
Expand Down Expand Up @@ -917,7 +917,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
if (arming_action != vehicle_command_s::ARMING_ACTION_ARM
&& arming_action != vehicle_command_s::ARMING_ACTION_DISARM) {
mavlink_log_critical(&_mavlink_log_pub, "Unsupported ARM_DISARM param: %.3f\t", (double)cmd.param1);
events::send<float>(events::ID("commander_unsupported_arm_disarm_param"), events::Log::Error,
events::send<float>(events::ID("commander_unsupported_arm_disarm_param"), events::Log::Critical,
"Unsupported ARM_DISARM param: {1:.3}", cmd.param1);

} else {
Expand Down Expand Up @@ -2811,7 +2811,7 @@ void Commander::dataLinkCheck()
_vehicle_status.gcs_connection_lost_counter++;

mavlink_log_info(&_mavlink_log_pub, "Connection to ground station lost\t");
events::send(events::ID("commander_gcs_lost"), {events::Log::Warning, events::LogInternal::Info},
events::send(events::ID("commander_gcs_lost"), {events::Log::Info, events::LogInternal::Info},
"Connection to ground control station lost");

_status_changed = true;
Expand Down Expand Up @@ -2872,7 +2872,7 @@ void Commander::battery_status_check()

if (!isArmed() && (px4_shutdown_request(60_s) == 0)) {
mavlink_log_critical(&_mavlink_log_pub, "Dangerously low battery! Shutting system down in 60 seconds\t");
events::send(events::ID("commander_low_bat_shutdown"), {events::Log::Emergency, events::LogInternal::Warning},
events::send(events::ID("commander_low_bat_shutdown"), {events::Log::Critical, events::LogInternal::Warning},
"Dangerously low battery! Shutting system down");

while (1) { px4_usleep(1); }
Expand All @@ -2882,7 +2882,7 @@ void Commander::battery_status_check()
/* EVENT
* @description Cannot shut down, most likely the system does not support it.
*/
events::send(events::ID("commander_low_bat_shutdown_failed"), {events::Log::Emergency, events::LogInternal::Error},
events::send(events::ID("commander_low_bat_shutdown_failed"), {events::Log::Critical, events::LogInternal::Error},
"Dangerously low battery! System shut down failed");
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -679,7 +679,7 @@ void EstimatorChecks::lowPositionAccuracy(const Context &context, Report &report
* This check can be configured via <param>COM_POS_LOW_EPH</param> parameter.
* </profile>
*/
events::send(events::ID("check_estimator_low_position_accuracy"), {events::Log::Error, events::LogInternal::Info},
events::send(events::ID("check_estimator_low_position_accuracy"), {events::Log::Warning, events::LogInternal::Info},
"Local position estimate has low accuracy");

if (reporter.mavlink_log_pub()) {
Expand Down Expand Up @@ -751,7 +751,7 @@ void EstimatorChecks::setModeRequirementFlags(const Context &context, bool pre_f
* This warning is triggered when the position error estimate is 90% of (or only 10m below) <param>COM_POS_FS_EPH</param> parameter.
* </profile>
*/
events::send(events::ID("check_estimator_position_failure_imminent"), {events::Log::Error, events::LogInternal::Info},
events::send(events::ID("check_estimator_position_failure_imminent"), {events::Log::Critical, events::LogInternal::Info},
"Estimated position error is approaching the failsafe threshold");

if (reporter.mavlink_log_pub()) {
Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/calibration_routines.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -347,7 +347,7 @@ bool calibrate_cancel_check(orb_advert_t *mavlink_log_pub, const hrt_abstime &ca
} else {
command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
mavlink_log_critical(mavlink_log_pub, "command denied during calibration: %" PRIu32 "\t", cmd.command);
events::send<uint32_t>(events::ID("commander_cal_cmd_denied"), {events::Log::Error, events::LogInternal::Info},
events::send<uint32_t>(events::ID("commander_cal_cmd_denied"), {events::Log::Critical, events::LogInternal::Info},
"Command denied during calibration: {1}", cmd.command);
tune_negative(true);
ret = false;
Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/rc_calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ int do_trim_calibration(orb_advert_t *mavlink_log_pub)

if (!changed) {
mavlink_log_critical(mavlink_log_pub, "no inputs, aborting\t");
events::send(events::ID("commander_cal_no_inputs"), {events::Log::Error, events::LogInternal::Info},
events::send(events::ID("commander_cal_no_inputs"), {events::Log::Critical, events::LogInternal::Info},
"No inputs, aborting RC trim calibration");
return PX4_ERROR;
}
Expand Down
2 changes: 1 addition & 1 deletion src/modules/ekf2/EKF2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -852,7 +852,7 @@ void EKF2::VerifyParams()
/* EVENT
* @description <param>EKF2_MAG_TYPE</param> is set to {1:.0}.
*/
events::send<float>(events::ID("ekf2_mag_type_invalid"), events::Log::Warning,
events::send<float>(events::ID("ekf2_mag_type_invalid"), events::Log::Critical,
"EKF2_MAG_TYPE invalid, resetting to default", _param_ekf2_mag_type.get());

_param_ekf2_mag_type.set(0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ bool FlightTaskOrbit::applyCommandParameters(const vehicle_command_s &command, b

} else {
mavlink_log_critical(&_mavlink_log_pub, "Orbit radius limit exceeded\t");
events::send(events::ID("orbit_radius_exceeded"), events::Log::Alert, "Orbit radius limit exceeded");
events::send(events::ID("orbit_radius_exceeded"), events::Log::Critical, "Orbit radius limit exceeded");
success = false;
}

Expand Down
2 changes: 1 addition & 1 deletion src/modules/logger/util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -234,7 +234,7 @@ int check_free_space(const char *log_root_dir, int32_t max_log_dirs_to_keep, orb
* @description Either manually free up some space, or enable automatic log rotation
* via <param>SDLOG_DIRS_MAX</param>.
*/
events::send<uint32_t>(events::ID("logger_storage_full"), events::Log::Error,
events::send<uint32_t>(events::ID("logger_storage_full"), events::Log::Critical,
"Not logging, storage is almost full: {1} MiB", (uint32_t)(statfs_buf.f_bavail * statfs_buf.f_bsize / 1024U / 1024U));
return 1;
}
Expand Down
4 changes: 2 additions & 2 deletions src/modules/manual_control/ManualControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -316,7 +316,7 @@ void ManualControl::updateParams()
/* EVENT
* @description <param>MAN_ARM_GESTURE</param> is now set to disable arm/disarm stick gesture.
*/
events::send(events::ID("rc_update_arm_stick_gesture_disabled_with_switch"), {events::Log::Info, events::LogInternal::Disabled},
events::send(events::ID("rc_update_arm_stick_gesture_disabled_with_switch"), {events::Log::Critical, events::LogInternal::Disabled},
"Arm stick gesture disabled if arm switch in use");
}
}
Expand All @@ -338,7 +338,7 @@ void ManualControl::updateParams()
/* EVENT
* @description <param>MC_AIRMODE</param> is now set to roll/pitch airmode.
*/
events::send(events::ID("commander_airmode_requires_no_arm_gesture"), {events::Log::Error, events::LogInternal::Disabled},
events::send(events::ID("commander_airmode_requires_no_arm_gesture"), {events::Log::Critical, events::LogInternal::Disabled},
"Yaw Airmode requires disabling the stick arm gesture");
}
}
Expand Down
42 changes: 21 additions & 21 deletions src/modules/mavlink/mavlink_mission.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -351,7 +351,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t

default:
_mavlink.send_statustext_critical("Received unknown mission type, abort.\t");
events::send(events::ID("mavlink_mission_recv_unknown_mis_type"), events::Log::Error,
events::send(events::ID("mavlink_mission_recv_unknown_mis_type"), events::Log::Critical,
"Received unknown mission type, abort");
break;
}
Expand Down Expand Up @@ -395,7 +395,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t
/* EVENT
* @description Mission type: {1}
*/
events::send<uint8_t>(events::ID("mavlink_mission_storage_read_failure"), events::Log::Error,
events::send<uint8_t>(events::ID("mavlink_mission_storage_read_failure"), events::Log::Critical,
"Mission: Unable to read from storage", _mission_type);
}

Expand Down Expand Up @@ -467,7 +467,7 @@ MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint1

} else {
_mavlink.send_statustext_critical("ERROR: Waypoint index exceeds list capacity\t");
events::send<uint16_t>(events::ID("mavlink_mission_wp_index_exceeds_list"), events::Log::Error,
events::send<uint16_t>(events::ID("mavlink_mission_wp_index_exceeds_list"), events::Log::Critical,
"Waypoint index eceeds list capacity (maximum: {1})", current_max_item_count());

PX4_DEBUG("WPM: Send MISSION_REQUEST ERROR: seq %u exceeds list capacity", seq);
Expand Down Expand Up @@ -510,7 +510,7 @@ MavlinkMissionManager::send()

} else {
_mavlink.send_statustext_critical("ERROR: wp index out of bounds\t");
events::send<uint16_t, uint16_t>(events::ID("mavlink_mission_wp_index_out_of_bounds"), events::Log::Error,
events::send<uint16_t, uint16_t>(events::ID("mavlink_mission_wp_index_out_of_bounds"), events::Log::Critical,
"Waypoint index out of bounds (current {1} \\>= total {2})", mission_result.seq_current, mission_result.seq_total);
}
}
Expand Down Expand Up @@ -563,7 +563,7 @@ MavlinkMissionManager::send()
&& hrt_elapsed_time(&_time_last_recv) > MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT) {

_mavlink.send_statustext_critical("Operation timeout\t");
events::send(events::ID("mavlink_mission_op_timeout"), events::Log::Error,
events::send(events::ID("mavlink_mission_op_timeout"), events::Log::Critical,
"Operation timeout, aborting transfer");

PX4_DEBUG("WPM: Last operation (state=%d) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _state);
Expand Down Expand Up @@ -675,7 +675,7 @@ MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg)

} else {
_mavlink.send_statustext_critical("REJ. WP CMD: partner id mismatch\t");
events::send(events::ID("mavlink_mission_partner_id_mismatch"), events::Log::Error,
events::send(events::ID("mavlink_mission_partner_id_mismatch"), events::Log::Critical,
"Rejecting waypoint command, component or system ID mismatch");

PX4_DEBUG("WPM: MISSION_ACK ERR: ID mismatch");
Expand All @@ -700,15 +700,15 @@ MavlinkMissionManager::handle_mission_set_current(const mavlink_message_t *msg)
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\t");
events::send(events::ID("mavlink_mission_seq_out_of_bounds"), events::Log::Error,
events::send(events::ID("mavlink_mission_seq_out_of_bounds"), events::Log::Critical,
"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\t");
events::send(events::ID("mavlink_mission_state_busy"), events::Log::Error,
events::send(events::ID("mavlink_mission_state_busy"), events::Log::Critical,
"Mission manager currently busy, ignoring new waypoint index");
}
}
Expand Down Expand Up @@ -769,7 +769,7 @@ MavlinkMissionManager::handle_mission_request_list(const mavlink_message_t *msg)
PX4_DEBUG("WPM: MISSION_REQUEST_LIST ERROR: busy");

_mavlink.send_statustext_info("Mission download request ignored, already active\t");
events::send(events::ID("mavlink_mission_req_ignored"), events::Log::Warning,
events::send(events::ID("mavlink_mission_req_ignored"), events::Log::Info,
"Mission download request ignored, already active");
}
}
Expand Down Expand Up @@ -844,7 +844,7 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg)

send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
_mavlink.send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected\t");
events::send(events::ID("mavlink_mission_wp_unexpected"), events::Log::Error,
events::send(events::ID("mavlink_mission_wp_unexpected"), events::Log::Critical,
"Unexpected waypoint index, aborting transfer");
return;
}
Expand All @@ -861,7 +861,7 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg)

send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
_mavlink.send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected\t");
events::send(events::ID("mavlink_mission_wp_unexpected2"), events::Log::Error,
events::send(events::ID("mavlink_mission_wp_unexpected2"), events::Log::Critical,
"Unexpected waypoint index, aborting mission transfer");
}

Expand All @@ -875,13 +875,13 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg)
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: busy (state %d).", _state);

_mavlink.send_statustext_critical("WPM: REJ. CMD: Busy\t");
events::send(events::ID("mavlink_mission_mis_req_ignored_busy"), events::Log::Error,
events::send(events::ID("mavlink_mission_mis_req_ignored_busy"), events::Log::Critical,
"Ignoring mission request, currently busy");
}

} else {
_mavlink.send_statustext_critical("WPM: REJ. CMD: partner id mismatch\t");
events::send(events::ID("mavlink_mission_partner_id_mismatch2"), events::Log::Error,
events::send(events::ID("mavlink_mission_partner_id_mismatch2"), events::Log::Critical,
"Rejecting mission request command, component or system ID mismatch");

PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: rejected, partner ID mismatch");
Expand Down Expand Up @@ -1001,7 +1001,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg)
PX4_DEBUG("WPM: MISSION_COUNT ERROR: busy, already receiving seq %u", _transfer_seq);

_mavlink.send_statustext_critical("WPM: REJ. CMD: Busy\t");
events::send(events::ID("mavlink_mission_getlist_busy"), events::Log::Error,
events::send(events::ID("mavlink_mission_getlist_busy"), events::Log::Critical,
"Mission upload busy, already receiving waypoint");

send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
Expand All @@ -1012,7 +1012,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg)
PX4_DEBUG("WPM: MISSION_COUNT ERROR: busy, state %i", _state);

_mavlink.send_statustext_critical("WPM: IGN MISSION_COUNT: Busy\t");
events::send(events::ID("mavlink_mission_ignore_mis_count"), events::Log::Error,
events::send(events::ID("mavlink_mission_ignore_mis_count"), events::Log::Critical,
"Mission upload busy, ignoring MISSION_COUNT");
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
return;
Expand Down Expand Up @@ -1089,7 +1089,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)
PX4_DEBUG("WPM: MISSION_ITEM ERROR: no transfer");

_mavlink.send_statustext_critical("IGN MISSION_ITEM: No transfer\t");
events::send(events::ID("mavlink_mission_no_transfer"), events::Log::Error,
events::send(events::ID("mavlink_mission_no_transfer"), events::Log::Critical,
"Ignoring mission item, no transfer in progress");
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
}
Expand All @@ -1100,7 +1100,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)
PX4_DEBUG("WPM: MISSION_ITEM ERROR: busy, state %i", _state);

_mavlink.send_statustext_critical("IGN MISSION_ITEM: Busy\t");
events::send(events::ID("mavlink_mission_mis_item_busy"), events::Log::Error,
events::send(events::ID("mavlink_mission_mis_item_busy"), events::Log::Critical,
"Ignoring mission item, busy");
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
return;
Expand All @@ -1114,7 +1114,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)
PX4_DEBUG("WPM: MISSION_ITEM ERROR: seq %u invalid item", wp.seq);

_mavlink.send_statustext_critical("IGN MISSION_ITEM: Invalid item\t");
events::send(events::ID("mavlink_mission_mis_item_invalid"), events::Log::Error,
events::send(events::ID("mavlink_mission_mis_item_invalid"), events::Log::Critical,
"Ignoring mission item, invalid item");

send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, ret);
Expand Down Expand Up @@ -1209,7 +1209,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)

default:
_mavlink.send_statustext_critical("Received unknown mission type, abort.\t");
events::send(events::ID("mavlink_mission_unknown_mis_type"), events::Log::Error,
events::send(events::ID("mavlink_mission_unknown_mis_type"), events::Log::Critical,
"Received unknown mission type, abort");
break;
}
Expand All @@ -1221,7 +1221,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)

if (write_failed) {
_mavlink.send_statustext_critical("Unable to write on micro SD\t");
events::send(events::ID("mavlink_mission_storage_failure"), events::Log::Error,
events::send(events::ID("mavlink_mission_storage_failure"), events::Log::Critical,
"Mission: unable to write to storage");
}

Expand Down Expand Up @@ -1362,7 +1362,7 @@ MavlinkMissionManager::handle_mission_clear_all(const mavlink_message_t *msg)

} else {
_mavlink.send_statustext_critical("WPM: IGN CLEAR CMD: Busy\t");
events::send(events::ID("mavlink_mission_ignore_clear"), events::Log::Error,
events::send(events::ID("mavlink_mission_ignore_clear"), events::Log::Critical,
"Ignoring mission clear command, busy");

PX4_DEBUG("WPM: CLEAR_ALL IGNORED: busy");
Expand Down
Loading
Loading