AP_BattMonitor: use GCS_SEND_TEXT rather than gcs().send_text

Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
Peter Barker 2024-08-07 13:17:20 +10:00 committed by Andrew Tridgell
parent ec5eb88217
commit d205e2e5cf
1 changed files with 1 additions and 1 deletions

View File

@ -1037,7 +1037,7 @@ void AP_BattMonitor::checkPoweringOff(void)
cmd_msg.command = MAV_CMD_POWER_OFF_INITIATED; cmd_msg.command = MAV_CMD_POWER_OFF_INITIATED;
cmd_msg.param1 = i+1; cmd_msg.param1 = i+1;
GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&cmd_msg, sizeof(cmd_msg)); GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&cmd_msg, sizeof(cmd_msg));
gcs().send_text(MAV_SEVERITY_WARNING, "Vehicle %d battery %d is powering off", mavlink_system.sysid, i+1); GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Vehicle %d battery %d is powering off", mavlink_system.sysid, i+1);
#endif #endif
// only send this once // only send this once