AP_Camera: if the RunCam supports both 2-key and 5-key control, use 2-key

adjust camera menus for Split4 4k
use power button to start/stop recording on Split4
This commit is contained in:
Andy Piper 2020-10-19 18:11:30 +01:00 committed by Andrew Tridgell
parent 8cd9af5ddd
commit bd6b28e5d9
2 changed files with 50 additions and 18 deletions

View File

@ -34,7 +34,7 @@ const AP_Param::GroupInfo AP_RunCam::var_info[] = {
// @Param: TYPE
// @DisplayName: RunCam device type
// @Description: RunCam deviee type used to determine OSD menu structure and shutter options.
// @Values: 0:Disabled, 1:RunCam Split Micro/RunCam with UART, 2:RunCam Split
// @Values: 0:Disabled, 1:RunCam Split Micro/RunCam with UART, 2:RunCam Split, 3:RunCam Split4 4k
AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceType::Disabled), AP_PARAM_FLAG_ENABLE),
// @Param: FEATURES
@ -112,6 +112,7 @@ AP_RunCam::Menu AP_RunCam::_menus[RUNCAM_MAX_DEVICE_TYPES] = {
// Video, Image, TV-OUT, Micro SD Card, General
{ 6, { 5, 8, 3, 3, 7 }}, // SplitMicro
{ 0, { 0 }}, // Split
{ 6, { 4, 10, 3, 3, 7 }}, // Split4 4K
};
AP_RunCam::AP_RunCam()
@ -361,12 +362,12 @@ void AP_RunCam::handle_initialized(Event ev)
// 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);
simulate_camera_button(start_recording_command(), _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);
simulate_camera_button(stop_recording_command(), _mode_delay_ms * 2);
}
_state = State::READY;
} else {
@ -389,7 +390,7 @@ void AP_RunCam::handle_ready(Event ev)
}
break;
case Event::START_RECORDING:
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_START_RECORDING, _mode_delay_ms);
simulate_camera_button(start_recording_command(), _mode_delay_ms);
_state = State::VIDEO_RECORDING;
break;
case Event::NONE:
@ -411,14 +412,14 @@ void AP_RunCam::handle_recording(Event ev)
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, _mode_delay_ms);
simulate_camera_button(stop_recording_command(), _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, _mode_delay_ms);
simulate_camera_button(stop_recording_command(), _mode_delay_ms);
_state = State::READY;
break;
case Event::NONE:
@ -435,11 +436,9 @@ void AP_RunCam::handle_recording(Event ev)
// handle the in_menu state
void AP_RunCam::handle_in_menu(Event ev)
{
if (has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE)) {
if (has_5_key_OSD()) {
handle_5_key_simulation_process(ev);
} else if (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)) {
} else if (has_2_key_OSD()) {
// otherwise the simpler 2 key OSD simulation, requires firmware 2.4.4 on the split micro
handle_2_key_simulation_process(ev);
}
@ -474,7 +473,7 @@ AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const
} else if (roll == RC_Channel::AuxSwitchPos::LOW) {
result = Event::IN_MENU_EXIT;
} else if (yaw == RC_Channel::AuxSwitchPos::MIDDLE && pitch == RC_Channel::AuxSwitchPos::MIDDLE && roll == RC_Channel::AuxSwitchPos::HIGH) {
if (has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE)) {
if (has_5_key_OSD()) {
result = Event::IN_MENU_RIGHT;
} else {
result = Event::IN_MENU_ENTER;
@ -608,7 +607,7 @@ void AP_RunCam::exit_2_key_osd_menu()
enable_osd();
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);
simulate_camera_button(start_recording_command(), _mode_delay_ms);
_state = State::VIDEO_RECORDING;
} else {
_state = State::READY;
@ -705,6 +704,24 @@ void AP_RunCam::handle_5_key_simulation_response(const Request& request)
_waiting_device_response = false;
}
// command to stop recording
AP_RunCam::ControlOperation AP_RunCam::start_recording_command() const {
if (DeviceType(_cam_type.get()) == DeviceType::Split4k) {
return ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_POWER_BTN;
} else {
return ControlOperation::RCDEVICE_PROTOCOL_CHANGE_START_RECORDING;
}
}
// command to stop recording
AP_RunCam::ControlOperation AP_RunCam::stop_recording_command() const {
if (DeviceType(_cam_type.get()) == DeviceType::Split4k) {
return ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_POWER_BTN;
} else {
return ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING;
}
}
// process a response from the serial port
void AP_RunCam::receive()
{
@ -937,10 +954,7 @@ void AP_RunCam::parse_device_info(const Request& request)
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);
has_5_key_OSD() ? 5 : has_2_key_OSD() ? 2 : 0);
} else {
// nothing as as nothing does
gcs().send_text(MAV_SEVERITY_WARNING, "RunCam device not found\n");

View File

@ -61,7 +61,8 @@ public:
enum class DeviceType {
Disabled = 0,
SplitMicro = 1, // video support only
Split = 2 // camera and video support
Split = 2, // camera and video support
Split4k = 3 // video support only + 5key OSD
};
// operation of camera button simulation
@ -122,6 +123,11 @@ private:
FEATURES_OVERRIDE = (1 << 14)
};
const uint16_t RCDEVICE_PROTOCOL_FEATURE_2_KEY_OSD =
uint16_t(Feature::RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE)
| uint16_t(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON)
| uint16_t(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON);
// camera control commands
enum class Command {
RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO = 0x00,
@ -211,7 +217,7 @@ private:
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 = 2;
static const uint8_t RUNCAM_MAX_DEVICE_TYPES = 3;
// supported features, usually probed from the device
AP_Int16 _features;
@ -375,6 +381,9 @@ private:
void handle_5_key_simulation_process(Event ev);
// handle a response
void handle_5_key_simulation_response(const Request& request);
// commands to start and stop recording
ControlOperation start_recording_command() const;
ControlOperation stop_recording_command() const;
// process a response from the serial port
void receive();
// empty the receive side of the serial port
@ -407,6 +416,15 @@ private:
bool camera_ready() const;
// whether or not the requested feature is supported
bool has_feature(const Feature feature) const { return _features.get() & uint16_t(feature); }
// input mode
bool has_2_key_OSD() const {
return (_features.get() & RCDEVICE_PROTOCOL_FEATURE_2_KEY_OSD) == RCDEVICE_PROTOCOL_FEATURE_2_KEY_OSD;
}
bool has_5_key_OSD() const {
// RunCam Hybrid lies about supporting both 5-key and 2-key
return !has_2_key_OSD() && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE);
}
// whether or not we can arm
bool is_arming_prevented() const { return _in_menu > _menu_enter_level; }
// error handler for OSD simulation