diff --git a/libraries/AP_Camera/AP_Camera_Backend.cpp b/libraries/AP_Camera/AP_Camera_Backend.cpp index 516d418684bef..4c2a165836468 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.cpp +++ b/libraries/AP_Camera/AP_Camera_Backend.cpp @@ -22,7 +22,7 @@ AP_Camera_Backend::AP_Camera_Backend(AP_Camera &frontend, AP_Camera_Params ¶ void AP_Camera_Backend::update() { // Check camera options and start/stop recording based on arm/disarm - if ((_params.options.get() & (uint8_t)Options::RecordWhileArmed) != 0) { + if (option_is_enabled(Option::RecordWhileArmed)) { if (hal.util->get_soft_armed() != last_is_armed) { last_is_armed = hal.util->get_soft_armed(); if (!record_video(last_is_armed)) { diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index 41d383527ec4b..6c5543cf826a7 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -37,9 +37,12 @@ class AP_Camera_Backend CLASS_NO_COPY(AP_Camera_Backend); // camera options parameter values - enum class Options : int8_t { + enum class Option : uint8_t { RecordWhileArmed = (1 << 0U) }; + bool option_is_enabled(Option option) const { + return ((uint8_t)_params.options.get() & (uint8_t)option) != 0; + } // init - performs any required initialisation virtual void init() {};