AP_Mount: correct compilation when GCS not available

This commit is contained in:
Peter Barker 2024-03-07 18:52:58 +11:00 committed by Peter Barker
parent eb3215cf12
commit 64d3897126
2 changed files with 8 additions and 8 deletions

View File

@ -313,14 +313,14 @@ void AP_Mount_Viewpro::process_packet()
const uint8_t patch_ver = atoi((const char*)fw_patch_str) & 0xFF; const uint8_t patch_ver = atoi((const char*)fw_patch_str) & 0xFF;
_firmware_version = (patch_ver << 16) | (minor_ver << 8) | major_ver; _firmware_version = (patch_ver << 16) | (minor_ver << 8) | major_ver;
_got_firmware_version = true; _got_firmware_version = true;
gcs().send_text(MAV_SEVERITY_INFO, "%s fw:%u.%u.%u", send_text_prefix, (unsigned)major_ver, (unsigned)minor_ver, (unsigned)patch_ver); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s fw:%u.%u.%u", send_text_prefix, (unsigned)major_ver, (unsigned)minor_ver, (unsigned)patch_ver);
break; break;
} }
case CommConfigCmd::QUERY_MODEL: case CommConfigCmd::QUERY_MODEL:
// gimbal model, length is 10 bytes // gimbal model, length is 10 bytes
strncpy((char *)_model_name, (const char *)&_msg_buff[_msg_buff_data_start+1], sizeof(_model_name)-1); strncpy((char *)_model_name, (const char *)&_msg_buff[_msg_buff_data_start+1], sizeof(_model_name)-1);
_got_model_name = true; _got_model_name = true;
gcs().send_text(MAV_SEVERITY_INFO, "%s %s", send_text_prefix, (const char*)_model_name); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s %s", send_text_prefix, (const char*)_model_name);
break; break;
default: default:
// unsupported control command // unsupported control command
@ -340,16 +340,16 @@ void AP_Mount_Viewpro::process_packet()
_last_tracking_status = tracking_status; _last_tracking_status = tracking_status;
switch (tracking_status) { switch (tracking_status) {
case TrackingStatus::STOPPED: case TrackingStatus::STOPPED:
gcs().send_text(MAV_SEVERITY_INFO, "%s tracking OFF", send_text_prefix); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s tracking OFF", send_text_prefix);
break; break;
case TrackingStatus::SEARCHING: case TrackingStatus::SEARCHING:
gcs().send_text(MAV_SEVERITY_INFO, "%s tracking searching", send_text_prefix); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s tracking searching", send_text_prefix);
break; break;
case TrackingStatus::TRACKING: case TrackingStatus::TRACKING:
gcs().send_text(MAV_SEVERITY_INFO, "%s tracking ON", send_text_prefix); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s tracking ON", send_text_prefix);
break; break;
case TrackingStatus::LOST: case TrackingStatus::LOST:
gcs().send_text(MAV_SEVERITY_INFO, "%s tracking Lost", send_text_prefix); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s tracking Lost", send_text_prefix);
break; break;
} }
} }
@ -368,7 +368,7 @@ void AP_Mount_Viewpro::process_packet()
const bool recording = (recording_status == RecordingStatus::RECORDING); const bool recording = (recording_status == RecordingStatus::RECORDING);
if (recording != _recording) { if (recording != _recording) {
_recording = recording; _recording = recording;
gcs().send_text(MAV_SEVERITY_INFO, "%s recording %s", send_text_prefix, _recording ? "ON" : "OFF"); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s recording %s", send_text_prefix, _recording ? "ON" : "OFF");
} }
// get optical zoom times // get optical zoom times

View File

@ -14,7 +14,7 @@
#endif #endif
#ifndef HAL_MOUNT_GREMSY_ENABLED #ifndef HAL_MOUNT_GREMSY_ENABLED
#define HAL_MOUNT_GREMSY_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024 #define HAL_MOUNT_GREMSY_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED && BOARD_FLASH_SIZE > 1024
#endif #endif
#ifndef HAL_MOUNT_SCRIPTING_ENABLED #ifndef HAL_MOUNT_SCRIPTING_ENABLED