AP_Camera: bug fixes to support 5-key remote RunCams

allow the boot-time recording state to be configured
only process events on state transitions. Simplifies logic and debugging.
support regular Split 2s
allow menu enter/exit in 5-key mode
match betaflight with 5-Key OSD which requires an "enter" key
This commit is contained in:
Andy Piper 2020-02-02 17:15:57 +00:00 committed by Andrew Tridgell
parent def108c0e0
commit 387b5e7002
2 changed files with 209 additions and 135 deletions

View File

@ -53,18 +53,18 @@ const AP_Param::GroupInfo AP_RunCam::var_info[] = {
// @DisplayName: RunCam button delay before allowing further button presses
// @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.
// @User: Advanced
AP_GROUPINFO("BTN_DELAY", 4, AP_RunCam, _button_delay_ms, 300),
AP_GROUPINFO("BTN_DELAY", 4, AP_RunCam, _button_delay_ms, RUNCAM_DEFAULT_BUTTON_PRESS_DELAY),
// @Param: MDE_DELAY
// @DisplayName: RunCam mode delay before allowing further button presses
// @Description: Time it takes for the a RunCam mode button press to be actived in ms. If this is too short then commands can get out of sync.
// @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.
// @User: Advanced
AP_GROUPINFO("MDE_DELAY", 5, AP_RunCam, _mode_delay_ms, 800),
// @Param: CONTROL
// @DisplayName: RunCam control option
// @Description: Specifies the allowed actions required to enter the OSD menu
// @Bitmask: 0:Stick yaw right,1:Stick roll right,2:3-position switch,3:2-position switch
// @Bitmask: 0:Stick yaw right,1:Stick roll right,2:3-position switch,3:2-position switch,4:Autorecording enabled
// @User: Advanced
AP_GROUPINFO("CONTROL", 6, AP_RunCam, _cam_control_option, uint8_t(ControlOption::STICK_ROLL_RIGHT) | uint8_t(ControlOption::TWO_POS_SWITCH)),
@ -74,7 +74,15 @@ const AP_Param::GroupInfo AP_RunCam::var_info[] = {
#define RUNCAM_DEBUG 0
#if RUNCAM_DEBUG
#define debug(fmt, args ...) do { hal.console->printf("RunCam[%d]: " fmt, int(_state), ## args); } while (0)
static const char* event_names[11] = {
"NONE", "ENTER_MENU", "EXIT_MENU",
"IN_MENU_ENTER", "IN_MENU_RIGHT", "IN_MENU_UP", "IN_MENU_DOWN", "IN_MENU_EXIT",
"BUTTON_RELEASE", "STOP_RECORDING", "START_RECORDING"
};
static const char* state_names[7] = {
"INITIALIZING", "INITIALIZED", "READY", "VIDEO_RECORDING", "ENTERING_MENU", "IN_MENU", "EXITING_MENU"
};
#define debug(fmt, args ...) do { hal.console->printf("RunCam[%s]: " fmt, state_names[int(_state)], ## args); } while (0)
#else
#define debug(fmt, args ...)
#endif
@ -101,7 +109,8 @@ static const uint32_t RUNCAM_OSD_UPDATE_INTERVAL_MS = 100; // 10Hz
AP_RunCam::Menu AP_RunCam::_menus[RUNCAM_MAX_DEVICE_TYPES] = {
// these are correct for the runcam split micro v2.4.4, others may vary
// Video, Image, TV-OUT, Micro SD Card, General
{ 6, { 5, 8, 3, 3, 7 }},
{ 6, { 5, 8, 3, 3, 7 }}, // SplitMicro
{ 0, { 0 }}, // Split
};
AP_RunCam::AP_RunCam()
@ -111,7 +120,8 @@ AP_RunCam::AP_RunCam()
AP_HAL::panic("AP_RunCam must be singleton");
}
_singleton = this;
_cam_type = constrain_int16(_cam_type, 0, RUNCAM_MAX_DEVICE_TYPES - 1);
_cam_type = constrain_int16(_cam_type, 0, RUNCAM_MAX_DEVICE_TYPES);
_video_recording = VideoOption(_cam_control_option & uint8_t(ControlOption::VIDEO_RECORDING_AT_BOOT));
}
// init the runcam device by finding a serial device configured for the RunCam protocol
@ -124,11 +134,11 @@ void AP_RunCam::init()
if (uart != nullptr) {
/*
if the user has setup a serial port as a runcam then default
type to the split. This makes setup a bit easier for most
type to the split micro (Andy's development platform!). This makes setup a bit easier for most
users while still enabling parameters to be hidden for users
without a runcam
*/
_cam_type.set_default(int8_t(DeviceType::Split));
_cam_type.set_default(int8_t(DeviceType::SplitMicro));
}
if (_cam_type.get() == int8_t(DeviceType::Disabled)) {
uart = nullptr;
@ -139,6 +149,12 @@ void AP_RunCam::init()
return;
}
// Split requires two mode presses to get into the menu
if (_cam_type.get() == int8_t(DeviceType::Split)) {
_menu_enter_level = -1;
_in_menu = -1;
}
uart->begin(115200);
// first transition is from initialized to ready
@ -149,13 +165,14 @@ void AP_RunCam::init()
}
// simulate pressing the camera button
bool AP_RunCam::simulate_camera_button(const ControlOperation operation)
bool AP_RunCam::simulate_camera_button(const ControlOperation operation, const uint32_t transition_timeout)
{
if (!uart || _protocol_version != ProtocolVersion::VERSION_1_0) {
return false;
}
debug("press button %d\n", int(operation));
_transition_timeout_ms = transition_timeout;
debug("press button %d, timeout=%dms\n", int(operation), int(transition_timeout));
send_packet(Command::RCDEVICE_PROTOCOL_COMMAND_CAMERA_CONTROL, uint8_t(operation));
return true;
@ -163,29 +180,29 @@ bool AP_RunCam::simulate_camera_button(const ControlOperation operation)
// start the video
void AP_RunCam::start_recording() {
debug("start recording\n");
_video_recording = true;
debug("start recording(%d)\n", int(_state));
_video_recording = VideoOption::RECORDING;
_osd_option = OSDOption::NO_OPTION;
}
// stop the video
void AP_RunCam::stop_recording() {
debug("stop recording\n");
_video_recording = false;
debug("stop recording(%d)\n", int(_state));
_video_recording = VideoOption::NOT_RECORDING;
_osd_option = OSDOption::NO_OPTION;
}
// enter the OSD menu
void AP_RunCam::enter_osd()
{
debug("enter osd\n");
debug("enter osd(%d)\n", int(_state));
_osd_option = OSDOption::ENTER;
}
// exit the OSD menu
void AP_RunCam::exit_osd()
{
debug("exit osd\n");
debug("exit osd(%d)\n", int(_state));
_osd_option = OSDOption::EXIT;
}
@ -221,7 +238,7 @@ bool AP_RunCam::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len)
}
// currently in the OSD menu, do not allow arming
if (_in_menu > 0) {
if (is_arming_prevented()) {
hal.util->snprintf(failure_msg, failure_msg_len, "In OSD menu");
return false;
}
@ -273,10 +290,10 @@ void AP_RunCam::update_state_machine_armed()
switch (_state) {
case State::READY:
handle_ready(_video_recording ? Event::START_RECORDING : Event::NONE);
handle_ready(_video_recording == VideoOption::RECORDING && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_START_RECORDING) ? Event::START_RECORDING : Event::NONE);
break;
case State::VIDEO_RECORDING:
handle_recording(!_video_recording ? Event::STOP_RECORDING : Event::NONE);
handle_recording(_video_recording == VideoOption::NOT_RECORDING && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_START_RECORDING) ? Event::STOP_RECORDING : Event::NONE);
break;
case State::INITIALIZING:
case State::INITIALIZED:
@ -292,6 +309,7 @@ void AP_RunCam::update_state_machine_disarmed()
{
const uint32_t now = AP_HAL::millis();
if (_waiting_device_response || (now - _transition_start_ms) < _transition_timeout_ms) {
_last_rc_event = Event::NONE;
return;
}
@ -299,10 +317,20 @@ void AP_RunCam::update_state_machine_disarmed()
_transition_timeout_ms = 0;
const Event ev = map_rc_input_to_event();
if (ev == Event::BUTTON_RELEASE) {
_button_pressed = false;
// only take action on transitions
if (ev == _last_rc_event && _state == _last_state && _osd_option == _last_osd_option
&& _last_in_menu == _in_menu && _last_video_recording == _video_recording) {
return;
}
debug("update_state_machine_disarmed(%s)\n", event_names[int(ev)]);
_last_rc_event = ev;
_last_state = _state;
_last_osd_option = _osd_option;
_last_in_menu = _in_menu;
_last_video_recording = _video_recording;
switch (_state) {
case State::INITIALIZING:
break;
@ -330,13 +358,20 @@ void AP_RunCam::update_state_machine_disarmed()
// handle the initialized state
void AP_RunCam::handle_initialized(Event ev)
{
// the camera always starts in recording mode by default
if (!_video_recording) {
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING);
set_mode_change_timeout();
// the camera should be configured to start with recording mode off by default
// a recording change needs significantly extra time to process
if (_video_recording == VideoOption::RECORDING && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_START_RECORDING)) {
if (!(_cam_control_option & uint8_t(ControlOption::VIDEO_RECORDING_AT_BOOT))) {
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_START_RECORDING, _mode_delay_ms * 2);
}
_state = State::VIDEO_RECORDING;
} else if (_video_recording == VideoOption::NOT_RECORDING && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_START_RECORDING)) {
if (_cam_control_option & uint8_t(ControlOption::VIDEO_RECORDING_AT_BOOT)) {
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING, _mode_delay_ms * 2);
}
_state = State::READY;
} else {
_state = State::VIDEO_RECORDING;
_state = State::READY;
}
debug("device fully booted after %ums\n", unsigned(AP_HAL::millis()));
}
@ -347,6 +382,7 @@ void AP_RunCam::handle_ready(Event ev)
switch (ev) {
case Event::ENTER_MENU:
case Event::IN_MENU_ENTER:
case Event::IN_MENU_RIGHT:
if (ev == Event::ENTER_MENU || _cam_control_option & uint8_t(ControlOption::STICK_ROLL_RIGHT)) {
_top_menu_pos = -1;
_sub_menu_pos = 0;
@ -354,13 +390,11 @@ void AP_RunCam::handle_ready(Event ev)
}
break;
case Event::START_RECORDING:
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_START_RECORDING);
set_mode_change_timeout();
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_START_RECORDING, _mode_delay_ms);
_state = State::VIDEO_RECORDING;
break;
case Event::NONE:
case Event::EXIT_MENU:
case Event::IN_MENU_RIGHT:
case Event::IN_MENU_UP:
case Event::IN_MENU_DOWN:
case Event::IN_MENU_EXIT:
@ -376,22 +410,20 @@ void AP_RunCam::handle_recording(Event ev)
switch (ev) {
case Event::ENTER_MENU:
case Event::IN_MENU_ENTER:
case Event::IN_MENU_RIGHT:
if (ev == Event::ENTER_MENU || _cam_control_option & uint8_t(ControlOption::STICK_ROLL_RIGHT)) {
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING);
set_mode_change_timeout();
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING, _mode_delay_ms);
_top_menu_pos = -1;
_sub_menu_pos = 0;
_state = State::ENTERING_MENU;
}
break;
case Event::STOP_RECORDING:
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING);
set_mode_change_timeout();
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING, _mode_delay_ms);
_state = State::READY;
break;
case Event::NONE:
case Event::EXIT_MENU:
case Event::IN_MENU_RIGHT:
case Event::IN_MENU_UP:
case Event::IN_MENU_DOWN:
case Event::IN_MENU_EXIT:
@ -424,26 +456,46 @@ AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const
Event result = Event::NONE;
if (_button_pressed
&& yaw == RC_Channel::MIDDLE && pitch == RC_Channel::MIDDLE && roll == RC_Channel::MIDDLE) {
result = Event::BUTTON_RELEASE;
if (_button_pressed != ButtonState::NONE) {
if (_button_pressed == ButtonState::PRESSED && yaw == RC_Channel::MIDDLE && pitch == RC_Channel::MIDDLE && roll == RC_Channel::MIDDLE) {
result = Event::BUTTON_RELEASE;
} else {
result = Event::NONE; // still waiting to be released
}
} else if (throttle == RC_Channel::MIDDLE && yaw == RC_Channel::LOW
&& pitch == RC_Channel::MIDDLE && roll == RC_Channel::MIDDLE
&& _cam_control_option & uint8_t(ControlOption::STICK_YAW_RIGHT)) {
// don't allow an action close to arming unless the user had configured it or arming is not possible
// but don't prevent the 5-Key control actually working
&& (_cam_control_option & uint8_t(ControlOption::STICK_YAW_RIGHT) || is_arming_prevented())) {
result = Event::EXIT_MENU;
}
if (throttle == RC_Channel::MIDDLE && yaw == RC_Channel::HIGH
} else if (throttle == RC_Channel::MIDDLE && yaw == RC_Channel::HIGH
&& pitch == RC_Channel::MIDDLE && roll == RC_Channel::MIDDLE
&& _cam_control_option & uint8_t(ControlOption::STICK_YAW_RIGHT)) {
&& (_cam_control_option & uint8_t(ControlOption::STICK_YAW_RIGHT) || is_arming_prevented())) {
result = Event::ENTER_MENU;
} else if (roll == RC_Channel::LOW) {
result = Event::IN_MENU_EXIT;
} else if (yaw == RC_Channel::MIDDLE && pitch == RC_Channel::MIDDLE && roll == RC_Channel::HIGH) {
result = Event::IN_MENU_ENTER;
} else if (pitch == RC_Channel::HIGH) {
result = Event::IN_MENU_UP;
if (has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE)) {
result = Event::IN_MENU_RIGHT;
} else {
result = Event::IN_MENU_ENTER;
}
} else if (pitch == RC_Channel::LOW) {
result = Event::IN_MENU_UP;
} else if (pitch == RC_Channel::HIGH) {
result = Event::IN_MENU_DOWN;
} else if (_video_recording != _last_video_recording) {
switch (_video_recording) {
case VideoOption::NOT_RECORDING:
result = Event::STOP_RECORDING;
break;
case VideoOption::RECORDING:
result = Event::START_RECORDING;
break;
}
} else if (_osd_option == _last_osd_option) {
// OSD option has not changed so assume stick re-centering
result = Event::NONE;
} else if (_osd_option == OSDOption::ENTER
&& _cam_control_option & uint8_t(ControlOption::TWO_POS_SWITCH)) {
result = Event::ENTER_MENU;
@ -465,15 +517,20 @@ AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const
// to make sure that the camera obeys
void AP_RunCam::handle_2_key_simulation_process(Event ev)
{
#if RUNCAM_DEBUG
if (_in_menu > 0 && ev != Event::NONE) {
debug("E:%d,M:%d,V:%d,O:%d\n", int(ev), _in_menu, _video_recording, int(_osd_option));
}
#endif
debug("%s,M:%d,V:%d,O:%d\n", event_names[int(ev)], _in_menu, int(_video_recording), int(_osd_option));
switch (ev) {
case Event::ENTER_MENU:
if (_in_menu == 0) {
enter_2_key_osd_menu();
if (_in_menu <= 0) {
_in_menu++;
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_MODE, _mode_delay_ms);
if (_in_menu > 0) {
// turn off built-in OSD so that the runcam OSD is visible
disable_osd();
_state = State::IN_MENU;
} else {
_state = State::ENTERING_MENU;
}
}
break;
@ -481,8 +538,7 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev)
// keep changing mode until we are fully out of the menu
if (_in_menu > 0) {
_in_menu--;
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_MODE);
set_mode_change_timeout();
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_MODE, _mode_delay_ms);
_state = State::EXITING_MENU;
} else {
exit_2_key_osd_menu();
@ -490,26 +546,24 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev)
break;
case Event::IN_MENU_ENTER:
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN); // change setting
// in a sub-menu and save-and-exit was selected
if (_in_menu > 1 && _sub_menu_pos == (get_sub_menu_length(_top_menu_pos) - 1)) {
set_button_press_timeout();
if (_in_menu > 1 && get_top_menu_length() > 0 && _sub_menu_pos == (get_sub_menu_length(_top_menu_pos) - 1)) {
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN, _button_delay_ms);
_in_menu--;
// in the top-menu and save-and-exit was selected
} else if (_in_menu == 1 && _top_menu_pos == (get_top_menu_length() - 1)) {
set_mode_change_timeout();
} else if (_in_menu == 1 && get_top_menu_length() > 0 && _top_menu_pos == (get_top_menu_length() - 1)) {
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN, _mode_delay_ms);
_in_menu--;
_state = State::EXITING_MENU;
} else {
set_button_press_timeout();
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN, _button_delay_ms);
_in_menu = MIN(_in_menu + 1, RUNCAM_OSD_MENU_DEPTH);
}
break;
case Event::IN_MENU_UP:
case Event::IN_MENU_DOWN:
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_POWER_BTN); // move to setting
set_button_press_timeout();
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_POWER_BTN, _button_delay_ms); // move to setting
if (_in_menu > 1) {
// in a sub-menu, keep track of the selected position
_sub_menu_pos = (_sub_menu_pos + 1) % get_sub_menu_length(_top_menu_pos);
@ -526,11 +580,11 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev)
// the only exception is if someone hits save and exit on the root menu - then we are lost.
if (_in_menu > 0) {
_in_menu--;
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_MODE); // move up/out a menu
set_mode_change_timeout();
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_MODE, _mode_delay_ms); // move up/out a menu
}
// no longer in the menu so trigger the OSD re-enablement
if (_in_menu == 0) {
_in_menu = _menu_enter_level;
_state = State::EXITING_MENU;
}
break;
@ -544,49 +598,40 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev)
}
}
// enter the 2 key OSD menu
void AP_RunCam::enter_2_key_osd_menu()
{
// turn off built-in OSD so that the runcam OSD is visible
disable_osd();
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_MODE);
set_mode_change_timeout();
_in_menu = 1;
_state = State::IN_MENU;
}
// exit the 2 key OSD menu
void AP_RunCam::exit_2_key_osd_menu()
{
_in_menu = _menu_enter_level;
// turn built-in OSD back on
enable_osd();
if (_video_recording) {
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_START_RECORDING);
set_mode_change_timeout();
if (_video_recording == VideoOption::RECORDING && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_START_RECORDING)) {
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_START_RECORDING, _mode_delay_ms);
_state = State::VIDEO_RECORDING;
}
else {
} else {
_state = State::READY;
}
_in_menu = 0;
}
// run the 5-key OSD simulation process
void AP_RunCam::handle_5_key_simulation_process(Event ev)
{
debug("%s,M:%d,B:%d,O:%d\n", event_names[int(ev)], _in_menu, int(_button_pressed), int(_osd_option));
switch (ev) {
case Event::BUTTON_RELEASE:
send_5_key_OSD_cable_simulation_event(ev);
_waiting_device_response = true;
return;
break;
case Event::ENTER_MENU:
if (_in_menu > 0) {
ev = Event::IN_MENU_RIGHT;
} else {
if (_in_menu == 0) {
// turn off built-in OSD so that the runcam OSD is visible
disable_osd();
send_5_key_OSD_cable_simulation_event(ev);
_in_menu = 1;
} else {
send_5_key_OSD_cable_simulation_event(Event::IN_MENU_ENTER);
}
break;
@ -594,24 +639,23 @@ void AP_RunCam::handle_5_key_simulation_process(Event ev)
if (_in_menu > 0) {
// turn built-in OSD back on
enable_osd();
send_5_key_OSD_cable_simulation_event(Event::EXIT_MENU);
_in_menu = 0;
}
break;
case Event::NONE:
case Event::IN_MENU_ENTER:
break;
case Event::IN_MENU_EXIT:
case Event::IN_MENU_RIGHT:
case Event::IN_MENU_ENTER:
case Event::IN_MENU_UP:
case Event::IN_MENU_DOWN:
case Event::IN_MENU_EXIT:
case Event::START_RECORDING:
case Event::STOP_RECORDING:
break;
}
if (ev != Event::NONE) {
send_5_key_OSD_cable_simulation_event(ev);
_button_pressed = true;
_waiting_device_response = true;
break;
}
}
@ -621,38 +665,36 @@ void AP_RunCam::handle_5_key_simulation_response(const Request& request)
debug("response for command %d result: %d\n", int(request._command), int(request._result));
if (request._result != RequestStatus::SUCCESS) {
simulation_OSD_cable_failed(request);
_button_pressed = ButtonState::NONE;
_waiting_device_response = false;
return;
}
switch (request._command) {
case Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE:
_button_pressed = false;
_button_pressed = ButtonState::NONE;
break;
case Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION:
{
// the high 4 bits is the operationID that we sent
// the low 4 bits is the result code
_button_pressed = true;
const ConnectionOperation operationID = ConnectionOperation(request._param);
const uint8_t errorCode = (request._recv_buf[1] & 0x0F);
switch (operationID) {
case ConnectionOperation::RCDEVICE_PROTOCOL_5KEY_FUNCTION_OPEN:
if (errorCode > 0) {
_in_menu = 1;
_state = State::IN_MENU;
}
break;
case ConnectionOperation::RCDEVICE_PROTOCOL_5KEY_FUNCTION_CLOSE:
if (errorCode > 0) {
_in_menu = 0;
_state = State::READY;
}
break;
}
break;
}
case Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS:
_button_pressed = true;
break;
case Command::RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO:
case Command::RCDEVICE_PROTOCOL_COMMAND_CAMERA_CONTROL:
case Command::COMMAND_NONE:
@ -698,7 +740,7 @@ void AP_RunCam::receive()
_pending_request._result = (crc == 0) ? RequestStatus::SUCCESS : RequestStatus::INCORRECT_CRC;
debug("received response %d\n", int(_pending_request._command));
debug("received response for command %d\n", int(_pending_request._command));
_pending_request.parse_response();
// we no longer have a pending request
_pending_request._result = RequestStatus::NONE;
@ -761,9 +803,14 @@ AP_RunCam::SimulationOperation AP_RunCam::map_key_to_protocol_operation(const Ev
}
// send an event
void AP_RunCam::send_5_key_OSD_cable_simulation_event(const Event key)
void AP_RunCam::send_5_key_OSD_cable_simulation_event(const Event key, const uint32_t transition_timeout)
{
debug("OSD cable simulation event %d\n", int(key));
debug("OSD cable simulation event %s\n", event_names[int(key)]);
_waiting_device_response = true;
// although we can control press/release, this causes the state machine to behave in the same way
// as the 2-key process
_transition_timeout_ms = transition_timeout;
switch (key) {
case Event::ENTER_MENU:
open_5_key_OSD_cable_connection(FUNCTOR_BIND_MEMBER(&AP_RunCam::handle_5_key_simulation_response, void, const Request&));
@ -809,12 +856,16 @@ void AP_RunCam::simulate_5_key_OSD_cable_button_press(const SimulationOperation
return;
}
_button_pressed = ButtonState::PRESSED;
send_request_and_waiting_response(Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS, uint8_t(operation), 400, 2, parseFunc);
}
// simulate button release event of 5 key OSD cable
void AP_RunCam::simulate_5_key_OSD_cable_button_release(parse_func_t parseFunc)
{
_button_pressed = ButtonState::RELEASED;
send_request_and_waiting_response(Command::RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE,
uint8_t(SimulationOperation::SIMULATION_NONE), 400, 2, parseFunc);
}
@ -859,6 +910,7 @@ void AP_RunCam::send_packet(Command command, uint8_t param)
// send data if possible
uart->write(buffer, buffer_len);
uart->flush();
}
// crc functions
@ -901,13 +953,18 @@ void AP_RunCam::parse_device_info(const Request& request)
if (!has_feature(Feature::FEATURES_OVERRIDE)) {
_features = (featureHighBits << 8) | featureLowBits;
}
_state = State::INITIALIZED;
gcs().send_text(MAV_SEVERITY_INFO, "RunCam initialized, features 0x%04X, %d-key OSD\n", _features.get(),
has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE) ? 5 :
(has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE) &&
has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON) &&
has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON)) ? 2 : 0);
debug("RunCam: initialized state: video: %d, osd: %d, cam: %d\n", _video_recording, int(_osd_option), int(_cam_control_option));
if (_features > 0) {
_state = State::INITIALIZED;
gcs().send_text(MAV_SEVERITY_INFO, "RunCam initialized, features 0x%04X, %d-key OSD\n", _features.get(),
has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE) ? 5 :
(has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE) &&
has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON) &&
has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON)) ? 2 : 0);
} else {
// nothing as as nothing does
gcs().send_text(MAV_SEVERITY_WARNING, "RunCam device not found\n");
}
debug("RunCam: initialized state: video: %d, osd: %d, cam: %d\n", int(_video_recording), int(_osd_option), int(_cam_control_option));
}
// wait for the RunCam device to be fully ready
@ -972,6 +1029,7 @@ AP_RunCam::Request::Request(AP_RunCam* device, Command commandID, uint8_t param,
_device(device),
_param(param),
_parser_func(parserFunc),
_recv_response_length(0),
_result(RequestStatus::PENDING)
{
_request_timestamp_ms = AP_HAL::millis();

View File

@ -36,7 +36,10 @@
#include <AP_Arming/AP_Arming.h>
#include <AP_OSD/AP_OSD.h>
#define RUNCAM_MAX_PACKET_SIZE 64
#define RUNCAM_MAX_PACKET_SIZE 64
#define RUNCAM_DEFAULT_BUTTON_PRESS_DELAY 300
// 5-key OSD auto-repeats if pressed for too long
#define RUNCAM_5KEY_BUTTON_PRESS_DELAY 100
/// @class AP_RunCam
@ -57,7 +60,8 @@ public:
enum class DeviceType {
Disabled = 0,
Split = 1,
SplitMicro = 1, // video support only
Split = 2 // camera and video support
};
// operation of camera button simulation
@ -75,13 +79,14 @@ public:
STICK_YAW_RIGHT = (1 << 0),
STICK_ROLL_RIGHT = (1 << 1),
THREE_POS_SWITCH = (1 << 2),
TWO_POS_SWITCH = (1 << 3)
TWO_POS_SWITCH = (1 << 3),
VIDEO_RECORDING_AT_BOOT = (1 << 4)
};
// initialize the RunCam driver
void init();
// camera button simulation
bool simulate_camera_button(const ControlOperation operation);
bool simulate_camera_button(const ControlOperation operation, const uint32_t transition_timeout = RUNCAM_DEFAULT_BUTTON_PRESS_DELAY);
// start the video
void start_recording();
// stop the video
@ -102,6 +107,9 @@ public:
private:
// definitions prefixed with RCDEVICE taken from https://support.runcam.com/hc/en-us/articles/360014537794-RunCam-Device-Protocol
// possible supported features
// RunCam Split 3S micro reports 0x77 (POWER, WIFI, MODE, SETTING, DPORT, START)
// RunCam Split 2S reports 0x57 (POWER, WIFI, MODE, SETTING, START)
// RunCam Racer 3 reports 0x08 (OSD)
enum class Feature {
RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON = (1 << 0),
RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON = (1 << 1), // WiFi/Mode button
@ -188,11 +196,22 @@ private:
NO_OPTION
};
enum class VideoOption {
NOT_RECORDING = 0,
RECORDING = 1
};
enum class ButtonState {
NONE,
PRESSED,
RELEASED
};
static const uint8_t RUNCAM_NUM_SUB_MENUS = 5;
static const uint8_t RUNCAM_NUM_EXPECTED_RESPONSES = 4;
static const uint8_t RUNCAM_MAX_MENUS = 1;
static const uint8_t RUNCAM_MAX_MENU_LENGTH = 6;
static const uint8_t RUNCAM_MAX_DEVICE_TYPES = 1;
static const uint8_t RUNCAM_MAX_DEVICE_TYPES = 2;
// supported features, usually probed from the device
AP_Int16 _features;
@ -208,7 +227,7 @@ private:
AP_Int8 _cam_control_option;
// video on/off
bool _video_recording = true;
VideoOption _video_recording = VideoOption::NOT_RECORDING;
// detected protocol version
ProtocolVersion _protocol_version = ProtocolVersion::UNKNOWN;
// uart for the device
@ -221,14 +240,22 @@ private:
uint32_t _transition_start_ms;
// timeout of the current button press or boot sequence
uint32_t _transition_timeout_ms;
// record last state transition to avoid spurious transitions
Event _last_rc_event;
State _last_state = State::INITIALIZING;
OSDOption _last_osd_option = OSDOption::NONE;
int8_t _last_in_menu;
VideoOption _last_video_recording = VideoOption::NOT_RECORDING;
// OSD state machine: button has been pressed
bool _button_pressed;
ButtonState _button_pressed = ButtonState::NONE;
// OSD state machine: waiting for a response
bool _waiting_device_response;
// OSD option from RC switches
OSDOption _osd_option;
// OSD state mechine: in the menu, value indicates depth
uint8_t _in_menu;
int8_t _in_menu;
// the starting value of _in_menu
int8_t _menu_enter_level;
// OSD state machine: current selection in the top menu
int8_t _top_menu_pos;
// OSD state machine: current selection in the sub menu
@ -295,23 +322,12 @@ private:
// return the length of the top menu
uint8_t get_top_menu_length() const {
return _menus[_cam_type]._top_menu_length;
return _menus[_cam_type - 1]._top_menu_length;
}
// return the length of a particular sub-menu
uint8_t get_sub_menu_length(uint8_t submenu) const {
return _menus[_cam_type]._sub_menu_lengths[submenu];
}
// start the counter for a button press
void set_button_press_timeout() {
_transition_timeout_ms = _button_delay_ms;
_button_pressed = true;
}
// start the counter for a mode change
void set_mode_change_timeout() {
_transition_timeout_ms = _mode_delay_ms;
_button_pressed = true;
return _menus[_cam_type - 1]._sub_menu_lengths[submenu];
}
// disable the OSD display
@ -354,8 +370,6 @@ private:
// run the 2-key OSD simulation process
void handle_2_key_simulation_process(Event ev);
// enter the 2 key OSD menu
void enter_2_key_osd_menu();
// eexit the 2 key OSD menu
void exit_2_key_osd_menu();
@ -373,7 +387,7 @@ private:
// 5 key osd cable simulation
SimulationOperation map_key_to_protocol_operation(const Event ev) const;
// send an event
void send_5_key_OSD_cable_simulation_event(const Event key);
void send_5_key_OSD_cable_simulation_event(const Event key, const uint32_t transition_timeout = RUNCAM_5KEY_BUTTON_PRESS_DELAY);
// enter the menu
void open_5_key_OSD_cable_connection(parse_func_t parseFunc);
// exit the menu
@ -395,7 +409,9 @@ private:
// wait for the RunCam device to be fully ready
bool camera_ready() const;
// whether or not the requested feature is supported
bool has_feature(const Feature feature) { return _features.get() & uint16_t(feature); }
bool has_feature(const Feature feature) const { return _features.get() & uint16_t(feature); }
// whether or not we can arm
bool is_arming_prevented() const { return _in_menu > _menu_enter_level; }
// error handler for OSD simulation
void simulation_OSD_cable_failed(const Request& request);
// process pending request, retrying as necessary