mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Camera: use GCS_SEND_TEXT rather than gcs().send_text
Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
parent
4565eed5ad
commit
ffb2a32144
@ -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;
|
const uint8_t fw_ver_build = (_cam_info.firmware_version & 0xFF000000) >> 24;
|
||||||
|
|
||||||
// display camera info to user
|
// 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.vendor_name,
|
||||||
_cam_info.model_name,
|
_cam_info.model_name,
|
||||||
(unsigned)fw_ver_major,
|
(unsigned)fw_ver_major,
|
||||||
|
@ -12,7 +12,7 @@
|
|||||||
bool AP_Camera_SoloGimbal::trigger_pic()
|
bool AP_Camera_SoloGimbal::trigger_pic()
|
||||||
{
|
{
|
||||||
if (gopro_status != GOPRO_HEARTBEAT_STATUS_CONNECTED) {
|
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;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -21,21 +21,21 @@ bool AP_Camera_SoloGimbal::trigger_pic()
|
|||||||
|
|
||||||
if (gopro_capture_mode == GOPRO_CAPTURE_MODE_PHOTO) {
|
if (gopro_capture_mode == GOPRO_CAPTURE_MODE_PHOTO) {
|
||||||
// Trigger shutter start to take a 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);
|
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) {
|
} else if (gopro_capture_mode == GOPRO_CAPTURE_MODE_VIDEO) {
|
||||||
if (gopro_is_recording) {
|
if (gopro_is_recording) {
|
||||||
// GoPro is recording, so stop 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);
|
mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_stop);
|
||||||
} else {
|
} else {
|
||||||
// GoPro is not recording, so start recording
|
// 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);
|
mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_start);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "GoPro Unsupported Capture Mode");
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GoPro Unsupported Capture Mode");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -52,7 +52,7 @@ void AP_Camera_SoloGimbal::cam_mode_toggle()
|
|||||||
uint8_t gopro_capture_mode_values[4] = { };
|
uint8_t gopro_capture_mode_values[4] = { };
|
||||||
|
|
||||||
if (gopro_status != GOPRO_HEARTBEAT_STATUS_CONNECTED) {
|
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;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -60,12 +60,12 @@ void AP_Camera_SoloGimbal::cam_mode_toggle()
|
|||||||
case GOPRO_CAPTURE_MODE_VIDEO:
|
case GOPRO_CAPTURE_MODE_VIDEO:
|
||||||
if (gopro_is_recording) {
|
if (gopro_is_recording) {
|
||||||
// GoPro is recording, cannot change modes
|
// 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 {
|
} else {
|
||||||
// Change to camera mode
|
// Change to camera mode
|
||||||
gopro_capture_mode_values[0] = GOPRO_CAPTURE_MODE_PHOTO;
|
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);
|
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;
|
break;
|
||||||
|
|
||||||
@ -74,7 +74,7 @@ void AP_Camera_SoloGimbal::cam_mode_toggle()
|
|||||||
// Change to video mode
|
// Change to video mode
|
||||||
gopro_capture_mode_values[0] = GOPRO_CAPTURE_MODE_VIDEO;
|
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);
|
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;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user