Skip to content

Commit

Permalink
AP_Camera: address review comments
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per committed Nov 27, 2024
1 parent 098da39 commit f357ac4
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 12 deletions.
2 changes: 1 addition & 1 deletion libraries/AP_Camera/AP_Camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -986,7 +986,7 @@ void AP_Camera::convert_params()
}

_params[1].type.set_and_save(rc_type);
#endif
#endif // AP_CAMERA_RUNCAM_ENABLED

// convert CAM_DURATION (in deci-seconds) to CAM1_DURATION (in seconds)
int8_t cam_duration = 0;
Expand Down
20 changes: 10 additions & 10 deletions libraries/AP_Camera/AP_RunCam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ const AP_Param::GroupInfo AP_RunCam::var_info[] = {
// @DisplayName: RunCam device type
// @Description: RunCam device 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, 4:RunCam Hybrid/RunCam Thumb Pro, 5:Runcam 2 4k
AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceType::SplitMicro), AP_PARAM_FLAG_ENABLE),
AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceModel::SplitMicro), AP_PARAM_FLAG_ENABLE),

// @Param: FEATURES
// @DisplayName: RunCam features available
Expand Down Expand Up @@ -154,10 +154,10 @@ void AP_RunCam::init()
users while still enabling parameters to be hidden for users
without a RunCam
*/
_cam_type.set_default(int8_t(DeviceType::SplitMicro));
_cam_type.set_default(int8_t(DeviceModel::SplitMicro));
AP_Param::invalidate_count();
}
if (_cam_type.get() == int8_t(DeviceType::Disabled)) {
if (_cam_type.get() == int8_t(DeviceModel::Disabled)) {
uart = nullptr;
return;
}
Expand All @@ -167,7 +167,7 @@ void AP_RunCam::init()
}

// Split and Runcam 2 4k requires two mode presses to get into the menu
if (_cam_type.get() == int8_t(DeviceType::Split) || _cam_type.get() == int8_t(DeviceType::Run24k)) {
if (_cam_type.get() == int8_t(DeviceModel::Split) || _cam_type.get() == int8_t(DeviceModel::Run24k)) {
_menu_enter_level = -1;
_in_menu = -1;
}
Expand Down Expand Up @@ -232,7 +232,7 @@ void AP_RunCam::osd_option() {
// input update loop
void AP_RunCam::update()
{
if (uart == nullptr || _cam_type.get() == int8_t(DeviceType::Disabled)) {
if (uart == nullptr || _cam_type.get() == int8_t(DeviceModel::Disabled)) {
return;
}

Expand Down Expand Up @@ -562,12 +562,12 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev)

case Event::IN_MENU_ENTER:
// in a sub-menu and save-and-exit was selected
if (_in_menu > 1 && get_top_menu_length() > 0 && _sub_menu_pos == (get_sub_menu_length(_top_menu_pos) - 1) && DeviceType(_cam_type.get()) != DeviceType::Run24k) {
if (_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) {
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN, _button_delay_ms);
_sub_menu_pos = 0;
_in_menu--;
// in the top-menu and save-and-exit was selected
} else if (_in_menu == 1 && get_top_menu_length() > 0 && _top_menu_pos == (get_top_menu_length() - 1) && DeviceType(_cam_type.get()) != DeviceType::Run24k) {
} else if (_in_menu == 1 && get_top_menu_length() > 0 && _top_menu_pos == (get_top_menu_length() - 1) && DeviceModel(_cam_type.get()) != DeviceModel::Run24k) {
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_WIFI_BTN, _mode_delay_ms);
_in_menu--;
_state = State::EXITING_MENU;
Expand Down Expand Up @@ -723,7 +723,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 || DeviceType(_cam_type.get()) == DeviceType::Hybrid || DeviceType(_cam_type.get()) == DeviceType::Run24k) {
if (DeviceModel(_cam_type.get()) == DeviceModel::Split4k || DeviceModel(_cam_type.get()) == DeviceModel::Hybrid || DeviceModel(_cam_type.get()) == DeviceModel::Run24k) {
return ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_POWER_BTN;
} else {
return ControlOperation::RCDEVICE_PROTOCOL_CHANGE_START_RECORDING;
Expand All @@ -732,7 +732,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 || DeviceType(_cam_type.get()) == DeviceType::Hybrid || DeviceType(_cam_type.get()) == DeviceType::Run24k) {
if (DeviceModel(_cam_type.get()) == DeviceModel::Split4k || DeviceModel(_cam_type.get()) == DeviceModel::Hybrid || DeviceModel(_cam_type.get()) == DeviceModel::Run24k) {
return ControlOperation::RCDEVICE_PROTOCOL_SIMULATE_POWER_BTN;
} else {
return ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING;
Expand Down Expand Up @@ -1091,7 +1091,7 @@ bool AP_RunCam::trigger_pic() {
void AP_RunCam::send_camera_information(mavlink_channel_t chan) const
{
// exit immediately if not initialised
if (!camera_ready()) {
if (!camera_ready() || _cam_type.get() == 0 || _cam_type.get() > ARRAY_SIZE(_models)) {
return;
}

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Camera/AP_RunCam.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ class AP_RunCam : public AP_Camera_Backend
return _singleton;
}

enum class DeviceType {
enum class DeviceModel {
Disabled = 0,
SplitMicro = 1, // video support only
Split = 2, // camera and video support
Expand Down

0 comments on commit f357ac4

Please sign in to comment.