AP_Camera: add MAV_CMD_IMAGE_STOP_CAPTURE support
Co-authored-by: Zachary Zalass <zachzalass@gmail.com>
This commit is contained in:
parent
518feedf41
commit
f30af5e072
@ -127,6 +127,31 @@ bool AP_Camera::take_multiple_pictures(uint8_t instance, uint32_t time_interval_
|
||||
return true;
|
||||
}
|
||||
|
||||
// stop capturing multiple image sequence
|
||||
void AP_Camera::stop_capture()
|
||||
{
|
||||
WITH_SEMAPHORE(_rsem);
|
||||
|
||||
// call for each instance
|
||||
for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {
|
||||
if (_backends[i] != nullptr) {
|
||||
_backends[i]->stop_capture();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool AP_Camera::stop_capture(uint8_t instance)
|
||||
{
|
||||
WITH_SEMAPHORE(_rsem);
|
||||
|
||||
auto *backend = get_instance(instance);
|
||||
if (backend == nullptr) {
|
||||
return false;
|
||||
}
|
||||
backend->stop_capture();
|
||||
return true;
|
||||
}
|
||||
|
||||
// start/stop recording video
|
||||
// start_recording should be true to start recording, false to stop recording
|
||||
bool AP_Camera::record_video(bool start_recording)
|
||||
@ -311,6 +336,16 @@ MAV_RESULT AP_Camera::handle_command_long(const mavlink_command_long_t &packet)
|
||||
}
|
||||
}
|
||||
return MAV_RESULT_UNSUPPORTED;
|
||||
case MAV_CMD_IMAGE_STOP_CAPTURE:
|
||||
if (is_zero(packet.param1)) {
|
||||
// stop capture for every backend
|
||||
stop_capture();
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
if (stop_capture(packet.param1)) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
return MAV_RESULT_UNSUPPORTED;
|
||||
case MAV_CMD_CAMERA_TRACK_POINT:
|
||||
if (set_tracking(TrackingType::TRK_POINT, Vector2f{packet.param1, packet.param2}, Vector2f{})) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
@ -120,6 +120,10 @@ public:
|
||||
void take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num);
|
||||
bool take_multiple_pictures(uint8_t instance, uint32_t time_interval_ms, int16_t total_num);
|
||||
|
||||
// stop capturing multiple image sequence
|
||||
void stop_capture();
|
||||
bool stop_capture(uint8_t instance);
|
||||
|
||||
// start/stop recording video
|
||||
// start_recording should be true to start recording, false to stop recording
|
||||
bool record_video(bool start_recording);
|
||||
|
@ -154,6 +154,12 @@ void AP_Camera_Backend::take_multiple_pictures(uint32_t time_interval_ms, int16_
|
||||
time_interval_settings = {time_interval_ms, total_num};
|
||||
}
|
||||
|
||||
// stop capturing multiple image sequence
|
||||
void AP_Camera_Backend::stop_capture()
|
||||
{
|
||||
time_interval_settings = {0, 0};
|
||||
}
|
||||
|
||||
// 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)
|
||||
{
|
||||
|
@ -60,6 +60,9 @@ public:
|
||||
// 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);
|
||||
|
||||
// stop capturing multiple image sequence
|
||||
void stop_capture();
|
||||
|
||||
// entry point to actually take a picture. returns true on success
|
||||
virtual bool trigger_pic() = 0;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user