diff --git a/libraries/AP_Camera/AP_Camera_Backend.cpp b/libraries/AP_Camera/AP_Camera_Backend.cpp index 4781c4180721a..fafe4546aa253 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.cpp +++ b/libraries/AP_Camera/AP_Camera_Backend.cpp @@ -17,11 +17,13 @@ AP_Camera_Backend::AP_Camera_Backend(AP_Camera &frontend, AP_Camera_Params ¶ // update - should be called at 50hz void AP_Camera_Backend::update() { - // Check CAMx_OPTIONS and start/stop recording based on arm/disarm - if (_params.options.get() & CAMOPTIONS::REC_ARM_DISARM) { + // Check camera options and start/stop recording based on arm/disarm + if ((_params.options.get() & (uint8_t)Options::RecordWhileArmed) != 0) { if (hal.util->get_soft_armed() != last_is_armed) { last_is_armed = hal.util->get_soft_armed(); - record_video(last_is_armed); + if (!record_video(last_is_armed)) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Camera: failed to %s recording", last_is_armed ? "start" : "stop"); + } } } diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index a6b4c8a60a320..b60e06d4dcd14 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -36,8 +36,9 @@ class AP_Camera_Backend /* Do not allow copies */ CLASS_NO_COPY(AP_Camera_Backend); - enum CAMOPTIONS { - REC_ARM_DISARM = 0, // Recording start/stop on Arm/Disarm + // camera options parameter values + enum class Options : int8_t { + RecordWhileArmed = (1 << 0U) }; // init - performs any required initialisation