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.cpp
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 functions2021RunCam protocol specification can be found at https://support.runcam.com/hc/en-us/articles/360014537794-RunCam-Device-Protocol22*/23#include "AP_RunCam.h"2425#if AP_CAMERA_RUNCAM_ENABLED2627#include <AP_Math/AP_Math.h>28#include <AP_Math/crc.h>29#include <GCS_MAVLink/GCS.h>30#include <AP_Logger/AP_Logger.h>31#include <AP_SerialManager/AP_SerialManager.h>3233const AP_Param::GroupInfo AP_RunCam::var_info[] = {34// @Param: TYPE35// @DisplayName: RunCam device type36// @Description: RunCam device type used to determine OSD menu structure and shutter options.37// @Values: 0:Disabled, 1:RunCam Split Micro/RunCam with UART, 2:RunCam Split, 3:RunCam Split4 4k, 4:RunCam Hybrid/RunCam Thumb Pro, 5:Runcam 2 4k38AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceModel::SplitMicro), AP_PARAM_FLAG_ENABLE),3940// @Param: FEATURES41// @DisplayName: RunCam features available42// @Description: The available features of the attached RunCam device. If 0 then the RunCam device will be queried for the features it supports, otherwise this setting is used.43// @User: Advanced44// @Bitmask: 0:Power Button,1:WiFi Button,2:Change Mode,3:5-Key OSD,4:Settings Access,5:DisplayPort,6:Start Recording,7:Stop Recording45AP_GROUPINFO("FEATURES", 2, AP_RunCam, _features, 0),4647// @Param: BT_DELAY48// @DisplayName: RunCam boot delay before allowing updates49// @Description: Time it takes for the RunCam to become fully ready in ms. If this is too short then commands can get out of sync.50// @User: Advanced51AP_GROUPINFO("BT_DELAY", 3, AP_RunCam, _boot_delay_ms, 7000),5253// @Param: BTN_DELAY54// @DisplayName: RunCam button delay before allowing further button presses55// @Description: Time it takes for the a RunCam button press to be actived in ms. If this is too short then commands can get out of sync.56// @User: Advanced57AP_GROUPINFO("BTN_DELY", 4, AP_RunCam, _button_delay_ms, RUNCAM_DEFAULT_BUTTON_PRESS_DELAY),5859// @Param: MDE_DELAY60// @DisplayName: RunCam mode delay before allowing further button presses61// @Description: Time it takes for the a RunCam mode button press to be actived in ms. If a mode change first requires a video recording change then double this value is used. If this is too short then commands can get out of sync.62// @User: Advanced63AP_GROUPINFO("MDE_DELY", 5, AP_RunCam, _mode_delay_ms, 800),6465// @Param: CONTROL66// @DisplayName: RunCam control option67// @Description: Specifies the allowed actions required to enter the OSD menu and other option like autorecording68// @Bitmask: 0:Stick yaw right,1:Stick roll right,2:3-position switch,3:2-position switch,4:Autorecording enabled69// @User: Advanced70AP_GROUPINFO("CONTROL", 6, AP_RunCam, _cam_control_option, uint8_t(ControlOption::STICK_ROLL_RIGHT) | uint8_t(ControlOption::TWO_POS_SWITCH)),7172AP_GROUPEND73};7475#define RUNCAM_DEBUG 07677#if RUNCAM_DEBUG78static const char* event_names[11] = {79"NONE", "ENTER_MENU", "EXIT_MENU",80"IN_MENU_ENTER", "IN_MENU_RIGHT", "IN_MENU_UP", "IN_MENU_DOWN", "IN_MENU_EXIT",81"BUTTON_RELEASE", "STOP_RECORDING", "START_RECORDING"82};83static const char* state_names[7] = {84"INITIALIZING", "INITIALIZED", "READY", "VIDEO_RECORDING", "ENTERING_MENU", "IN_MENU", "EXITING_MENU"85};86#define debug(fmt, args ...) do { hal.console->printf("RunCam[%s]: " fmt, state_names[int(_state)], ## args); } while (0)87#else88#define debug(fmt, args ...)89#endif9091extern const AP_HAL::HAL& hal;9293// singleton instance94AP_RunCam *AP_RunCam::_singleton;9596AP_RunCam::Request::Length AP_RunCam::Request::_expected_responses_length[RUNCAM_NUM_EXPECTED_RESPONSES] = {97{ Command::RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO, 5 },98{ Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS, 2 },99{ Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE, 2 },100{ Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION, 3 },101};102103// the protocol for Runcam Device definition104static const uint8_t RUNCAM_HEADER = 0xCC;105static const uint8_t RUNCAM_OSD_MENU_DEPTH = 2;106static const uint32_t RUNCAM_INIT_INTERVAL_MS = 1000;107static const uint32_t RUNCAM_OSD_UPDATE_INTERVAL_MS = 100; // 10Hz108109// menu structures of runcam devices110AP_RunCam::Menu AP_RunCam::_menus[RUNCAM_MAX_DEVICE_TYPES] = {111// these are correct for the runcam split micro v2.4.4, others may vary112// Video, Image, TV-OUT, Micro SD Card, General113{ 6, { 5, 8, 3, 3, 7 }}, // SplitMicro114{ 0, { 0 }}, // Split115{ 6, { 4, 10, 3, 3, 7 }}, // Split4 4K116{ 1, { 0 }}, // Hybrid, simple mode switch117{ 6, { 3, 10, 2, 2, 8 }}, // Runcam 2 4K118};119120const char* AP_RunCam::_models[RUNCAM_MAX_DEVICE_TYPES] = {121"SplitMicro",122"Split",123"Split4k",124"Hybrid",125"Run24k"126};127128AP_RunCam::AP_RunCam(AP_Camera &frontend, AP_Camera_Params ¶ms, uint8_t instance, uint8_t runcam_instance)129: AP_Camera_Backend(frontend, params, instance), _runcam_instance(runcam_instance)130{131AP_Param::setup_object_defaults(this, var_info);132if (_singleton != nullptr && _singleton->_instance == instance) {133AP_HAL::panic("AP_RunCam instance must be a singleton %u", instance);134}135if (_singleton == nullptr) {136_singleton = this;137}138_cam_type.set(constrain_int16(_cam_type, 0, RUNCAM_MAX_DEVICE_TYPES));139_video_recording = VideoOption(_cam_control_option & uint8_t(ControlOption::VIDEO_RECORDING_AT_BOOT));140}141142// init the runcam device by finding a serial device configured for the RunCam protocol143void AP_RunCam::init()144{145AP_SerialManager *serial_manager = AP_SerialManager::get_singleton();146if (serial_manager) {147uart = serial_manager->find_serial(AP_SerialManager::SerialProtocol_RunCam, _runcam_instance);148}149if (uart != nullptr) {150/*151if the user has setup a serial port as a runcam then default152type to the split micro (Andy's development platform!). This makes setup a bit easier for most153users while still enabling parameters to be hidden for users154without a RunCam155*/156_cam_type.set_default(int8_t(DeviceModel::SplitMicro));157AP_Param::invalidate_count();158}159if (_cam_type.get() == int8_t(DeviceModel::Disabled)) {160uart = nullptr;161return;162}163164if (uart == nullptr) {165return;166}167168// Split and Runcam 2 4k requires two mode presses to get into the menu169if (_cam_type.get() == int8_t(DeviceModel::Split) || _cam_type.get() == int8_t(DeviceModel::Run24k)) {170_menu_enter_level = -1;171_in_menu = -1;172}173174start_uart();175176// first transition is from initialized to ready177_transition_start_ms = AP_HAL::millis();178_transition_timeout_ms = _boot_delay_ms;179180get_device_info();181}182183// simulate pressing the camera button184bool AP_RunCam::simulate_camera_button(const ControlOperation operation, const uint32_t transition_timeout)185{186if (!uart || _protocol_version != ProtocolVersion::VERSION_1_0) {187return false;188}189190_transition_timeout_ms = transition_timeout;191debug("press button %d, timeout=%dms\n", int(operation), int(transition_timeout));192send_packet(Command::RCDEVICE_PROTOCOL_COMMAND_CAMERA_CONTROL, uint8_t(operation));193194return true;195}196197// start the video198void AP_RunCam::start_recording() {199debug("start recording(%d)\n", int(_state));200_video_recording = VideoOption::RECORDING;201_osd_option = OSDOption::NO_OPTION;202}203204// stop the video205void AP_RunCam::stop_recording() {206debug("stop recording(%d)\n", int(_state));207_video_recording = VideoOption::NOT_RECORDING;208_osd_option = OSDOption::NO_OPTION;209}210211// enter the OSD menu212void AP_RunCam::enter_osd()213{214debug("enter osd(%d)\n", int(_state));215_osd_option = OSDOption::ENTER;216}217218// exit the OSD menu219void AP_RunCam::exit_osd()220{221debug("exit osd(%d)\n", int(_state));222_osd_option = OSDOption::EXIT;223}224225// OSD control determined by camera options226void AP_RunCam::osd_option() {227debug("osd option\n");228_osd_option = OSDOption::OPTION;229}230231// input update loop232void AP_RunCam::update()233{234if (uart == nullptr || _cam_type.get() == int8_t(DeviceModel::Disabled)) {235return;236}237238// process any pending packets239receive();240241uint32_t now = AP_HAL::millis();242if ((now - _last_osd_update_ms) > RUNCAM_OSD_UPDATE_INTERVAL_MS) {243update_osd();244_last_osd_update_ms = now;245}246}247248// pre_arm_check - returns true if all pre-takeoff checks have completed successfully249bool AP_RunCam::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const250{251// if not enabled return true252if (!uart) {253return true;254}255256// currently in the OSD menu, do not allow arming257if (is_arming_prevented()) {258hal.util->snprintf(failure_msg, failure_msg_len, "In OSD menu");259return false;260}261262if (!camera_ready()) {263hal.util->snprintf(failure_msg, failure_msg_len, "Camera not ready");264return false;265}266267// if we got this far everything must be ok268return true;269270}271272// OSD update loop273void AP_RunCam::update_osd()274{275bool use_armed_state_machine = hal.util->get_soft_armed();276#if OSD_ENABLED277// prevent runcam stick gestures interfering with osd stick gestures278if (!use_armed_state_machine) {279const AP_OSD* osd = AP::osd();280if (osd != nullptr) {281use_armed_state_machine = !osd->is_readonly_screen();282}283}284#endif285// run a reduced state simulation process when armed286if (use_armed_state_machine) {287update_state_machine_armed();288return;289}290291update_state_machine_disarmed();292}293294// update the state machine when armed or flying295void AP_RunCam::update_state_machine_armed()296{297const uint32_t now = AP_HAL::millis();298if ((now - _transition_start_ms) < _transition_timeout_ms) {299return;300}301302_transition_start_ms = now;303_transition_timeout_ms = 0;304305switch (_state) {306case State::READY:307handle_ready(_video_recording == VideoOption::RECORDING && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_START_RECORDING) ? Event::START_RECORDING : Event::NONE);308break;309case State::VIDEO_RECORDING:310handle_recording(_video_recording == VideoOption::NOT_RECORDING && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_START_RECORDING) ? Event::STOP_RECORDING : Event::NONE);311break;312case State::INITIALIZING:313case State::INITIALIZED:314case State::ENTERING_MENU:315case State::IN_MENU:316case State::EXITING_MENU:317break;318}319}320321// update the state machine when disarmed322void AP_RunCam::update_state_machine_disarmed()323{324const uint32_t now = AP_HAL::millis();325if (_waiting_device_response || (now - _transition_start_ms) < _transition_timeout_ms) {326_last_rc_event = Event::NONE;327return;328}329330_transition_start_ms = now;331_transition_timeout_ms = 0;332333const Event ev = map_rc_input_to_event();334// only take action on transitions335if (ev == _last_rc_event && _state == _last_state && _osd_option == _last_osd_option336&& _last_in_menu == _in_menu && _last_video_recording == _video_recording) {337return;338}339340debug("update_state_machine_disarmed(%s)\n", event_names[int(ev)]);341342_last_rc_event = ev;343_last_state = _state;344_last_osd_option = _osd_option;345_last_in_menu = _in_menu;346_last_video_recording = _video_recording;347348switch (_state) {349case State::INITIALIZING:350break;351case State::INITIALIZED:352handle_initialized(ev);353break;354case State::READY:355handle_ready(ev);356break;357case State::VIDEO_RECORDING:358handle_recording(ev);359break;360case State::ENTERING_MENU:361handle_in_menu(Event::ENTER_MENU);362break;363case State::IN_MENU:364handle_in_menu(ev);365break;366case State::EXITING_MENU:367handle_in_menu(Event::EXIT_MENU);368break;369}370}371372// handle the initialized state373void AP_RunCam::handle_initialized(Event ev)374{375// the camera should be configured to start with recording mode off by default376// a recording change needs significantly extra time to process377if (_video_recording == VideoOption::RECORDING && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_START_RECORDING)) {378if (!(_cam_control_option & uint8_t(ControlOption::VIDEO_RECORDING_AT_BOOT))) {379simulate_camera_button(start_recording_command(), _mode_delay_ms * 2);380}381_state = State::VIDEO_RECORDING;382} else if (_video_recording == VideoOption::NOT_RECORDING && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_START_RECORDING)) {383if (_cam_control_option & uint8_t(ControlOption::VIDEO_RECORDING_AT_BOOT)) {384simulate_camera_button(stop_recording_command(), _mode_delay_ms * 2);385}386_state = State::READY;387} else {388_state = State::READY;389}390debug("device fully booted after %ums\n", unsigned(AP_HAL::millis()));391}392393// handle the ready state394void AP_RunCam::handle_ready(Event ev)395{396switch (ev) {397case Event::ENTER_MENU:398case Event::IN_MENU_ENTER:399case Event::IN_MENU_RIGHT:400if (ev == Event::ENTER_MENU || _cam_control_option & uint8_t(ControlOption::STICK_ROLL_RIGHT)) {401_top_menu_pos = -1;402_sub_menu_pos = 0;403_state = State::ENTERING_MENU;404}405break;406case Event::START_RECORDING:407simulate_camera_button(start_recording_command(), _mode_delay_ms);408_state = State::VIDEO_RECORDING;409break;410case Event::NONE:411case Event::EXIT_MENU:412case Event::IN_MENU_UP:413case Event::IN_MENU_DOWN:414case Event::IN_MENU_EXIT:415case Event::BUTTON_RELEASE:416case Event::STOP_RECORDING:417break;418}419}420421// handle the recording state422void AP_RunCam::handle_recording(Event ev)423{424switch (ev) {425case Event::ENTER_MENU:426case Event::IN_MENU_ENTER:427case Event::IN_MENU_RIGHT:428if (ev == Event::ENTER_MENU || _cam_control_option & uint8_t(ControlOption::STICK_ROLL_RIGHT)) {429simulate_camera_button(stop_recording_command(), _mode_delay_ms);430_top_menu_pos = -1;431_sub_menu_pos = 0;432_state = State::ENTERING_MENU;433}434break;435case Event::STOP_RECORDING:436simulate_camera_button(stop_recording_command(), _mode_delay_ms);437_state = State::READY;438break;439case Event::NONE:440case Event::EXIT_MENU:441case Event::IN_MENU_UP:442case Event::IN_MENU_DOWN:443case Event::IN_MENU_EXIT:444case Event::BUTTON_RELEASE:445case Event::START_RECORDING:446break;447}448}449450// handle the in_menu state451void AP_RunCam::handle_in_menu(Event ev)452{453if (has_5_key_OSD()) {454handle_5_key_simulation_process(ev);455} else if (has_2_key_OSD()) {456// otherwise the simpler 2 key OSD simulation, requires firmware 2.4.4 on the split micro457handle_2_key_simulation_process(ev);458}459}460461// map rc input to an event462AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const463{464const RC_Channel::AuxSwitchPos throttle = rc().get_throttle_channel().get_stick_gesture_pos();465const RC_Channel::AuxSwitchPos yaw = rc().get_yaw_channel().get_stick_gesture_pos();466const RC_Channel::AuxSwitchPos roll = rc().get_roll_channel().get_stick_gesture_pos();467const RC_Channel::AuxSwitchPos pitch = rc().get_pitch_channel().get_stick_gesture_pos();468469Event result = Event::NONE;470471if (_button_pressed != ButtonState::NONE) {472if (_button_pressed == ButtonState::PRESSED && yaw == RC_Channel::AuxSwitchPos::MIDDLE && pitch == RC_Channel::AuxSwitchPos::MIDDLE && roll == RC_Channel::AuxSwitchPos::MIDDLE) {473result = Event::BUTTON_RELEASE;474} else {475result = Event::NONE; // still waiting to be released476}477} else if (throttle == RC_Channel::AuxSwitchPos::MIDDLE && yaw == RC_Channel::AuxSwitchPos::LOW478&& pitch == RC_Channel::AuxSwitchPos::MIDDLE && roll == RC_Channel::AuxSwitchPos::MIDDLE479// don't allow an action close to arming unless the user had configured it or arming is not possible480// but don't prevent the 5-Key control actually working481&& (_cam_control_option & uint8_t(ControlOption::STICK_YAW_RIGHT) || is_arming_prevented())) {482result = Event::EXIT_MENU;483} else if (throttle == RC_Channel::AuxSwitchPos::MIDDLE && yaw == RC_Channel::AuxSwitchPos::HIGH484&& pitch == RC_Channel::AuxSwitchPos::MIDDLE && roll == RC_Channel::AuxSwitchPos::MIDDLE485&& (_cam_control_option & uint8_t(ControlOption::STICK_YAW_RIGHT) || is_arming_prevented())) {486result = Event::ENTER_MENU;487} else if (roll == RC_Channel::AuxSwitchPos::LOW) {488result = Event::IN_MENU_EXIT;489} else if (yaw == RC_Channel::AuxSwitchPos::MIDDLE && pitch == RC_Channel::AuxSwitchPos::MIDDLE && roll == RC_Channel::AuxSwitchPos::HIGH) {490if (has_5_key_OSD()) {491result = Event::IN_MENU_RIGHT;492} else {493result = Event::IN_MENU_ENTER;494}495} else if (pitch == RC_Channel::AuxSwitchPos::LOW) {496result = Event::IN_MENU_UP;497} else if (pitch == RC_Channel::AuxSwitchPos::HIGH) {498result = Event::IN_MENU_DOWN;499} else if (_video_recording != _last_video_recording) {500switch (_video_recording) {501case VideoOption::NOT_RECORDING:502result = Event::STOP_RECORDING;503break;504case VideoOption::RECORDING:505result = Event::START_RECORDING;506break;507}508} else if (_osd_option == _last_osd_option) {509// OSD option has not changed so assume stick re-centering510result = Event::NONE;511} else if (_osd_option == OSDOption::ENTER512&& _cam_control_option & uint8_t(ControlOption::TWO_POS_SWITCH)) {513result = Event::ENTER_MENU;514} else if ((_osd_option == OSDOption::OPTION || _osd_option == OSDOption::ENTER)515&& _cam_control_option & uint8_t(ControlOption::THREE_POS_SWITCH)) {516result = Event::ENTER_MENU;517} else if (_osd_option == OSDOption::EXIT518&& _cam_control_option & uint8_t(ControlOption::TWO_POS_SWITCH)) {519result = Event::EXIT_MENU;520} else if ((_osd_option == OSDOption::NO_OPTION || _osd_option == OSDOption::EXIT)521&& _cam_control_option & uint8_t(ControlOption::THREE_POS_SWITCH)) {522result = Event::EXIT_MENU;523} else {524debug("map_rc_input_to_event(): nothing selected\n");525}526return result;527}528529// run the 2-key OSD simulation process, this involves using the power and mode (wifi) buttons530// to cycle through options. unfortunately these are one-way requests so we need to use delays531// to make sure that the camera obeys532void AP_RunCam::handle_2_key_simulation_process(Event ev)533{534debug("%s,M:%d,V:%d,O:%d\n", event_names[int(ev)], _in_menu, int(_video_recording), int(_osd_option));535536switch (ev) {537case Event::ENTER_MENU:538if (_in_menu <= 0) {539_in_menu++;540simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_MODE, _mode_delay_ms);541if (_in_menu > 0) {542// turn off built-in OSD so that the runcam OSD is visible543disable_osd();544_state = State::IN_MENU;545} else {546_state = State::ENTERING_MENU;547}548}549break;550551case Event::EXIT_MENU:552// keep changing mode until we are fully out of the menu553if (_in_menu > 0) {554_in_menu--;555simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_MODE, _mode_delay_ms);556_state = State::EXITING_MENU;557} else {558exit_2_key_osd_menu();559}560break;561562case Event::IN_MENU_ENTER:563// in a sub-menu and save-and-exit was selected564if (_in_menu > 1 && get_top_menu_length() > 0 && _sub_menu_pos == (get_sub_menu_length(_top_menu_pos) - 1) && DeviceModel(_cam_type.get()) != DeviceModel::Run24k) {565simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN, _button_delay_ms);566_sub_menu_pos = 0;567_in_menu--;568// in the top-menu and save-and-exit was selected569} else if (_in_menu == 1 && get_top_menu_length() > 0 && _top_menu_pos == (get_top_menu_length() - 1) && DeviceModel(_cam_type.get()) != DeviceModel::Run24k) {570simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN, _mode_delay_ms);571_in_menu--;572_state = State::EXITING_MENU;573} else if (_top_menu_pos >= 0 && get_sub_menu_length(_top_menu_pos) > 0) {574simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN, _button_delay_ms);575_in_menu = MIN(_in_menu + 1, RUNCAM_OSD_MENU_DEPTH);576}577break;578579case Event::IN_MENU_UP:580case Event::IN_MENU_DOWN:581simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_POWER_BTN, _button_delay_ms); // move to setting582if (_in_menu > 1) {583// in a sub-menu, keep track of the selected position584_sub_menu_pos = (_sub_menu_pos + 1) % get_sub_menu_length(_top_menu_pos);585} else {586// in the top-menu, keep track of the selected position587_top_menu_pos = (_top_menu_pos + 1) % get_top_menu_length();588}589break;590591case Event::IN_MENU_EXIT:592// if we are in a sub-menu this will move us out, if we are in the root menu this will593// exit causing the state machine to get out of sync. the OSD menu hierarchy is consistently594// 2 deep so we can count and be reasonably confident of where we are.595// the only exception is if someone hits save and exit on the root menu - then we are lost.596if (_in_menu > 0) {597_in_menu--;598_sub_menu_pos = 0;599simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_MODE, _mode_delay_ms); // move up/out a menu600}601// no longer in the menu so trigger the OSD re-enablement602if (_in_menu == 0) {603_in_menu = _menu_enter_level;604_state = State::EXITING_MENU;605}606break;607608case Event::NONE:609case Event::IN_MENU_RIGHT:610case Event::BUTTON_RELEASE:611case Event::START_RECORDING:612case Event::STOP_RECORDING:613break;614}615}616617// exit the 2 key OSD menu618void AP_RunCam::exit_2_key_osd_menu()619{620_in_menu = _menu_enter_level;621622// turn built-in OSD back on623enable_osd();624625if (_video_recording == VideoOption::RECORDING && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_START_RECORDING)) {626simulate_camera_button(start_recording_command(), _mode_delay_ms);627_state = State::VIDEO_RECORDING;628} else {629_state = State::READY;630}631}632633// run the 5-key OSD simulation process634void AP_RunCam::handle_5_key_simulation_process(Event ev)635{636debug("%s,M:%d,B:%d,O:%d\n", event_names[int(ev)], _in_menu, int(_button_pressed), int(_osd_option));637638switch (ev) {639case Event::BUTTON_RELEASE:640send_5_key_OSD_cable_simulation_event(ev);641break;642643case Event::ENTER_MENU:644if (_in_menu == 0) {645// turn off built-in OSD so that the runcam OSD is visible646disable_osd();647send_5_key_OSD_cable_simulation_event(ev);648_in_menu = 1;649} else {650send_5_key_OSD_cable_simulation_event(Event::IN_MENU_ENTER);651}652break;653654case Event::EXIT_MENU:655if (_in_menu > 0) {656// turn built-in OSD back on657enable_osd();658send_5_key_OSD_cable_simulation_event(Event::EXIT_MENU);659_in_menu = 0;660}661break;662663case Event::NONE:664break;665666case Event::IN_MENU_EXIT:667case Event::IN_MENU_RIGHT:668case Event::IN_MENU_ENTER:669case Event::IN_MENU_UP:670case Event::IN_MENU_DOWN:671case Event::START_RECORDING:672case Event::STOP_RECORDING:673send_5_key_OSD_cable_simulation_event(ev);674break;675}676}677678// handle a response679void AP_RunCam::handle_5_key_simulation_response(const Request& request)680{681debug("response for command %d result: %d\n", int(request._command), int(request._result));682if (request._result != RequestStatus::SUCCESS) {683simulation_OSD_cable_failed(request);684_button_pressed = ButtonState::NONE;685_waiting_device_response = false;686return;687}688689switch (request._command) {690case Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE:691_button_pressed = ButtonState::NONE;692break;693case Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION:694{695// the high 4 bits is the operationID that we sent696// the low 4 bits is the result code697const ConnectionOperation operationID = ConnectionOperation(request._param);698const uint8_t errorCode = (request._recv_buf[1] & 0x0F);699switch (operationID) {700case ConnectionOperation::RCDEVICE_PROTOCOL_5KEY_FUNCTION_OPEN:701if (errorCode > 0) {702_state = State::IN_MENU;703}704break;705case ConnectionOperation::RCDEVICE_PROTOCOL_5KEY_FUNCTION_CLOSE:706if (errorCode > 0) {707_state = State::READY;708}709break;710}711break;712}713case Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS:714case Command::RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO:715case Command::RCDEVICE_PROTOCOL_COMMAND_CAMERA_CONTROL:716case Command::COMMAND_NONE:717break;718}719720_waiting_device_response = false;721}722723// command to start recording724AP_RunCam::ControlOperation AP_RunCam::start_recording_command() const {725if (DeviceModel(_cam_type.get()) == DeviceModel::Split4k || DeviceModel(_cam_type.get()) == DeviceModel::Hybrid || DeviceModel(_cam_type.get()) == DeviceModel::Run24k) {726return ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_POWER_BTN;727} else {728return ControlOperation::RCDEVICE_PROTOCOL_CHANGE_START_RECORDING;729}730}731732// command to stop recording733AP_RunCam::ControlOperation AP_RunCam::stop_recording_command() const {734if (DeviceModel(_cam_type.get()) == DeviceModel::Split4k || DeviceModel(_cam_type.get()) == DeviceModel::Hybrid || DeviceModel(_cam_type.get()) == DeviceModel::Run24k) {735return ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_POWER_BTN;736} else {737return ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING;738}739}740741// process a response from the serial port742void AP_RunCam::receive()743{744if (!uart) {745return;746}747// process any pending request at least once-per cycle, regardless of available bytes748if (!request_pending(AP_HAL::millis())) {749return;750}751752uint32_t avail = MIN(uart->available(), (uint32_t)RUNCAM_MAX_PACKET_SIZE);753754for (uint32_t i = 0; i < avail; i++) {755756if (!request_pending(AP_HAL::millis())) {757return;758}759760const uint8_t c = uart->read();761if (_pending_request._recv_response_length == 0) {762// Only start receiving packet when we found a header763if (c != RUNCAM_HEADER) {764continue;765}766}767768_pending_request._recv_buf[_pending_request._recv_response_length] = c;769_pending_request._recv_response_length += 1;770771// if data received done, trigger callback to parse response data, and update RUNCAM state772if (_pending_request._recv_response_length == _pending_request._expected_response_length) {773uint8_t crc = _pending_request.get_crc();774775_pending_request._result = (crc == 0) ? RequestStatus::SUCCESS : RequestStatus::INCORRECT_CRC;776777debug("received response for command %d\n", int(_pending_request._command));778_pending_request.parse_response();779// we no longer have a pending request780_pending_request._result = RequestStatus::NONE;781}782}783}784785// every time we send a packet to device and want to get a response786// it's better to clear the rx buffer before the sending the packet787// otherwise useless data in rx buffer will cause the response decoding788// to fail789void AP_RunCam::drain()790{791if (!uart) {792return;793}794795uart->discard_input();796}797798// start the uart if we have one799void AP_RunCam::start_uart()800{801// 8N1 communication802uart->configure_parity(0);803uart->set_stop_bits(1);804uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);805uart->set_options(uart->get_options() | AP_HAL::UARTDriver::OPTION_NODMA_TX | AP_HAL::UARTDriver::OPTION_NODMA_RX);806uart->begin(115200, 10, 10);807uart->discard_input();808}809810// get the device info (firmware version, protocol version and features)811void AP_RunCam::get_device_info()812{813send_request_and_waiting_response(Command::RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO, 0, RUNCAM_INIT_INTERVAL_MS * 4,814UINT16_MAX, FUNCTOR_BIND_MEMBER(&AP_RunCam::parse_device_info, void, const Request&));815}816817// map a Event to a SimulationOperation818AP_RunCam::SimulationOperation AP_RunCam::map_key_to_protocol_operation(const Event key) const819{820SimulationOperation operation = SimulationOperation::SIMULATION_NONE;821switch (key) {822case Event::IN_MENU_EXIT:823operation = SimulationOperation::RCDEVICE_PROTOCOL_5KEY_SIMULATION_LEFT;824break;825case Event::IN_MENU_UP:826operation = SimulationOperation::RCDEVICE_PROTOCOL_5KEY_SIMULATION_UP;827break;828case Event::IN_MENU_RIGHT:829operation = SimulationOperation::RCDEVICE_PROTOCOL_5KEY_SIMULATION_RIGHT;830break;831case Event::IN_MENU_DOWN:832operation = SimulationOperation::RCDEVICE_PROTOCOL_5KEY_SIMULATION_DOWN;833break;834case Event::IN_MENU_ENTER:835operation = SimulationOperation::RCDEVICE_PROTOCOL_5KEY_SIMULATION_SET;836break;837case Event::BUTTON_RELEASE:838case Event::NONE:839case Event::ENTER_MENU:840case Event::EXIT_MENU:841case Event::STOP_RECORDING:842case Event::START_RECORDING:843break;844}845return operation;846}847848// send an event849void AP_RunCam::send_5_key_OSD_cable_simulation_event(const Event key, const uint32_t transition_timeout)850{851debug("OSD cable simulation event %s\n", event_names[int(key)]);852_waiting_device_response = true;853// although we can control press/release, this causes the state machine to behave in the same way854// as the 2-key process855_transition_timeout_ms = transition_timeout;856857switch (key) {858case Event::ENTER_MENU:859open_5_key_OSD_cable_connection(FUNCTOR_BIND_MEMBER(&AP_RunCam::handle_5_key_simulation_response, void, const Request&));860break;861case Event::EXIT_MENU:862close_5_key_OSD_cable_connection(FUNCTOR_BIND_MEMBER(&AP_RunCam::handle_5_key_simulation_response, void, const Request&));863break;864case Event::IN_MENU_UP:865case Event::IN_MENU_RIGHT:866case Event::IN_MENU_DOWN:867case Event::IN_MENU_ENTER:868case Event::IN_MENU_EXIT:869simulate_5_key_OSD_cable_button_press(map_key_to_protocol_operation(key), FUNCTOR_BIND_MEMBER(&AP_RunCam::handle_5_key_simulation_response, void, const Request&));870break;871case Event::BUTTON_RELEASE:872simulate_5_key_OSD_cable_button_release(FUNCTOR_BIND_MEMBER(&AP_RunCam::handle_5_key_simulation_response, void, const Request&));873break;874case Event::STOP_RECORDING:875case Event::START_RECORDING:876case Event::NONE:877break;878}879}880881// every time we run the OSD menu simulation it's necessary to open the connection882void AP_RunCam::open_5_key_OSD_cable_connection(parse_func_t parseFunc)883{884send_request_and_waiting_response(Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION,885uint8_t(ConnectionOperation::RCDEVICE_PROTOCOL_5KEY_FUNCTION_OPEN), 400, 2, parseFunc);886}887888// every time we exit the OSD menu simulation it's necessary to close the connection889void AP_RunCam::close_5_key_OSD_cable_connection(parse_func_t parseFunc)890{891send_request_and_waiting_response(Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION,892uint8_t(ConnectionOperation::RCDEVICE_PROTOCOL_5KEY_FUNCTION_CLOSE), 400, 2, parseFunc);893}894895// simulate button press event of 5 key OSD cable with special button896void AP_RunCam::simulate_5_key_OSD_cable_button_press(const SimulationOperation operation, parse_func_t parseFunc)897{898if (operation == SimulationOperation::SIMULATION_NONE) {899return;900}901902_button_pressed = ButtonState::PRESSED;903904send_request_and_waiting_response(Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS, uint8_t(operation), 400, 2, parseFunc);905}906907// simulate button release event of 5 key OSD cable908void AP_RunCam::simulate_5_key_OSD_cable_button_release(parse_func_t parseFunc)909{910_button_pressed = ButtonState::RELEASED;911912send_request_and_waiting_response(Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE,913uint8_t(SimulationOperation::SIMULATION_NONE), 400, 2, parseFunc);914}915916// send a RunCam request and register a response to be processed917void AP_RunCam::send_request_and_waiting_response(Command commandID, uint8_t param,918uint32_t timeout, uint16_t maxRetryTimes, parse_func_t parserFunc)919{920drain();921922_pending_request = Request(this, commandID, param, timeout, maxRetryTimes, parserFunc);923debug("sending command: %d, op: %d\n", int(commandID), int(param));924// send packet925send_packet(commandID, param);926}927928// send a packet to the serial port929void AP_RunCam::send_packet(Command command, uint8_t param)930{931// is this device open?932if (!uart) {933return;934}935936uint8_t buffer[4];937938bool have_param = param > 0 || command == Command::RCDEVICE_PROTOCOL_COMMAND_CAMERA_CONTROL;939uint8_t buffer_len = have_param ? 4 : 3;940941buffer[0] = RUNCAM_HEADER;942buffer[1] = uint8_t(command);943if (have_param) {944buffer[2] = param;945}946947uint8_t crc = 0;948for (uint8_t i = 0; i < buffer_len - 1; i++) {949crc = crc8_dvb_s2(crc, buffer[i]);950}951952buffer[buffer_len - 1] = crc;953954// send data if possible955uart->write(buffer, buffer_len);956uart->flush();957}958959// handle a device info response960void AP_RunCam::parse_device_info(const Request& request)961{962_protocol_version = ProtocolVersion(request._recv_buf[1]);963964uint8_t featureLowBits = request._recv_buf[2];965uint8_t featureHighBits = request._recv_buf[3];966if (!has_feature(Feature::FEATURES_OVERRIDE)) {967_features.set((featureHighBits << 8) | featureLowBits);968}969if (_features > 0) {970_state = State::INITIALIZED;971GCS_SEND_TEXT(MAV_SEVERITY_INFO, "RunCam initialized, features 0x%04X, %d-key OSD\n", _features.get(),972has_5_key_OSD() ? 5 : has_2_key_OSD() ? 2 : 0);973} else {974// nothing as as nothing does975GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "RunCam device not found\n");976}977debug("RunCam: initialized state: video: %d, osd: %d, cam: %d\n", int(_video_recording), int(_osd_option), int(_cam_control_option));978}979980// wait for the RunCam device to be fully ready981bool AP_RunCam::camera_ready() const982{983if (_state != State::INITIALIZING && _state != State::INITIALIZED) {984return true;985}986return false;987}988989// error handler for OSD simulation990void AP_RunCam::simulation_OSD_cable_failed(const Request& request)991{992_waiting_device_response = false;993if (request._command == Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION) {994uint8_t operationID = request._param;995if (operationID == uint8_t(ConnectionOperation::RCDEVICE_PROTOCOL_5KEY_FUNCTION_CLOSE)) {996return;997}998}999}10001001// process all of the pending responses, retrying as necessary1002bool AP_RunCam::request_pending(uint32_t now)1003{1004if (_pending_request._result == RequestStatus::NONE) {1005return false;1006}10071008if (_pending_request._request_timestamp_ms != 0 && (now - _pending_request._request_timestamp_ms) < _pending_request._timeout_ms) {1009// request still in play1010return true;1011}10121013if (_pending_request._max_retry_times > 0) {1014// request timed out, so resend1015debug("retrying[%d] command 0x%X, op 0x%X\n", int(_pending_request._max_retry_times), int(_pending_request._command), int(_pending_request._param));1016start_uart();1017_pending_request._device->send_packet(_pending_request._command, _pending_request._param);1018_pending_request._recv_response_length = 0;1019_pending_request._request_timestamp_ms = now;1020_pending_request._max_retry_times -= 1;10211022return false;1023}1024debug("timeout command 0x%X, op 0x%X\n", int(_pending_request._command), int(_pending_request._param));1025// too many retries, fail the request1026_pending_request._result = RequestStatus::TIMEOUT;1027_pending_request.parse_response();1028_pending_request._result = RequestStatus::NONE;10291030return false;1031}10321033// constructor for a response structure1034AP_RunCam::Request::Request(AP_RunCam* device, Command commandID, uint8_t param,1035uint32_t timeout, uint16_t maxRetryTimes, parse_func_t parserFunc)1036: _recv_buf(device->_recv_buf),1037_device(device),1038_command(commandID),1039_param(param),1040_recv_response_length(0),1041_timeout_ms(timeout),1042_max_retry_times(maxRetryTimes),1043_parser_func(parserFunc),1044_result(RequestStatus::PENDING)1045{1046_request_timestamp_ms = AP_HAL::millis();1047_expected_response_length = get_expected_response_length(commandID);1048}10491050uint8_t AP_RunCam::Request::get_crc() const1051{1052uint8_t crc = 0;1053for (int i = 0; i < _recv_response_length; i++) {1054crc = crc8_dvb_s2(crc, _recv_buf[i]);1055}1056return crc;1057}10581059// get the length of a response1060uint8_t AP_RunCam::Request::get_expected_response_length(const Command command) const1061{1062for (uint16_t i = 0; i < RUNCAM_NUM_EXPECTED_RESPONSES; i++) {1063if (_expected_responses_length[i].command == command) {1064return _expected_responses_length[i].reponse_length;1065}1066}10671068return 0;1069}10701071// AP_Camera API10721073// return true if healthy1074bool AP_RunCam::healthy() const1075{1076return camera_ready();1077}10781079// momentary switch to change camera between picture and video modes1080void AP_RunCam::cam_mode_toggle()1081{10821083}10841085// entry point to actually take a picture. returns true on success1086bool AP_RunCam::trigger_pic()1087{1088return false;1089}10901091// send camera information message to GCS1092void AP_RunCam::send_camera_information(mavlink_channel_t chan) const1093{1094// exit immediately if not initialised1095if (!camera_ready() || _cam_type.get() <= 0 || _cam_type.get() > int8_t(ARRAY_SIZE(_models))) {1096return;1097}10981099static const uint8_t vendor_name[32] = "RunCam";1100uint8_t model_name[32] {};1101strncpy((char *)model_name, _models[_cam_type.get()-1], MIN(sizeof(model_name), sizeof(_models[_cam_type.get()-1])));1102const char cam_definition_uri[140] {};11031104// capability flags1105uint32_t flags = 0;11061107if (has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_START_RECORDING)) {1108flags = CAMERA_CAP_FLAGS_CAPTURE_VIDEO;1109}11101111if (has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE)) {1112flags |= CAMERA_CAP_FLAGS_CAPTURE_IMAGE;1113}11141115// send CAMERA_INFORMATION message1116mavlink_msg_camera_information_send(1117chan,1118AP_HAL::millis(), // time_boot_ms1119vendor_name, // vendor_name uint8_t[32]1120model_name, // model_name uint8_t[32]11210, // firmware version uint32_t1122NaNf, // focal_length float (mm)1123NaNf, // sensor_size_h float (mm)1124NaNf, // sensor_size_v float (mm)11250, // resolution_h uint16_t (pix)11260, // resolution_v uint16_t (pix)11270, // lens_id uint8_t1128flags, // flags uint32_t (CAMERA_CAP_FLAGS)11290, // cam_definition_version uint16_t1130cam_definition_uri, // cam_definition_uri char[140]1131_instance + 1); // gimbal_device_id uint8_t1132}11331134// send camera settings message to GCS1135void AP_RunCam::send_camera_settings(mavlink_channel_t chan) const1136{1137// exit immediately if not initialised1138if (!camera_ready()) {1139return;1140}11411142// send CAMERA_SETTINGS message1143mavlink_msg_camera_settings_send(1144chan,1145AP_HAL::millis(), // time_boot_ms1146_video_recording == VideoOption::RECORDING ? CAMERA_MODE_VIDEO : CAMERA_MODE_IMAGE, // camera mode (0:image, 1:video, 2:image survey)1147NaNf, // zoomLevel float, percentage from 0 to 100, NaN if unknown1148NaNf); // focusLevel float, percentage from 0 to 100, NaN if unknown1149}11501151AP_RunCam *AP::runcam() {1152return AP_RunCam::get_singleton();1153}11541155#endif // AP_CAMERA_RUNCAM_ENABLED115611571158