mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Camera: add time based triggering support
This commit is contained in:
parent
903a9a1a22
commit
2141f06967
@ -87,6 +87,18 @@ void AP_Camera::take_picture()
|
||||
primary->take_picture();
|
||||
}
|
||||
|
||||
// take multiple pictures, time_interval between two consecutive pictures is in miliseconds
|
||||
// total_num is number of pictures to be taken, -1 means capture forever
|
||||
void AP_Camera::take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num)
|
||||
{
|
||||
WITH_SEMAPHORE(_rsem);
|
||||
|
||||
if (primary == nullptr) {
|
||||
return;
|
||||
}
|
||||
primary->take_multiple_pictures(time_interval_ms, 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)
|
||||
@ -240,10 +252,13 @@ 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
|
||||
if (is_equal(packet.param3, 0.0f)) {
|
||||
take_multiple_pictures(packet.param2*1000, -1);
|
||||
} else {
|
||||
take_multiple_pictures(packet.param2*1000, packet.param3);
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
take_picture();
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
@ -115,6 +115,10 @@ public:
|
||||
void take_picture();
|
||||
void take_picture(uint8_t instance);
|
||||
|
||||
// take multiple pictures, time_interval between two consecutive pictures is in miliseconds
|
||||
// total_num is number of pictures to be taken, -1 means capture forever
|
||||
void take_multiple_pictures(uint32_t time_interval_ms, 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);
|
||||
|
@ -32,6 +32,21 @@ void AP_Camera_Backend::update()
|
||||
// check feedback pin
|
||||
check_feedback();
|
||||
|
||||
// time based triggering
|
||||
// if time and distance triggering both are enabled then we only do time based triggering
|
||||
if (time_interval_settings.num_remaining != 0) {
|
||||
uint32_t delta_ms = AP_HAL::millis() - last_picture_time_ms;
|
||||
if (delta_ms > time_interval_settings.time_interval_ms) {
|
||||
if (take_picture()) {
|
||||
// decrease num_remaining except when its -1 i.e. capture forever
|
||||
if (time_interval_settings.num_remaining > 0) {
|
||||
time_interval_settings.num_remaining--;
|
||||
}
|
||||
}
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
// implement trigger distance
|
||||
if (!is_positive(_params.trigg_dist)) {
|
||||
last_location.lat = 0;
|
||||
@ -86,7 +101,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;
|
||||
}
|
||||
@ -96,7 +111,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;
|
||||
@ -105,6 +120,13 @@ bool AP_Camera_Backend::take_picture()
|
||||
return false;
|
||||
}
|
||||
|
||||
// take multiple pictures, time_interval between two consecutive pictures is in miliseconds
|
||||
// total_num is number of pictures to be taken, -1 means capture forever
|
||||
void AP_Camera_Backend::take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num)
|
||||
{
|
||||
time_interval_settings = {time_interval_ms, total_num};
|
||||
}
|
||||
|
||||
// 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)
|
||||
{
|
||||
|
@ -56,6 +56,10 @@ public:
|
||||
// take a picture. returns true on success
|
||||
bool take_picture();
|
||||
|
||||
// take multiple pictures, time_interval between two consecutive pictures is in miliseconds
|
||||
// total_num is number of pictures to be taken, -1 means capture forever
|
||||
void take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num);
|
||||
|
||||
// entry point to actually take a picture. returns true on success
|
||||
virtual bool trigger_pic() = 0;
|
||||
|
||||
@ -128,6 +132,12 @@ protected:
|
||||
uint32_t feedback_trigger_logged_count; // ID sequence number
|
||||
} camera_feedback;
|
||||
|
||||
// Picture settings
|
||||
struct {
|
||||
uint32_t time_interval_ms; // time interval (in miliseconds) between two consecutive pictures
|
||||
int16_t num_remaining; // number of pictures still to be taken, -1 means take unlimited pictures
|
||||
} time_interval_settings;
|
||||
|
||||
// Logging Function
|
||||
void log_picture();
|
||||
void Write_Camera(uint64_t timestamp_us=0);
|
||||
@ -143,7 +153,7 @@ protected:
|
||||
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
|
||||
|
Loading…
Reference in New Issue
Block a user