Skip to content

Commit

Permalink
AP_Camera: fixed build on navio
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Dec 30, 2019
1 parent f10adeb commit f1dfb2e
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
8 changes: 4 additions & 4 deletions libraries/AP_Camera/AP_RunCam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ const AP_Param::GroupInfo AP_RunCam::var_info[] = {
// @DisplayName: RunCam device type
// @Description: RunCam deviee type used to determine OSD menu structure and shutter options
// @Values: 0:Disabled, 1:RunCam Split
AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceType::DISABLED), AP_PARAM_FLAG_ENABLE),
AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceType::Disabled), AP_PARAM_FLAG_ENABLE),

// @Param: FEATURES
// @DisplayName: RunCam features available
Expand Down Expand Up @@ -128,9 +128,9 @@ void AP_RunCam::init()
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::Split));
}
if (_cam_type.get() == int8_t(DeviceType::DISABLED)) {
if (_cam_type.get() == int8_t(DeviceType::Disabled)) {
uart = nullptr;
return;
}
Expand Down Expand Up @@ -198,7 +198,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(DeviceType::Disabled)) {
return;
}

Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Camera/AP_RunCam.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,8 @@ class AP_RunCam
}

enum class DeviceType {
DISABLED = 0,
SPLIT = 1,
Disabled = 0,
Split = 1,
};

// operation of camera button simulation
Expand Down

0 comments on commit f1dfb2e

Please sign in to comment.