Browse Source

AP_Camera: add RunCam TYPE and CONTROL options for menu/OSD control

zr-v5.1
Andy Piper 5 years ago committed by Andrew Tridgell
parent
commit
7ad9ce0a01
  1. 73
      libraries/AP_Camera/AP_RunCam.cpp
  2. 47
      libraries/AP_Camera/AP_RunCam.h

73
libraries/AP_Camera/AP_RunCam.cpp

@ -49,6 +49,20 @@ const AP_Param::GroupInfo AP_RunCam::var_info[] = { @@ -49,6 +49,20 @@ const AP_Param::GroupInfo AP_RunCam::var_info[] = {
// @User: Advanced
AP_GROUPINFO("BTN_DELAY", 3, AP_RunCam, _button_delay_ms, 300),
// @Param: TYPE
// @DisplayName: RunCam device type
// @Description: RunCam deviee type used to determine OSD menu structure and shutter options
// @Values: 0:RunCam Split
// @User: Advanced
AP_GROUPINFO("TYPE", 4, AP_RunCam, _cam_type, 0),
// @Param: CONTROL
// @DisplayName: RunCam control option
// @Description: Specifies the allowed actions required to enter the OSD menu.
// @Bitmask: 0:Stick roll right, 1:3-way switch, 2: 2-way switch
// @User: Advanced
AP_GROUPINFO("CONTROL", 5, AP_RunCam, _cam_control_option, uint8_t(ControlOption::STICK_YAW_RIGHT)),
AP_GROUPEND
};
@ -78,11 +92,11 @@ static const uint8_t RUNCAM_OSD_MENU_DEPTH = 2; @@ -78,11 +92,11 @@ static const uint8_t RUNCAM_OSD_MENU_DEPTH = 2;
static const uint32_t RUNCAM_INIT_INTERVAL_MS = 500;
static const uint32_t RUNCAM_OSD_UPDATE_INTERVAL_MS = 100; // 10Hz
// these are correct for the runcam split micro v2.4.4, others may vary
// Video, Image, TV-OUT, Micro SD Card, General
static const uint8_t RUNCAM_TOP_MENU_LENGTH = 6;
uint8_t AP_RunCam::_sub_menu_lengths[RUNCAM_NUM_SUB_MENUS] = {
5, 8, 3, 3, 7
// menu structures of runcam devices
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 }}
};
AP_RunCam::AP_RunCam()
@ -92,6 +106,7 @@ AP_RunCam::AP_RunCam() @@ -92,6 +106,7 @@ 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);
}
// init the runcam device by finding a serial device configured for the RunCam protocol
@ -132,12 +147,41 @@ bool AP_RunCam::simulate_camera_button(const ControlOperation operation) @@ -132,12 +147,41 @@ bool AP_RunCam::simulate_camera_button(const ControlOperation operation)
void AP_RunCam::start_recording() {
debug("start recording\n");
_video_recording = true;
if (_cam_control_option & uint8_t(ControlOption::THREE_POS_SWITCH) && _osd_option == OSDOption::OPTION) {
_osd_option = OSDOption::EXIT;
}
}
// stop the video
void AP_RunCam::stop_recording() {
debug("stop recording\n");
_video_recording = false;
if (_cam_control_option & uint8_t(ControlOption::THREE_POS_SWITCH) && _osd_option == OSDOption::OPTION) {
_osd_option = OSDOption::EXIT;
}
}
// enter the OSD menu
void AP_RunCam::enter_osd()
{
if (_cam_control_option & uint8_t(ControlOption::TWO_POS_SWITCH)) {
_osd_option = OSDOption::ENTER;
}
}
// exit the OSD menu
void AP_RunCam::exit_osd()
{
if (_cam_control_option & uint8_t(ControlOption::TWO_POS_SWITCH)) {
_osd_option = OSDOption::EXIT;
}
}
// OSD control determined by camera options
void AP_RunCam::osd_option() {
if (_cam_control_option & uint8_t(ControlOption::THREE_POS_SWITCH)) {
_osd_option = OSDOption::OPTION;
}
}
// input update loop
@ -294,6 +338,7 @@ void AP_RunCam::handle_ready(Event ev) @@ -294,6 +338,7 @@ void AP_RunCam::handle_ready(Event ev)
_top_menu_pos = -1;
_sub_menu_pos = 0;
_state = State::ENTERING_MENU;
_osd_option = OSDOption::NONE;
break;
case Event::START_RECORDING:
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_START_RECORDING);
@ -322,6 +367,7 @@ void AP_RunCam::handle_recording(Event ev) @@ -322,6 +367,7 @@ void AP_RunCam::handle_recording(Event ev)
set_mode_change_timeout();
_sub_menu_pos = 0;
_top_menu_pos = -1;
_osd_option = OSDOption::NONE;
_state = State::ENTERING_MENU;
break;
case Event::STOP_RECORDING:
@ -373,7 +419,8 @@ AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const @@ -373,7 +419,8 @@ AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const
result = Event::EXIT_MENU;
}
if (throttle == RC_Channel::MIDDLE && yaw == RC_Channel::HIGH
&& pitch == RC_Channel::MIDDLE && roll == RC_Channel::MIDDLE) {
&& pitch == RC_Channel::MIDDLE && roll == RC_Channel::MIDDLE
&& _cam_control_option & uint8_t(ControlOption::STICK_YAW_RIGHT)) {
result = Event::ENTER_MENU;
} else if (roll == RC_Channel::LOW) {
result = Event::IN_MENU_EXIT;
@ -383,6 +430,10 @@ AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const @@ -383,6 +430,10 @@ AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const
result = Event::IN_MENU_UP;
} else if (pitch == RC_Channel::LOW) {
result = Event::IN_MENU_DOWN;
} else if (_osd_option == OSDOption::ENTER || _osd_option == OSDOption::OPTION) {
result = Event::ENTER_MENU;
} else if (_osd_option == OSDOption::EXIT) {
result = Event::EXIT_MENU;
} else if (_state == State::READY && _video_recording) {
// generate an event if we are in the wrong recording state
result = Event::START_RECORDING;
@ -416,6 +467,7 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev) @@ -416,6 +467,7 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev)
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_MODE);
set_mode_change_timeout();
_state = State::EXITING_MENU;
_osd_option = OSDOption::NONE;
} else {
exit_2_key_osd_menu();
}
@ -425,10 +477,10 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev) @@ -425,10 +477,10 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev)
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN); // change setting
set_button_press_timeout();
// in a sub-menu and save-and-exit was selected
if (_in_menu > 1 && _sub_menu_pos == (_sub_menu_lengths[_top_menu_pos] - 1)) {
if (_in_menu > 1 && _sub_menu_pos == (get_sub_menu_length(_top_menu_pos) - 1)) {
_in_menu--;
// in the top-menu and save-and-exit was selected
} else if (_in_menu == 1 && _top_menu_pos == (RUNCAM_TOP_MENU_LENGTH - 1)) {
} else if (_in_menu == 1 && _top_menu_pos == (get_top_menu_length() - 1)) {
_in_menu--;
_state = State::EXITING_MENU;
} else {
@ -442,10 +494,10 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev) @@ -442,10 +494,10 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev)
set_button_press_timeout();
if (_in_menu > 1) {
// in a sub-menu, keep track of the selected position
_sub_menu_pos = (_sub_menu_pos + 1) % _sub_menu_lengths[_top_menu_pos];
_sub_menu_pos = (_sub_menu_pos + 1) % get_sub_menu_length(_top_menu_pos);
} else {
// in the top-menu, keep track of the selected position
_top_menu_pos = (_top_menu_pos + 1) % RUNCAM_TOP_MENU_LENGTH;
_top_menu_pos = (_top_menu_pos + 1) % get_top_menu_length();
}
break;
@ -518,6 +570,7 @@ void AP_RunCam::handle_5_key_simulation_process(Event ev) @@ -518,6 +570,7 @@ void AP_RunCam::handle_5_key_simulation_process(Event ev)
break;
case Event::EXIT_MENU:
_osd_option = OSDOption::NONE;
if (_in_menu > 0) {
// turn built-in OSD back on
enable_osd();

47
libraries/AP_Camera/AP_RunCam.h

@ -66,6 +66,13 @@ public: @@ -66,6 +66,13 @@ public:
UNKNOWN_CAMERA_OPERATION = 0xFF
};
// control for OSD menu entry
enum class ControlOption {
STICK_YAW_RIGHT = 0x01,
THREE_POS_SWITCH = 0x02,
TWO_POS_SWITCH = 0x04
};
// initialize the RunCam driver
void init();
// camera button simulation
@ -74,6 +81,12 @@ public: @@ -74,6 +81,12 @@ public:
void start_recording();
// stop the video
void stop_recording();
// enter the OSD menu
void enter_osd();
// exit the OSD menu
void exit_osd();
// OSD control determined by camera options
void osd_option();
// update loop
void update();
// Check whether arming is allowed
@ -161,8 +174,18 @@ private: @@ -161,8 +174,18 @@ private:
START_RECORDING
};
enum class OSDOption {
NONE,
ENTER,
EXIT,
OPTION
};
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;
// supported features, usually probed from the device
AP_Int16 _features;
@ -174,6 +197,10 @@ private: @@ -174,6 +197,10 @@ private:
AP_Int32 _boot_delay_ms;
// delay time to make sure a button press has been activated
AP_Int32 _button_delay_ms;
// runcam type/firmware revision
AP_Int8 _cam_type;
// runcam control options
AP_Int8 _cam_control_option;
// video on/off
bool _video_recording = true;
@ -193,6 +220,8 @@ private: @@ -193,6 +220,8 @@ private:
bool _button_pressed;
// 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;
// OSD state machine: current selection in the top menu
@ -251,6 +280,24 @@ private: @@ -251,6 +280,24 @@ private:
static Length _expected_responses_length[RUNCAM_NUM_EXPECTED_RESPONSES];
} _pending_request;
// menu structure of the runcam device
struct Menu {
uint8_t _top_menu_length;
uint8_t _sub_menu_lengths[RUNCAM_MAX_MENU_LENGTH];
};
static Menu _menus[RUNCAM_MAX_DEVICE_TYPES];
// return the length of the top menu
uint8_t get_top_menu_length() const {
return _menus[_cam_type]._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;

Loading…
Cancel
Save