AP_Camera: Add handler for CAMERA_CAPTURE_STATUS request
This commit is contained in:
parent
ba76d4e2f9
commit
477534b446
@ -541,6 +541,19 @@ void AP_Camera::send_camera_fov_status(mavlink_channel_t chan)
|
||||
}
|
||||
#endif
|
||||
|
||||
// send camera capture status message to GCS
|
||||
void AP_Camera::send_camera_capture_status(mavlink_channel_t chan)
|
||||
{
|
||||
WITH_SEMAPHORE(_rsem);
|
||||
|
||||
// call each instance
|
||||
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
|
||||
if (_backends[instance] != nullptr) {
|
||||
_backends[instance]->send_camera_capture_status(chan);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
update; triggers by distance moved and camera trigger
|
||||
*/
|
||||
|
@ -100,6 +100,9 @@ public:
|
||||
void send_camera_fov_status(mavlink_channel_t chan);
|
||||
#endif
|
||||
|
||||
// send camera capture status message to GCS
|
||||
void send_camera_capture_status(mavlink_channel_t chan);
|
||||
|
||||
// configure camera
|
||||
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time);
|
||||
void configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time);
|
||||
|
@ -286,6 +286,26 @@ void AP_Camera_Backend::send_camera_fov_status(mavlink_channel_t chan) const
|
||||
}
|
||||
#endif
|
||||
|
||||
// send camera capture status message to GCS
|
||||
void AP_Camera_Backend::send_camera_capture_status(mavlink_channel_t chan) const
|
||||
{
|
||||
const float NaN = nanf("0x4152");
|
||||
|
||||
// Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)
|
||||
const uint8_t image_status = (time_interval_settings.num_remaining > 0) ? 2 : 0;
|
||||
|
||||
// send CAMERA_CAPTURE_STATUS message
|
||||
mavlink_msg_camera_capture_status_send(
|
||||
chan,
|
||||
AP_HAL::millis(),
|
||||
image_status,
|
||||
0, // current status of video capturing (0: idle, 1: capture in progress)
|
||||
static_cast<float>(time_interval_settings.time_interval_ms) / 1000.0, // image capture interval (s)
|
||||
0, // elapsed time since recording started (ms)
|
||||
NaN, // available storage capacity (ms)
|
||||
image_index); // total number of images captured
|
||||
}
|
||||
|
||||
// setup a callback for a feedback pin. When on PX4 with the right FMU
|
||||
// mode we can use the microsecond timer.
|
||||
void AP_Camera_Backend::setup_feedback_callback()
|
||||
|
@ -115,6 +115,9 @@ public:
|
||||
void send_camera_fov_status(mavlink_channel_t chan) const;
|
||||
#endif
|
||||
|
||||
// send camera capture status message to GCS
|
||||
virtual void send_camera_capture_status(mavlink_channel_t chan) const;
|
||||
|
||||
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||
// accessor to allow scripting backend to retrieve state
|
||||
// returns true on success and cam_state is filled in
|
||||
|
Loading…
Reference in New Issue
Block a user