Skip to content

Commit

Permalink
AP_Camera: fix video recording while armed
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 authored and peterbarker committed Feb 15, 2024
1 parent 2263dce commit a16d71c
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 5 deletions.
8 changes: 5 additions & 3 deletions libraries/AP_Camera/AP_Camera_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,13 @@ AP_Camera_Backend::AP_Camera_Backend(AP_Camera &frontend, AP_Camera_Params &para
// 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");
}
}
}

Expand Down
5 changes: 3 additions & 2 deletions libraries/AP_Camera/AP_Camera_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit a16d71c

Please sign in to comment.