Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Camera: add CAMx_OPTION support for start/stop recording when arm/Disarm #24193

Merged
merged 1 commit into from Jul 4, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
8 changes: 8 additions & 0 deletions libraries/AP_Camera/AP_Camera_Backend.cpp
Expand Up @@ -16,6 +16,14 @@ 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) {
if (hal.util->get_soft_armed() != last_is_armed) {
last_is_armed = hal.util->get_soft_armed();
record_video(last_is_armed);
}
}

// try to take picture if pending
if (trigger_pending) {
take_picture();
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_Camera/AP_Camera_Backend.h
Expand Up @@ -36,6 +36,11 @@ class AP_Camera_Backend
/* Do not allow copies */
CLASS_NO_COPY(AP_Camera_Backend);

enum CAMOPTIONS {
NONE = 0,
REC_ARM_DISARM = 1, // Recording start/stop on Arm/Disarm
};

// init - performs any required initialisation
virtual void init() {};

Expand Down Expand Up @@ -138,6 +143,7 @@ class AP_Camera_Backend
uint32_t last_photo_time_ms; // system time that photo was last taken
Location last_location; // Location that last picture was taken at (used for trigg_dist calculation)
uint16_t image_index; // number of pictures taken since boot
bool last_is_armed; // stores last arm/disarm state. true if it was armed lastly
};

#endif // AP_CAMERA_ENABLED
7 changes: 7 additions & 0 deletions libraries/AP_Camera/AP_Camera_Params.cpp
Expand Up @@ -74,6 +74,13 @@ const AP_Param::GroupInfo AP_Camera_Params::var_info[] = {
// @User: Standard
AP_GROUPINFO("_FEEDBAK_POL", 9, AP_Camera_Params, feedback_polarity, 1),

// @Param: _OPTIONS
// @DisplayName: Camera options
// @Description: Camera options bitmask
// @Bitmask: 0:None,1: Recording Starts at arming and stops at disarming
// @User: Standard
AP_GROUPINFO("_OPTIONS", 10, AP_Camera_Params, options, 0),

AP_GROUPEND

};
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Camera/AP_Camera_Params.h
Expand Up @@ -21,6 +21,7 @@ class AP_Camera_Params {
AP_Float trigg_dist; // distance between trigger points (meters)
AP_Int8 relay_on; // relay value to trigger camera
AP_Float interval_min; // minimum time (in seconds) between shots required by camera
AP_Int8 options; // whether to start recording when armed and stop when disarmed

// pin number for accurate camera feedback messages
AP_Int8 feedback_pin;
Expand Down