Skip to content

Commit

Permalink
AP_Camera: add CAMx_OPTION support for start/stop recording when arm/…
Browse files Browse the repository at this point in the history
…disarm
  • Loading branch information
khanasif786 committed Jul 2, 2023
1 parent 670873d commit bf03688
Show file tree
Hide file tree
Showing 7 changed files with 33 additions and 2 deletions.
7 changes: 7 additions & 0 deletions libraries/AP_Camera/AP_Camera_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#if AP_CAMERA_ENABLED
#include <GCS_MAVLink/GCS.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_DAL/AP_DAL.h>

extern const AP_HAL::HAL& hal;

Expand All @@ -16,6 +17,12 @@ AP_Camera_Backend::AP_Camera_Backend(AP_Camera &frontend, AP_Camera_Params &para
// update - should be called at 50hz
void AP_Camera_Backend::update()
{
if (_params.options == 1 && AP::dal().get_armed()) {
this->record_video(true);
} else if (_params.options == 1 && !AP::dal().get_armed()) {
this->record_video(false);
}

// try to take picture if pending
if (trigger_pending) {
take_picture();
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Camera/AP_Camera_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,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 is_recording = false; // true if recording is on
};

#endif // AP_CAMERA_ENABLED
6 changes: 5 additions & 1 deletion libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,10 @@ bool AP_Camera_MAVLinkCamV2::record_video(bool start_recording)
return false;
}

if ((start_recording & is_recording) == 1U) {
return false;
}

// prepare and send message
mavlink_command_long_t pkt {};

Expand All @@ -60,7 +64,7 @@ bool AP_Camera_MAVLinkCamV2::record_video(bool start_recording)
}

_link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt);

is_recording = start_recording;
return true;
}

Expand Down
9 changes: 8 additions & 1 deletion libraries/AP_Camera/AP_Camera_Mount.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,16 @@ bool AP_Camera_Mount::trigger_pic()
// start_recording should be true to start recording, false to stop recording
bool AP_Camera_Mount::record_video(bool start_recording)
{
if ((start_recording & is_recording) == 1U) {
return false;
}

AP_Mount* mount = AP::mount();
if (mount != nullptr) {
return mount->record_video(0, start_recording);
if (mount->record_video(0, start_recording)) {
is_recording = start_recording;
return true;
}
}
return false;
}
Expand Down
7 changes: 7 additions & 0 deletions libraries/AP_Camera/AP_Camera_Params.cpp
Original file line number Diff line number Diff line change
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
// @Values: 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
Original file line number Diff line number Diff line change
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
4 changes: 4 additions & 0 deletions libraries/AP_Camera/AP_Camera_Scripting.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,11 @@ bool AP_Camera_Scripting::trigger_pic()
// set start_recording = true to start record, false to stop recording
bool AP_Camera_Scripting::record_video(bool start_recording)
{
if ((start_recording & is_recording) == 1U) {
return false;
}
_cam_state.recording_video = start_recording;
is_recording = start_recording;
return true;
}

Expand Down

0 comments on commit bf03688

Please sign in to comment.