Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Camera/AP_RunCam.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15implementation of RunCam camera protocols1617With thanks to betaflight for a great reference18implementation. Several of the functions below are based on19betaflight equivalent functions20*/21#pragma once2223#include "AP_Camera_config.h"2425#include "AP_Camera_Backend.h"2627#if AP_CAMERA_RUNCAM_ENABLED2829#include <AP_Param/AP_Param.h>30#include <RC_Channel/RC_Channel.h>31#include <AP_Arming/AP_Arming.h>32#include <AP_OSD/AP_OSD.h>3334#define RUNCAM_MAX_PACKET_SIZE 6435#define RUNCAM_DEFAULT_BUTTON_PRESS_DELAY 30036// 5-key OSD auto-repeats if pressed for too long37#define RUNCAM_5KEY_BUTTON_PRESS_DELAY 100383940/// @class AP_RunCam41/// @brief Object managing a RunCam device42class AP_RunCam : public AP_Camera_Backend43{44public:45AP_RunCam(AP_Camera &frontend, AP_Camera_Params ¶ms, uint8_t instance, uint8_t runcam_instance);4647// do not allow copies48CLASS_NO_COPY(AP_RunCam);4950// get singleton instance51static AP_RunCam *get_singleton() {52return _singleton;53}5455enum class DeviceModel {56Disabled = 0,57SplitMicro = 1, // video support only58Split = 2, // camera and video support59Split4k = 3, // video support only + 5key OSD60Hybrid = 4, // video support + QR mode switch61Run24k = 5, // camera and video support like Split but recording command like Split4k62};6364// operation of camera button simulation65enum class ControlOperation {66RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN = 0x00, // WiFi/Mode button67RCDEVICE_PROTOCOL_SIMULATE_POWER_BTN = 0x01,68RCDEVICE_PROTOCOL_CHANGE_MODE = 0x02,69RCDEVICE_PROTOCOL_CHANGE_START_RECORDING = 0x03,70RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING = 0x04,71UNKNOWN_CAMERA_OPERATION = 0xFF72};7374// control for OSD menu entry75enum class ControlOption {76STICK_YAW_RIGHT = (1 << 0),77STICK_ROLL_RIGHT = (1 << 1),78THREE_POS_SWITCH = (1 << 2),79TWO_POS_SWITCH = (1 << 3),80VIDEO_RECORDING_AT_BOOT = (1 << 4)81};828384// return true if healthy85bool healthy() const override;8687// momentary switch to change camera between picture and video modes88void cam_mode_toggle() override;8990// entry point to actually take a picture. returns true on success91bool trigger_pic() override;9293// send camera information message to GCS94void send_camera_information(mavlink_channel_t chan) const override;9596// send camera settings message to GCS97void send_camera_settings(mavlink_channel_t chan) const override;9899// initialize the RunCam driver100void init() override;101// camera button simulation102bool simulate_camera_button(const ControlOperation operation, const uint32_t transition_timeout = RUNCAM_DEFAULT_BUTTON_PRESS_DELAY);103// start the video104void start_recording();105// stop the video106void stop_recording();107// start or stop video recording. returns true on success108// set start_recording = true to start record, false to stop recording109bool record_video(bool _start_recording) override {110if (_start_recording) {111start_recording();112} else {113stop_recording();114}115return true;116}117118// enter the OSD menu119void enter_osd();120// exit the OSD menu121void exit_osd();122// OSD control determined by camera options123void osd_option();124// update - should be called at 50hz125void update() override;126// Check whether arming is allowed127bool pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const;128129static const struct AP_Param::GroupInfo var_info[];130131private:132// definitions prefixed with RCDEVICE taken from https://support.runcam.com/hc/en-us/articles/360014537794-RunCam-Device-Protocol133// possible supported features134// RunCam 2 4k and Split 3S micro reports 0x77 (POWER, WIFI, MODE, SETTING, DPORT, START)135// RunCam Split 2S reports 0x57 (POWER, WIFI, MODE, SETTING, START)136// RunCam Racer 3 reports 0x08 (OSD)137enum class Feature {138RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON = (1 << 0),139RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON = (1 << 1), // WiFi/Mode button140RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE = (1 << 2),141RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE = (1 << 3),142RCDEVICE_PROTOCOL_FEATURE_DEVICE_SETTINGS_ACCESS = (1 << 4),143RCDEVICE_PROTOCOL_FEATURE_DISPLAY_PORT = (1 << 5),144RCDEVICE_PROTOCOL_FEATURE_START_RECORDING = (1 << 6),145RCDEVICE_PROTOCOL_FEATURE_STOP_RECORDING = (1 << 7),146FEATURES_OVERRIDE = (1 << 14)147};148149const uint16_t RCDEVICE_PROTOCOL_FEATURE_2_KEY_OSD =150uint16_t(Feature::RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE)151| uint16_t(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON)152| uint16_t(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON);153154// camera control commands155enum class Command {156RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO = 0x00,157RCDEVICE_PROTOCOL_COMMAND_CAMERA_CONTROL = 0x01,158RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS = 0x02,159RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE = 0x03,160RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION = 0x04,161COMMAND_NONE162};163164// operation of RC5KEY_CONNECTION165enum class ConnectionOperation {166RCDEVICE_PROTOCOL_5KEY_FUNCTION_OPEN = 0x01,167RCDEVICE_PROTOCOL_5KEY_FUNCTION_CLOSE = 0x02168};169170// operation of 5 Key OSD cable simulation171enum class SimulationOperation {172SIMULATION_NONE = 0x00,173RCDEVICE_PROTOCOL_5KEY_SIMULATION_SET = 0x01,174RCDEVICE_PROTOCOL_5KEY_SIMULATION_LEFT = 0x02,175RCDEVICE_PROTOCOL_5KEY_SIMULATION_RIGHT = 0x03,176RCDEVICE_PROTOCOL_5KEY_SIMULATION_UP = 0x04,177RCDEVICE_PROTOCOL_5KEY_SIMULATION_DOWN = 0x05178};179180// protocol versions, only version 1.0 is supported181enum class ProtocolVersion {182RCSPLIT_VERSION = 0x00, // unsupported firmware version <= 1.1.0183VERSION_1_0 = 0x01,184UNKNOWN185};186187// status of command188enum class RequestStatus {189NONE,190PENDING,191SUCCESS,192INCORRECT_CRC,193TIMEOUT194};195196enum class State {197INITIALIZING, // uart open198INITIALIZED, // features received199READY,200VIDEO_RECORDING,201ENTERING_MENU,202IN_MENU,203EXITING_MENU204};205206enum class Event {207NONE,208ENTER_MENU,209EXIT_MENU,210IN_MENU_ENTER,211IN_MENU_RIGHT, // only used by the 5-key process212IN_MENU_UP,213IN_MENU_DOWN,214IN_MENU_EXIT,215BUTTON_RELEASE,216STOP_RECORDING,217START_RECORDING218};219220enum class OSDOption {221NONE,222ENTER,223EXIT,224OPTION,225NO_OPTION226};227228enum class VideoOption {229NOT_RECORDING = 0,230RECORDING = 1231};232233enum class ButtonState {234NONE,235PRESSED,236RELEASED237};238239static const uint8_t RUNCAM_NUM_SUB_MENUS = 5;240static const uint8_t RUNCAM_NUM_EXPECTED_RESPONSES = 4;241static const uint8_t RUNCAM_MAX_MENUS = 1;242static const uint8_t RUNCAM_MAX_MENU_LENGTH = 6;243static const uint8_t RUNCAM_MAX_DEVICE_TYPES = 5;244245// supported features, usually probed from the device246AP_Int16 _features;247// delay time to make sure the camera is fully booted248AP_Int32 _boot_delay_ms;249// delay time to make sure a button press has been activated250AP_Int32 _button_delay_ms;251// delay time to make sure a mode change has been activated252AP_Int32 _mode_delay_ms;253// runcam type/firmware revision254AP_Int8 _cam_type;255// runcam control options256AP_Int8 _cam_control_option;257258// video on/off259VideoOption _video_recording = VideoOption::NOT_RECORDING;260// detected protocol version261ProtocolVersion _protocol_version = ProtocolVersion::UNKNOWN;262// uart for the device263AP_HAL::UARTDriver *uart;264// camera state265State _state = State::INITIALIZING;266// time since last OSD cycle267uint32_t _last_osd_update_ms;268// start time of the current button press or boot sequence269uint32_t _transition_start_ms;270// timeout of the current button press or boot sequence271uint32_t _transition_timeout_ms;272// record last state transition to avoid spurious transitions273Event _last_rc_event;274State _last_state = State::INITIALIZING;275OSDOption _last_osd_option = OSDOption::NONE;276int8_t _last_in_menu;277VideoOption _last_video_recording = VideoOption::NOT_RECORDING;278// OSD state machine: button has been pressed279ButtonState _button_pressed = ButtonState::NONE;280// OSD state machine: waiting for a response281bool _waiting_device_response;282// OSD option from RC switches283OSDOption _osd_option;284// OSD state mechine: in the menu, value indicates depth285int8_t _in_menu;286// the starting value of _in_menu287int8_t _menu_enter_level;288// OSD state machine: current selection in the top menu289int8_t _top_menu_pos;290// OSD state machine: current selection in the sub menu291uint8_t _sub_menu_pos;292// lengths of the sub-menus293static uint8_t _sub_menu_lengths[RUNCAM_NUM_SUB_MENUS];294// shared inbound scratch space295uint8_t _recv_buf[RUNCAM_MAX_PACKET_SIZE]; // all the response contexts use same recv buffer296// the runcam instance297uint8_t _runcam_instance;298299static const char* _models[RUNCAM_MAX_DEVICE_TYPES];300301class Request;302303FUNCTOR_TYPEDEF(parse_func_t, void, const Request&);304305// class to represent a request306class Request307{308friend class AP_RunCam;309310public:311Request(AP_RunCam *device, Command commandID, uint8_t param,312uint32_t timeout, uint16_t maxRetryTimes, parse_func_t parserFunc);313Request() { _command = Command::COMMAND_NONE; }314315uint8_t *_recv_buf; // response data buffer316AP_RunCam *_device; // parent device317Command _command; // command for which a response is expected318uint8_t _param; // parameter data, the protocol can take more but we never use it319320private:321uint8_t _recv_response_length; // length of the data received322uint8_t _expected_response_length; // total length of response data wanted323uint32_t _timeout_ms; // how long to wait before giving up324uint32_t _request_timestamp_ms; // when the request was sent, if it's zero keep waiting for the response325uint16_t _max_retry_times; // number of times to resend the request326parse_func_t _parser_func; // function to parse the response327RequestStatus _result; // whether we were successful or not328329// get the length of the expected response330uint8_t get_expected_response_length(const Command command) const;331// calculate a crc332uint8_t get_crc() const;333// parse the response334void parse_response() {335if (_parser_func != nullptr) {336_parser_func(*this);337}338}339340struct Length {341Command command;342uint8_t reponse_length;343};344345static Length _expected_responses_length[RUNCAM_NUM_EXPECTED_RESPONSES];346} _pending_request;347348// menu structure of the runcam device349struct Menu {350uint8_t _top_menu_length;351uint8_t _sub_menu_lengths[RUNCAM_MAX_MENU_LENGTH];352};353354static Menu _menus[RUNCAM_MAX_DEVICE_TYPES];355356// return the length of the top menu357uint8_t get_top_menu_length() const {358return _menus[_cam_type - 1]._top_menu_length;359}360361// return the length of a particular sub-menu362uint8_t get_sub_menu_length(uint8_t submenu) const {363return _menus[_cam_type - 1]._sub_menu_lengths[submenu];364}365366// disable the OSD display367void disable_osd() {368#if OSD_ENABLED369AP_OSD* osd = AP::osd();370if (osd != nullptr) {371osd->disable();372}373#endif374}375// enable the OSD display376void enable_osd() {377#if OSD_ENABLED378AP_OSD* osd = AP::osd();379if (osd != nullptr) {380osd->enable();381}382#endif383}384385// OSD update loop386void update_osd();387// update the state machine when armed or flying388void update_state_machine_armed();389// update the state machine when disarmed390void update_state_machine_disarmed();391// handle the initialized state392void handle_initialized(Event ev);393// handle the ready state394void handle_ready(Event ev);395// handle the recording state396void handle_recording(Event ev);397// run the 2-key OSD simulation process398void handle_in_menu(Event ev);399// map rc input to an event400AP_RunCam::Event map_rc_input_to_event() const;401402// run the 2-key OSD simulation process403void handle_2_key_simulation_process(Event ev);404// eexit the 2 key OSD menu405void exit_2_key_osd_menu();406407// run the 5-key OSD simulation process408void handle_5_key_simulation_process(Event ev);409// handle a response410void handle_5_key_simulation_response(const Request& request);411// commands to start and stop recording412ControlOperation start_recording_command() const;413ControlOperation stop_recording_command() const;414// process a response from the serial port415void receive();416// empty the receive side of the serial port417void drain();418// start the uart with appropriate settings419void start_uart();420421// get the RunCam device information422void get_device_info();423// 5 key osd cable simulation424SimulationOperation map_key_to_protocol_operation(const Event ev) const;425// send an event426void send_5_key_OSD_cable_simulation_event(const Event key, const uint32_t transition_timeout = RUNCAM_5KEY_BUTTON_PRESS_DELAY);427// enter the menu428void open_5_key_OSD_cable_connection(parse_func_t parseFunc);429// exit the menu430void close_5_key_OSD_cable_connection(parse_func_t parseFunc);431// press a button432void simulate_5_key_OSD_cable_button_press(const SimulationOperation operation, parse_func_t parseFunc);433// release a button434void simulate_5_key_OSD_cable_button_release(parse_func_t parseFunc);435// send a RunCam request and register a response to be processed436void send_request_and_waiting_response(Command commandID, uint8_t param, uint32_t timeout,437uint16_t maxRetryTimes, parse_func_t parseFunc);438// send a packet to the serial port439void send_packet(Command command, uint8_t param);440// handle a device info response441void parse_device_info(const Request& request);442// wait for the RunCam device to be fully ready443bool camera_ready() const;444// whether or not the requested feature is supported445bool has_feature(const Feature feature) const { return _features.get() & uint16_t(feature); }446// input mode447bool has_2_key_OSD() const {448return (_features.get() & RCDEVICE_PROTOCOL_FEATURE_2_KEY_OSD) == RCDEVICE_PROTOCOL_FEATURE_2_KEY_OSD;449}450bool has_5_key_OSD() const {451// RunCam Hybrid lies about supporting both 5-key and 2-key452return !has_2_key_OSD() && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE);453}454455// whether or not we can arm456bool is_arming_prevented() const { return _in_menu > _menu_enter_level; }457// error handler for OSD simulation458void simulation_OSD_cable_failed(const Request& request);459// process pending request, retrying as necessary460bool request_pending(uint32_t now);461462static AP_RunCam *_singleton;463};464465namespace AP466{467AP_RunCam *runcam();468};469470#endif // AP_CAMERA_RUNCAM_ENABLED471472473