mirror of https://github.com/ArduPilot/ardupilot
AP_Camera: create and use an option_is_enabled
This commit is contained in:
parent
d859e9aa55
commit
b86380bbc6
|
@ -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)) {
|
||||
|
|
|
@ -37,9 +37,12 @@ public:
|
|||
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() {};
|
||||
|
|
Loading…
Reference in New Issue