From ffb2a32144a63c5b0bf4ddeb20d723d1ac04c117 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 7 Aug 2024 13:17:20 +1000 Subject: [PATCH] AP_Camera: use GCS_SEND_TEXT rather than gcs().send_text Co-authored-by: muramura --- libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp | 2 +- libraries/AP_Camera/AP_Camera_SoloGimbal.cpp | 18 +++++++++--------- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp index 25027cf3b8..a47816c70e 100644 --- a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp +++ b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp @@ -141,7 +141,7 @@ void AP_Camera_MAVLinkCamV2::handle_message(mavlink_channel_t chan, const mavlin const uint8_t fw_ver_build = (_cam_info.firmware_version & 0xFF000000) >> 24; // display camera info to user - gcs().send_text(MAV_SEVERITY_INFO, "Camera: %.32s %.32s fw:%u.%u.%u.%u", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Camera: %.32s %.32s fw:%u.%u.%u.%u", _cam_info.vendor_name, _cam_info.model_name, (unsigned)fw_ver_major, diff --git a/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp b/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp index 06ecf6ee3a..c2cb2d400a 100644 --- a/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp +++ b/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp @@ -12,7 +12,7 @@ bool AP_Camera_SoloGimbal::trigger_pic() { if (gopro_status != GOPRO_HEARTBEAT_STATUS_CONNECTED) { - gcs().send_text(MAV_SEVERITY_ERROR, "GoPro Not Available"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GoPro Not Available"); return false; } @@ -21,21 +21,21 @@ bool AP_Camera_SoloGimbal::trigger_pic() if (gopro_capture_mode == GOPRO_CAPTURE_MODE_PHOTO) { // Trigger shutter start to take a photo - gcs().send_text(MAV_SEVERITY_INFO, "GoPro Photo Trigger"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro Photo Trigger"); mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_start); } else if (gopro_capture_mode == GOPRO_CAPTURE_MODE_VIDEO) { if (gopro_is_recording) { // GoPro is recording, so stop recording - gcs().send_text(MAV_SEVERITY_INFO, "GoPro Recording Stop"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro Recording Stop"); mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_stop); } else { // GoPro is not recording, so start recording - gcs().send_text(MAV_SEVERITY_INFO, "GoPro Recording Start"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro Recording Start"); mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_start); } } else { - gcs().send_text(MAV_SEVERITY_ERROR, "GoPro Unsupported Capture Mode"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GoPro Unsupported Capture Mode"); return false; } @@ -52,7 +52,7 @@ void AP_Camera_SoloGimbal::cam_mode_toggle() uint8_t gopro_capture_mode_values[4] = { }; if (gopro_status != GOPRO_HEARTBEAT_STATUS_CONNECTED) { - gcs().send_text(MAV_SEVERITY_ERROR, "GoPro Not Available"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GoPro Not Available"); return; } @@ -60,12 +60,12 @@ void AP_Camera_SoloGimbal::cam_mode_toggle() case GOPRO_CAPTURE_MODE_VIDEO: if (gopro_is_recording) { // GoPro is recording, cannot change modes - gcs().send_text(MAV_SEVERITY_INFO, "GoPro recording, can't change modes"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro recording, can't change modes"); } else { // Change to camera mode gopro_capture_mode_values[0] = GOPRO_CAPTURE_MODE_PHOTO; mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_CAPTURE_MODE,gopro_capture_mode_values); - gcs().send_text(MAV_SEVERITY_INFO, "GoPro changing to mode photo"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro changing to mode photo"); } break; @@ -74,7 +74,7 @@ void AP_Camera_SoloGimbal::cam_mode_toggle() // Change to video mode gopro_capture_mode_values[0] = GOPRO_CAPTURE_MODE_VIDEO; mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_CAPTURE_MODE,gopro_capture_mode_values); - gcs().send_text(MAV_SEVERITY_INFO, "GoPro changing to mode video"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro changing to mode video"); break; } }