Skip to content

Commit

Permalink
AP_Camera: add time based triggering support
Browse files Browse the repository at this point in the history
  • Loading branch information
khanasif786 committed Aug 2, 2023
1 parent 7238c60 commit c7801c7
Show file tree
Hide file tree
Showing 4 changed files with 51 additions and 7 deletions.
18 changes: 14 additions & 4 deletions libraries/AP_Camera/AP_Camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,17 @@ void AP_Camera::take_picture()
primary->take_picture();
}

// take a picture
void AP_Camera::take_multiple_pictures(float time_interval, int16_t total_num)
{
WITH_SEMAPHORE(_rsem);

if (primary == nullptr) {
return;
}
primary->take_multiple_pictures(time_interval, total_num);
}

// start/stop recording video
// start_recording should be true to start recording, false to stop recording
bool AP_Camera::record_video(bool start_recording)
Expand Down Expand Up @@ -240,10 +251,9 @@ MAV_RESULT AP_Camera::handle_command_long(const mavlink_command_long_t &packet)
return MAV_RESULT_DENIED;
case MAV_CMD_IMAGE_START_CAPTURE:
if (!is_zero(packet.param2) || !is_equal(packet.param3, 1.0f) || !is_zero(packet.param4)) {
// time interval is not supported
// multiple image capture is not supported
// capture sequence number is not supported
return MAV_RESULT_UNSUPPORTED;
// Its a multiple picture request
int16_t(packet.param3) == 0 ? take_multiple_pictures(packet.param2, -1) : take_multiple_pictures(packet.param2, packet.param3);
return MAV_RESULT_ACCEPTED;
}
take_picture();
return MAV_RESULT_ACCEPTED;
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_Camera/AP_Camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,10 @@ class AP_Camera {
void take_picture();
void take_picture(uint8_t instance);

// take multiple pictures
// total_num is number of pictures to be taken, -1 means capture forever
void take_multiple_pictures(float time_interval, int16_t total_num);

// start/stop recording video
// start_recording should be true to start recording, false to stop recording
bool record_video(bool start_recording);
Expand Down
24 changes: 22 additions & 2 deletions libraries/AP_Camera/AP_Camera_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,19 @@ void AP_Camera_Backend::update()
// check feedback pin
check_feedback();

// time based triggering
// if time and distance trigerring both are enabled then we only do time based triggering
if (time_interval_settings.enabled) {
uint32_t interval_ms = AP_HAL::millis() - last_picture_time_ms;
if ((interval_ms > time_interval_settings.time_interval*1000.0f) && take_picture()) {
// we don't execute this condition if num_remaining is -1 i.e. capture forever
if ((time_interval_settings.num_remaining > 0) && (--time_interval_settings.num_remaining == 0)) {
time_interval_settings.enabled = false;
}
}
return;
}

// implement trigger distance
if (!is_positive(_params.trigg_dist)) {
last_location.lat = 0;
Expand Down Expand Up @@ -86,7 +99,7 @@ bool AP_Camera_Backend::take_picture()

// check minimum time interval since last picture taken
uint32_t now_ms = AP_HAL::millis();
if (now_ms - last_photo_time_ms < (uint32_t)(_params.interval_min * 1000)) {
if (now_ms - last_picture_time_ms < (uint32_t)(_params.interval_min * 1000)) {
trigger_pending = true;
return false;
}
Expand All @@ -96,7 +109,7 @@ bool AP_Camera_Backend::take_picture()
// trigger actually taking picture and update image count
if (trigger_pic()) {
image_index++;
last_photo_time_ms = now_ms;
last_picture_time_ms = now_ms;
IGNORE_RETURN(AP::ahrs().get_location(last_location));
log_picture();
return true;
Expand All @@ -105,6 +118,13 @@ bool AP_Camera_Backend::take_picture()
return false;
}

// take a picture. returns true on success
bool AP_Camera_Backend::take_multiple_pictures(float time_interval, int16_t total_num)
{
time_interval_settings = {true, time_interval, total_num};
return true;
}

// handle camera control
void AP_Camera_Backend::control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id)
{
Expand Down
12 changes: 11 additions & 1 deletion libraries/AP_Camera/AP_Camera_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,9 @@ class AP_Camera_Backend
// take a picture. returns true on success
bool take_picture();

// take multiple pictures
bool take_multiple_pictures(float time_interval, int16_t total_num);

// entry point to actually take a picture. returns true on success
virtual bool trigger_pic() = 0;

Expand Down Expand Up @@ -128,6 +131,13 @@ class AP_Camera_Backend
uint32_t feedback_trigger_logged_count; // ID sequence number
} camera_feedback;

// Picture settings
struct {
bool enabled; // true if taking multiple pictures is enabled
float time_interval; // time interval (in seconds) between two consecutive pictures
int16_t num_remaining; // number of pictures still to be taken
} time_interval_settings;

// Logging Function
void log_picture();
void Write_Camera(uint64_t timestamp_us=0);
Expand All @@ -143,7 +153,7 @@ class AP_Camera_Backend
uint32_t feedback_trigger_timestamp_us; // system time (in microseconds) that timer detected the feedback pin changed
uint32_t feedback_trigger_logged_count; // number of times the feedback has been logged
bool trigger_pending; // true if a call to take_pic() was delayed due to the minimum time interval time
uint32_t last_photo_time_ms; // system time that photo was last taken
uint32_t last_picture_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
Expand Down

0 comments on commit c7801c7

Please sign in to comment.