mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-25 01:03:59 -04:00
AP_Camera: take_pic and take_multiple_pic report success
Methods return success if at least one backend succeeds
This commit is contained in:
parent
66337af882
commit
9e3ab558b3
@ -77,16 +77,20 @@ void AP_Camera::cam_mode_toggle()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// take a picture
|
// take a picture
|
||||||
void AP_Camera::take_picture()
|
bool AP_Camera::take_picture()
|
||||||
{
|
{
|
||||||
WITH_SEMAPHORE(_rsem);
|
WITH_SEMAPHORE(_rsem);
|
||||||
|
|
||||||
// call for each instance
|
// call for each instance
|
||||||
|
bool success = false;
|
||||||
for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {
|
for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {
|
||||||
if (_backends[i] != nullptr) {
|
if (_backends[i] != nullptr) {
|
||||||
_backends[i]->take_picture();
|
success |= _backends[i]->take_picture();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// return true if at least once pic taken
|
||||||
|
return success;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_Camera::take_picture(uint8_t instance)
|
bool AP_Camera::take_picture(uint8_t instance)
|
||||||
@ -97,28 +101,45 @@ bool AP_Camera::take_picture(uint8_t instance)
|
|||||||
if (backend == nullptr) {
|
if (backend == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
backend->take_picture();
|
return backend->take_picture();
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// take multiple pictures, time_interval between two consecutive pictures is in miliseconds
|
// take multiple pictures, time_interval between two consecutive pictures is in miliseconds
|
||||||
|
// if instance is not provided, all available cameras affected
|
||||||
|
// time_interval_ms must be positive
|
||||||
// total_num is number of pictures to be taken, -1 means capture forever
|
// 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)
|
// returns true if at least one camera is successful
|
||||||
|
bool AP_Camera::take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num)
|
||||||
{
|
{
|
||||||
WITH_SEMAPHORE(_rsem);
|
WITH_SEMAPHORE(_rsem);
|
||||||
|
|
||||||
|
// sanity check time interval
|
||||||
|
if (time_interval_ms == 0) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// call for all instances
|
// call for all instances
|
||||||
|
bool success = false;
|
||||||
for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {
|
for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {
|
||||||
if (_backends[i] != nullptr) {
|
if (_backends[i] != nullptr) {
|
||||||
_backends[i]->take_multiple_pictures(time_interval_ms, total_num);
|
_backends[i]->take_multiple_pictures(time_interval_ms, total_num);
|
||||||
|
success = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// return true if at least once backend was successful
|
||||||
|
return success;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_Camera::take_multiple_pictures(uint8_t instance, uint32_t time_interval_ms, int16_t total_num)
|
bool AP_Camera::take_multiple_pictures(uint8_t instance, uint32_t time_interval_ms, int16_t total_num)
|
||||||
{
|
{
|
||||||
WITH_SEMAPHORE(_rsem);
|
WITH_SEMAPHORE(_rsem);
|
||||||
|
|
||||||
|
// sanity check time interval
|
||||||
|
if (time_interval_ms == 0) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
auto *backend = get_instance(instance);
|
auto *backend = get_instance(instance);
|
||||||
if (backend == nullptr) {
|
if (backend == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
|
@ -111,13 +111,17 @@ public:
|
|||||||
void cam_mode_toggle();
|
void cam_mode_toggle();
|
||||||
void cam_mode_toggle(uint8_t instance);
|
void cam_mode_toggle(uint8_t instance);
|
||||||
|
|
||||||
// take a picture
|
// take a picture. If instance is not provided, all available cameras affected
|
||||||
void take_picture();
|
// returns true if at least one camera took a picture
|
||||||
|
bool take_picture();
|
||||||
bool take_picture(uint8_t instance);
|
bool take_picture(uint8_t instance);
|
||||||
|
|
||||||
// take multiple pictures, time_interval between two consecutive pictures is in miliseconds
|
// take multiple pictures, time_interval between two consecutive pictures is in miliseconds
|
||||||
|
// if instance is not provided, all available cameras affected
|
||||||
|
// time_interval_ms must be positive
|
||||||
// total_num is number of pictures to be taken, -1 means capture forever
|
// 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);
|
// returns true if at least one camera is successful
|
||||||
|
bool 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);
|
bool take_multiple_pictures(uint8_t instance, uint32_t time_interval_ms, int16_t total_num);
|
||||||
|
|
||||||
// stop capturing multiple image sequence
|
// stop capturing multiple image sequence
|
||||||
|
Loading…
Reference in New Issue
Block a user