AP_Camera: support RunCam Hybrid correctly

This commit is contained in:
Andy Piper 2021-06-02 18:27:47 +01:00 committed by Andrew Tridgell
parent f2b7d44772
commit cf257074c6
2 changed files with 8 additions and 6 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, 3:RunCam Split4 4k
// @Values: 0:Disabled, 1:RunCam Split Micro/RunCam with UART, 2:RunCam Split, 3:RunCam Split4 4k, 4:RunCam Hybrid
AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceType::Disabled), AP_PARAM_FLAG_ENABLE),
// @Param: FEATURES
@ -113,6 +113,7 @@ AP_RunCam::Menu AP_RunCam::_menus[RUNCAM_MAX_DEVICE_TYPES] = {
{ 6, { 5, 8, 3, 3, 7 }}, // SplitMicro
{ 0, { 0 }}, // Split
{ 6, { 4, 10, 3, 3, 7 }}, // Split4 4K
{ 1, { 0 }}, // Hybrid, simple mode switch
};
AP_RunCam::AP_RunCam()
@ -554,7 +555,7 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev)
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN, _mode_delay_ms);
_in_menu--;
_state = State::EXITING_MENU;
} else {
} else if (_top_menu_pos >= 0 && get_sub_menu_length(_top_menu_pos) > 0) {
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN, _button_delay_ms);
_in_menu = MIN(_in_menu + 1, RUNCAM_OSD_MENU_DEPTH);
}
@ -706,7 +707,7 @@ void AP_RunCam::handle_5_key_simulation_response(const Request& request)
// command to start recording
AP_RunCam::ControlOperation AP_RunCam::start_recording_command() const {
if (DeviceType(_cam_type.get()) == DeviceType::Split4k) {
if (DeviceType(_cam_type.get()) == DeviceType::Split4k || DeviceType(_cam_type.get()) == DeviceType::Hybrid) {
return ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_POWER_BTN;
} else {
return ControlOperation::RCDEVICE_PROTOCOL_CHANGE_START_RECORDING;
@ -715,7 +716,7 @@ AP_RunCam::ControlOperation AP_RunCam::start_recording_command() const {
// command to stop recording
AP_RunCam::ControlOperation AP_RunCam::stop_recording_command() const {
if (DeviceType(_cam_type.get()) == DeviceType::Split4k) {
if (DeviceType(_cam_type.get()) == DeviceType::Split4k || DeviceType(_cam_type.get()) == DeviceType::Hybrid) {
return ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_POWER_BTN;
} else {
return ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING;

View File

@ -62,7 +62,8 @@ public:
Disabled = 0,
SplitMicro = 1, // video support only
Split = 2, // camera and video support
Split4k = 3 // video support only + 5key OSD
Split4k = 3, // video support only + 5key OSD
Hybrid = 4, // video support + QR mode switch
};
// operation of camera button simulation
@ -217,7 +218,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 = 3;
static const uint8_t RUNCAM_MAX_DEVICE_TYPES = 4;
// supported features, usually probed from the device
AP_Int16 _features;