Browse Source

AP_Camera: fixed build on navio

zr-v5.1
Andrew Tridgell 5 years ago
parent
commit
f1dfb2e401
  1. 8
      libraries/AP_Camera/AP_RunCam.cpp
  2. 4
      libraries/AP_Camera/AP_RunCam.h

8
libraries/AP_Camera/AP_RunCam.cpp

@ -34,7 +34,7 @@ const AP_Param::GroupInfo AP_RunCam::var_info[] = { @@ -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
@ -128,9 +128,9 @@ void AP_RunCam::init() @@ -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;
}
@ -198,7 +198,7 @@ void AP_RunCam::osd_option() { @@ -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;
}

4
libraries/AP_Camera/AP_RunCam.h

@ -56,8 +56,8 @@ public: @@ -56,8 +56,8 @@ public:
}
enum class DeviceType {
DISABLED = 0,
SPLIT = 1,
Disabled = 0,
Split = 1,
};
// operation of camera button simulation

Loading…
Cancel
Save