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_RunCam.h
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
/*
16
implementation of RunCam camera protocols
17
18
With thanks to betaflight for a great reference
19
implementation. Several of the functions below are based on
20
betaflight equivalent functions
21
*/
22
#pragma once
23
24
#include "AP_Camera_config.h"
25
26
#include "AP_Camera_Backend.h"
27
28
#if AP_CAMERA_RUNCAM_ENABLED
29
30
#include <AP_Param/AP_Param.h>
31
#include <RC_Channel/RC_Channel.h>
32
#include <AP_Arming/AP_Arming.h>
33
#include <AP_OSD/AP_OSD.h>
34
35
#define RUNCAM_MAX_PACKET_SIZE 64
36
#define RUNCAM_DEFAULT_BUTTON_PRESS_DELAY 300
37
// 5-key OSD auto-repeats if pressed for too long
38
#define RUNCAM_5KEY_BUTTON_PRESS_DELAY 100
39
40
41
/// @class AP_RunCam
42
/// @brief Object managing a RunCam device
43
class AP_RunCam : public AP_Camera_Backend
44
{
45
public:
46
AP_RunCam(AP_Camera &frontend, AP_Camera_Params &params, uint8_t instance, uint8_t runcam_instance);
47
48
// do not allow copies
49
CLASS_NO_COPY(AP_RunCam);
50
51
// get singleton instance
52
static AP_RunCam *get_singleton() {
53
return _singleton;
54
}
55
56
enum class DeviceModel {
57
Disabled = 0,
58
SplitMicro = 1, // video support only
59
Split = 2, // camera and video support
60
Split4k = 3, // video support only + 5key OSD
61
Hybrid = 4, // video support + QR mode switch
62
Run24k = 5, // camera and video support like Split but recording command like Split4k
63
};
64
65
// operation of camera button simulation
66
enum class ControlOperation {
67
RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN = 0x00, // WiFi/Mode button
68
RCDEVICE_PROTOCOL_SIMULATE_POWER_BTN = 0x01,
69
RCDEVICE_PROTOCOL_CHANGE_MODE = 0x02,
70
RCDEVICE_PROTOCOL_CHANGE_START_RECORDING = 0x03,
71
RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING = 0x04,
72
UNKNOWN_CAMERA_OPERATION = 0xFF
73
};
74
75
// control for OSD menu entry
76
enum class ControlOption {
77
STICK_YAW_RIGHT = (1 << 0),
78
STICK_ROLL_RIGHT = (1 << 1),
79
THREE_POS_SWITCH = (1 << 2),
80
TWO_POS_SWITCH = (1 << 3),
81
VIDEO_RECORDING_AT_BOOT = (1 << 4)
82
};
83
84
85
// return true if healthy
86
bool healthy() const override;
87
88
// momentary switch to change camera between picture and video modes
89
void cam_mode_toggle() override;
90
91
// entry point to actually take a picture. returns true on success
92
bool trigger_pic() override;
93
94
// send camera information message to GCS
95
void send_camera_information(mavlink_channel_t chan) const override;
96
97
// send camera settings message to GCS
98
void send_camera_settings(mavlink_channel_t chan) const override;
99
100
// initialize the RunCam driver
101
void init() override;
102
// camera button simulation
103
bool simulate_camera_button(const ControlOperation operation, const uint32_t transition_timeout = RUNCAM_DEFAULT_BUTTON_PRESS_DELAY);
104
// start the video
105
void start_recording();
106
// stop the video
107
void stop_recording();
108
// start or stop video recording. returns true on success
109
// set start_recording = true to start record, false to stop recording
110
bool record_video(bool _start_recording) override {
111
if (_start_recording) {
112
start_recording();
113
} else {
114
stop_recording();
115
}
116
return true;
117
}
118
119
// enter the OSD menu
120
void enter_osd();
121
// exit the OSD menu
122
void exit_osd();
123
// OSD control determined by camera options
124
void osd_option();
125
// update - should be called at 50hz
126
void update() override;
127
// Check whether arming is allowed
128
bool pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const;
129
130
static const struct AP_Param::GroupInfo var_info[];
131
132
private:
133
// definitions prefixed with RCDEVICE taken from https://support.runcam.com/hc/en-us/articles/360014537794-RunCam-Device-Protocol
134
// possible supported features
135
// RunCam 2 4k and Split 3S micro reports 0x77 (POWER, WIFI, MODE, SETTING, DPORT, START)
136
// RunCam Split 2S reports 0x57 (POWER, WIFI, MODE, SETTING, START)
137
// RunCam Racer 3 reports 0x08 (OSD)
138
enum class Feature {
139
RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON = (1 << 0),
140
RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON = (1 << 1), // WiFi/Mode button
141
RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE = (1 << 2),
142
RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE = (1 << 3),
143
RCDEVICE_PROTOCOL_FEATURE_DEVICE_SETTINGS_ACCESS = (1 << 4),
144
RCDEVICE_PROTOCOL_FEATURE_DISPLAY_PORT = (1 << 5),
145
RCDEVICE_PROTOCOL_FEATURE_START_RECORDING = (1 << 6),
146
RCDEVICE_PROTOCOL_FEATURE_STOP_RECORDING = (1 << 7),
147
FEATURES_OVERRIDE = (1 << 14)
148
};
149
150
const uint16_t RCDEVICE_PROTOCOL_FEATURE_2_KEY_OSD =
151
uint16_t(Feature::RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE)
152
| uint16_t(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON)
153
| uint16_t(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON);
154
155
// camera control commands
156
enum class Command {
157
RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO = 0x00,
158
RCDEVICE_PROTOCOL_COMMAND_CAMERA_CONTROL = 0x01,
159
RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS = 0x02,
160
RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE = 0x03,
161
RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION = 0x04,
162
COMMAND_NONE
163
};
164
165
// operation of RC5KEY_CONNECTION
166
enum class ConnectionOperation {
167
RCDEVICE_PROTOCOL_5KEY_FUNCTION_OPEN = 0x01,
168
RCDEVICE_PROTOCOL_5KEY_FUNCTION_CLOSE = 0x02
169
};
170
171
// operation of 5 Key OSD cable simulation
172
enum class SimulationOperation {
173
SIMULATION_NONE = 0x00,
174
RCDEVICE_PROTOCOL_5KEY_SIMULATION_SET = 0x01,
175
RCDEVICE_PROTOCOL_5KEY_SIMULATION_LEFT = 0x02,
176
RCDEVICE_PROTOCOL_5KEY_SIMULATION_RIGHT = 0x03,
177
RCDEVICE_PROTOCOL_5KEY_SIMULATION_UP = 0x04,
178
RCDEVICE_PROTOCOL_5KEY_SIMULATION_DOWN = 0x05
179
};
180
181
// protocol versions, only version 1.0 is supported
182
enum class ProtocolVersion {
183
RCSPLIT_VERSION = 0x00, // unsupported firmware version <= 1.1.0
184
VERSION_1_0 = 0x01,
185
UNKNOWN
186
};
187
188
// status of command
189
enum class RequestStatus {
190
NONE,
191
PENDING,
192
SUCCESS,
193
INCORRECT_CRC,
194
TIMEOUT
195
};
196
197
enum class State {
198
INITIALIZING, // uart open
199
INITIALIZED, // features received
200
READY,
201
VIDEO_RECORDING,
202
ENTERING_MENU,
203
IN_MENU,
204
EXITING_MENU
205
};
206
207
enum class Event {
208
NONE,
209
ENTER_MENU,
210
EXIT_MENU,
211
IN_MENU_ENTER,
212
IN_MENU_RIGHT, // only used by the 5-key process
213
IN_MENU_UP,
214
IN_MENU_DOWN,
215
IN_MENU_EXIT,
216
BUTTON_RELEASE,
217
STOP_RECORDING,
218
START_RECORDING
219
};
220
221
enum class OSDOption {
222
NONE,
223
ENTER,
224
EXIT,
225
OPTION,
226
NO_OPTION
227
};
228
229
enum class VideoOption {
230
NOT_RECORDING = 0,
231
RECORDING = 1
232
};
233
234
enum class ButtonState {
235
NONE,
236
PRESSED,
237
RELEASED
238
};
239
240
static const uint8_t RUNCAM_NUM_SUB_MENUS = 5;
241
static const uint8_t RUNCAM_NUM_EXPECTED_RESPONSES = 4;
242
static const uint8_t RUNCAM_MAX_MENUS = 1;
243
static const uint8_t RUNCAM_MAX_MENU_LENGTH = 6;
244
static const uint8_t RUNCAM_MAX_DEVICE_TYPES = 5;
245
246
// supported features, usually probed from the device
247
AP_Int16 _features;
248
// delay time to make sure the camera is fully booted
249
AP_Int32 _boot_delay_ms;
250
// delay time to make sure a button press has been activated
251
AP_Int32 _button_delay_ms;
252
// delay time to make sure a mode change has been activated
253
AP_Int32 _mode_delay_ms;
254
// runcam type/firmware revision
255
AP_Int8 _cam_type;
256
// runcam control options
257
AP_Int8 _cam_control_option;
258
259
// video on/off
260
VideoOption _video_recording = VideoOption::NOT_RECORDING;
261
// detected protocol version
262
ProtocolVersion _protocol_version = ProtocolVersion::UNKNOWN;
263
// uart for the device
264
AP_HAL::UARTDriver *uart;
265
// camera state
266
State _state = State::INITIALIZING;
267
// time since last OSD cycle
268
uint32_t _last_osd_update_ms;
269
// start time of the current button press or boot sequence
270
uint32_t _transition_start_ms;
271
// timeout of the current button press or boot sequence
272
uint32_t _transition_timeout_ms;
273
// record last state transition to avoid spurious transitions
274
Event _last_rc_event;
275
State _last_state = State::INITIALIZING;
276
OSDOption _last_osd_option = OSDOption::NONE;
277
int8_t _last_in_menu;
278
VideoOption _last_video_recording = VideoOption::NOT_RECORDING;
279
// OSD state machine: button has been pressed
280
ButtonState _button_pressed = ButtonState::NONE;
281
// OSD state machine: waiting for a response
282
bool _waiting_device_response;
283
// OSD option from RC switches
284
OSDOption _osd_option;
285
// OSD state mechine: in the menu, value indicates depth
286
int8_t _in_menu;
287
// the starting value of _in_menu
288
int8_t _menu_enter_level;
289
// OSD state machine: current selection in the top menu
290
int8_t _top_menu_pos;
291
// OSD state machine: current selection in the sub menu
292
uint8_t _sub_menu_pos;
293
// lengths of the sub-menus
294
static uint8_t _sub_menu_lengths[RUNCAM_NUM_SUB_MENUS];
295
// shared inbound scratch space
296
uint8_t _recv_buf[RUNCAM_MAX_PACKET_SIZE]; // all the response contexts use same recv buffer
297
// the runcam instance
298
uint8_t _runcam_instance;
299
300
static const char* _models[RUNCAM_MAX_DEVICE_TYPES];
301
302
class Request;
303
304
FUNCTOR_TYPEDEF(parse_func_t, void, const Request&);
305
306
// class to represent a request
307
class Request
308
{
309
friend class AP_RunCam;
310
311
public:
312
Request(AP_RunCam *device, Command commandID, uint8_t param,
313
uint32_t timeout, uint16_t maxRetryTimes, parse_func_t parserFunc);
314
Request() { _command = Command::COMMAND_NONE; }
315
316
uint8_t *_recv_buf; // response data buffer
317
AP_RunCam *_device; // parent device
318
Command _command; // command for which a response is expected
319
uint8_t _param; // parameter data, the protocol can take more but we never use it
320
321
private:
322
uint8_t _recv_response_length; // length of the data received
323
uint8_t _expected_response_length; // total length of response data wanted
324
uint32_t _timeout_ms; // how long to wait before giving up
325
uint32_t _request_timestamp_ms; // when the request was sent, if it's zero keep waiting for the response
326
uint16_t _max_retry_times; // number of times to resend the request
327
parse_func_t _parser_func; // function to parse the response
328
RequestStatus _result; // whether we were successful or not
329
330
// get the length of the expected response
331
uint8_t get_expected_response_length(const Command command) const;
332
// calculate a crc
333
uint8_t get_crc() const;
334
// parse the response
335
void parse_response() {
336
if (_parser_func != nullptr) {
337
_parser_func(*this);
338
}
339
}
340
341
struct Length {
342
Command command;
343
uint8_t reponse_length;
344
};
345
346
static Length _expected_responses_length[RUNCAM_NUM_EXPECTED_RESPONSES];
347
} _pending_request;
348
349
// menu structure of the runcam device
350
struct Menu {
351
uint8_t _top_menu_length;
352
uint8_t _sub_menu_lengths[RUNCAM_MAX_MENU_LENGTH];
353
};
354
355
static Menu _menus[RUNCAM_MAX_DEVICE_TYPES];
356
357
// return the length of the top menu
358
uint8_t get_top_menu_length() const {
359
return _menus[_cam_type - 1]._top_menu_length;
360
}
361
362
// return the length of a particular sub-menu
363
uint8_t get_sub_menu_length(uint8_t submenu) const {
364
return _menus[_cam_type - 1]._sub_menu_lengths[submenu];
365
}
366
367
// disable the OSD display
368
void disable_osd() {
369
#if OSD_ENABLED
370
AP_OSD* osd = AP::osd();
371
if (osd != nullptr) {
372
osd->disable();
373
}
374
#endif
375
}
376
// enable the OSD display
377
void enable_osd() {
378
#if OSD_ENABLED
379
AP_OSD* osd = AP::osd();
380
if (osd != nullptr) {
381
osd->enable();
382
}
383
#endif
384
}
385
386
// OSD update loop
387
void update_osd();
388
// update the state machine when armed or flying
389
void update_state_machine_armed();
390
// update the state machine when disarmed
391
void update_state_machine_disarmed();
392
// handle the initialized state
393
void handle_initialized(Event ev);
394
// handle the ready state
395
void handle_ready(Event ev);
396
// handle the recording state
397
void handle_recording(Event ev);
398
// run the 2-key OSD simulation process
399
void handle_in_menu(Event ev);
400
// map rc input to an event
401
AP_RunCam::Event map_rc_input_to_event() const;
402
403
// run the 2-key OSD simulation process
404
void handle_2_key_simulation_process(Event ev);
405
// eexit the 2 key OSD menu
406
void exit_2_key_osd_menu();
407
408
// run the 5-key OSD simulation process
409
void handle_5_key_simulation_process(Event ev);
410
// handle a response
411
void handle_5_key_simulation_response(const Request& request);
412
// commands to start and stop recording
413
ControlOperation start_recording_command() const;
414
ControlOperation stop_recording_command() const;
415
// process a response from the serial port
416
void receive();
417
// empty the receive side of the serial port
418
void drain();
419
// start the uart with appropriate settings
420
void start_uart();
421
422
// get the RunCam device information
423
void get_device_info();
424
// 5 key osd cable simulation
425
SimulationOperation map_key_to_protocol_operation(const Event ev) const;
426
// send an event
427
void send_5_key_OSD_cable_simulation_event(const Event key, const uint32_t transition_timeout = RUNCAM_5KEY_BUTTON_PRESS_DELAY);
428
// enter the menu
429
void open_5_key_OSD_cable_connection(parse_func_t parseFunc);
430
// exit the menu
431
void close_5_key_OSD_cable_connection(parse_func_t parseFunc);
432
// press a button
433
void simulate_5_key_OSD_cable_button_press(const SimulationOperation operation, parse_func_t parseFunc);
434
// release a button
435
void simulate_5_key_OSD_cable_button_release(parse_func_t parseFunc);
436
// send a RunCam request and register a response to be processed
437
void send_request_and_waiting_response(Command commandID, uint8_t param, uint32_t timeout,
438
uint16_t maxRetryTimes, parse_func_t parseFunc);
439
// send a packet to the serial port
440
void send_packet(Command command, uint8_t param);
441
// handle a device info response
442
void parse_device_info(const Request& request);
443
// wait for the RunCam device to be fully ready
444
bool camera_ready() const;
445
// whether or not the requested feature is supported
446
bool has_feature(const Feature feature) const { return _features.get() & uint16_t(feature); }
447
// input mode
448
bool has_2_key_OSD() const {
449
return (_features.get() & RCDEVICE_PROTOCOL_FEATURE_2_KEY_OSD) == RCDEVICE_PROTOCOL_FEATURE_2_KEY_OSD;
450
}
451
bool has_5_key_OSD() const {
452
// RunCam Hybrid lies about supporting both 5-key and 2-key
453
return !has_2_key_OSD() && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE);
454
}
455
456
// whether or not we can arm
457
bool is_arming_prevented() const { return _in_menu > _menu_enter_level; }
458
// error handler for OSD simulation
459
void simulation_OSD_cable_failed(const Request& request);
460
// process pending request, retrying as necessary
461
bool request_pending(uint32_t now);
462
463
static AP_RunCam *_singleton;
464
};
465
466
namespace AP
467
{
468
AP_RunCam *runcam();
469
};
470
471
#endif // AP_CAMERA_RUNCAM_ENABLED
472
473