mirror of https://github.com/ArduPilot/ardupilot
AP_Camera: fix video recording while armed
This commit is contained in:
parent
23e69995af
commit
885dd15cd1
|
@ -17,11 +17,13 @@ AP_Camera_Backend::AP_Camera_Backend(AP_Camera &frontend, AP_Camera_Params ¶
|
||||||
// update - should be called at 50hz
|
// update - should be called at 50hz
|
||||||
void AP_Camera_Backend::update()
|
void AP_Camera_Backend::update()
|
||||||
{
|
{
|
||||||
// Check CAMx_OPTIONS and start/stop recording based on arm/disarm
|
// Check camera options and start/stop recording based on arm/disarm
|
||||||
if (_params.options.get() & CAMOPTIONS::REC_ARM_DISARM) {
|
if ((_params.options.get() & (uint8_t)Options::RecordWhileArmed) != 0) {
|
||||||
if (hal.util->get_soft_armed() != last_is_armed) {
|
if (hal.util->get_soft_armed() != last_is_armed) {
|
||||||
last_is_armed = hal.util->get_soft_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");
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -36,8 +36,9 @@ public:
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
CLASS_NO_COPY(AP_Camera_Backend);
|
CLASS_NO_COPY(AP_Camera_Backend);
|
||||||
|
|
||||||
enum CAMOPTIONS {
|
// camera options parameter values
|
||||||
REC_ARM_DISARM = 0, // Recording start/stop on Arm/Disarm
|
enum class Options : int8_t {
|
||||||
|
RecordWhileArmed = (1 << 0U)
|
||||||
};
|
};
|
||||||
|
|
||||||
// init - performs any required initialisation
|
// init - performs any required initialisation
|
||||||
|
|
Loading…
Reference in New Issue