CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp
Views: 1798
1
#include "AP_Camera_SoloGimbal.h"
2
3
#if AP_CAMERA_SOLOGIMBAL_ENABLED
4
5
#include <GCS_MAVLink/GCS.h>
6
7
// Toggle the shutter on the GoPro
8
// This is so ArduPilot can toggle the shutter directly, either for mission/GCS commands, or when the
9
// Solo's gimbal is installed on a vehicle other than a Solo. The usual GoPro controls through the
10
// Solo app and Solo controller do not use this, as it is done offboard on the companion computer.
11
// entry point to actually take a picture. returns true on success
12
bool AP_Camera_SoloGimbal::trigger_pic()
13
{
14
if (gopro_status != GOPRO_HEARTBEAT_STATUS_CONNECTED) {
15
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GoPro Not Available");
16
return false;
17
}
18
19
const uint8_t gopro_shutter_start[4] = { 1, 0, 0, 0};
20
const uint8_t gopro_shutter_stop[4] = { 0, 0, 0, 0};
21
22
if (gopro_capture_mode == GOPRO_CAPTURE_MODE_PHOTO) {
23
// Trigger shutter start to take a photo
24
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro Photo Trigger");
25
mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_start);
26
27
} else if (gopro_capture_mode == GOPRO_CAPTURE_MODE_VIDEO) {
28
if (gopro_is_recording) {
29
// GoPro is recording, so stop recording
30
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro Recording Stop");
31
mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_stop);
32
} else {
33
// GoPro is not recording, so start recording
34
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro Recording Start");
35
mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_start);
36
}
37
} else {
38
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GoPro Unsupported Capture Mode");
39
return false;
40
}
41
42
return true;
43
}
44
45
// Cycle the GoPro capture mode
46
// This is so ArduPilot can cycle through the capture modes of the GoPro directly, probably with an RC Aux function.
47
// This is primarily for Solo's gimbal being installed on a vehicle other than a Solo. The usual GoPro controls
48
// through the Solo app and Solo controller do not use this, as it is done offboard on the companion computer.
49
// momentary switch to change camera between picture and video modes
50
void AP_Camera_SoloGimbal::cam_mode_toggle()
51
{
52
uint8_t gopro_capture_mode_values[4] = { };
53
54
if (gopro_status != GOPRO_HEARTBEAT_STATUS_CONNECTED) {
55
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GoPro Not Available");
56
return;
57
}
58
59
switch(gopro_capture_mode) {
60
case GOPRO_CAPTURE_MODE_VIDEO:
61
if (gopro_is_recording) {
62
// GoPro is recording, cannot change modes
63
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro recording, can't change modes");
64
} else {
65
// Change to camera mode
66
gopro_capture_mode_values[0] = GOPRO_CAPTURE_MODE_PHOTO;
67
mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_CAPTURE_MODE,gopro_capture_mode_values);
68
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro changing to mode photo");
69
}
70
break;
71
72
case GOPRO_CAPTURE_MODE_PHOTO:
73
default:
74
// Change to video mode
75
gopro_capture_mode_values[0] = GOPRO_CAPTURE_MODE_VIDEO;
76
mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_CAPTURE_MODE,gopro_capture_mode_values);
77
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro changing to mode video");
78
break;
79
}
80
}
81
82
// handle incoming heartbeat from the Solo gimbal GoPro
83
void AP_Camera_SoloGimbal::handle_message(mavlink_channel_t chan, const mavlink_message_t &msg)
84
{
85
mavlink_gopro_heartbeat_t report_msg;
86
mavlink_msg_gopro_heartbeat_decode(&msg, &report_msg);
87
gopro_is_recording = report_msg.flags & GOPRO_FLAG_RECORDING;
88
heartbeat_channel = chan;
89
90
switch((GOPRO_HEARTBEAT_STATUS)report_msg.status) {
91
case GOPRO_HEARTBEAT_STATUS_DISCONNECTED:
92
case GOPRO_HEARTBEAT_STATUS_INCOMPATIBLE:
93
case GOPRO_HEARTBEAT_STATUS_ERROR:
94
case GOPRO_HEARTBEAT_STATUS_CONNECTED:
95
gopro_status = (GOPRO_HEARTBEAT_STATUS)report_msg.status;
96
break;
97
case GOPRO_HEARTBEAT_STATUS_ENUM_END:
98
break;
99
}
100
101
switch((GOPRO_CAPTURE_MODE)report_msg.capture_mode){
102
case GOPRO_CAPTURE_MODE_VIDEO:
103
case GOPRO_CAPTURE_MODE_PHOTO:
104
case GOPRO_CAPTURE_MODE_BURST:
105
case GOPRO_CAPTURE_MODE_TIME_LAPSE:
106
case GOPRO_CAPTURE_MODE_MULTI_SHOT:
107
case GOPRO_CAPTURE_MODE_PLAYBACK:
108
case GOPRO_CAPTURE_MODE_SETUP:
109
case GOPRO_CAPTURE_MODE_UNKNOWN:
110
gopro_capture_mode = (GOPRO_CAPTURE_MODE)report_msg.capture_mode;
111
break;
112
case GOPRO_CAPTURE_MODE_ENUM_END:
113
break;
114
}
115
}
116
117
#endif // AP_CAMERA_SOLOGIMBAL_ENABLED
118
119