Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Camera, AP_Mount: Add handler for CAMERA_CAPTURE_STATUS request #24953

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 13 additions & 0 deletions libraries/AP_Camera/AP_Camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Copy link
Contributor Author

@nexton-winjeel nexton-winjeel Sep 12, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I've copied the way the other messages (e.g. CAMERA_SETTINGS, CAMERA_INFORMATION) are handled.

However, these handlers are problematic if there are multiple camera backends:

  • these messages do not have IDs (MAVLink intent is to use compid to distinguish components);
  • however, all of these are sent with the MAV_COMP_ID_AUTOPILOT1 compid, which will confuse a GCS.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Raised #24955.

}
}
}

/*
update; triggers by distance moved and camera trigger
*/
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_Camera/AP_Camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,9 @@ class AP_Camera {
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);
Expand Down
20 changes: 20 additions & 0 deletions libraries/AP_Camera/AP_Camera_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_Camera/AP_Camera_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,9 @@ class AP_Camera_Backend
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
Expand Down
9 changes: 9 additions & 0 deletions libraries/AP_Camera/AP_Camera_Mount.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,4 +88,13 @@ void AP_Camera_Mount::send_camera_settings(mavlink_channel_t chan) const
}
}

// send camera capture status message to GCS
void AP_Camera_Mount::send_camera_capture_status(mavlink_channel_t chan) const
{
AP_Mount* mount = AP::mount();
if (mount != nullptr) {
return mount->send_camera_capture_status(get_mount_instance(), chan);
}
}

#endif // AP_CAMERA_MOUNT_ENABLED
3 changes: 3 additions & 0 deletions libraries/AP_Camera/AP_Camera_Mount.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,9 @@ class AP_Camera_Mount : public AP_Camera_Backend

// send camera settings message to GCS
void send_camera_settings(mavlink_channel_t chan) const override;

// send camera capture status message to GCS
void send_camera_capture_status(mavlink_channel_t chan) const override;
};

#endif // AP_CAMERA_MOUNT_ENABLED
10 changes: 10 additions & 0 deletions libraries/AP_Mount/AP_Mount.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -850,6 +850,16 @@ void AP_Mount::send_camera_settings(uint8_t instance, mavlink_channel_t chan) co
backend->send_camera_settings(chan);
}

// send camera capture status message to GCS
void AP_Mount::send_camera_capture_status(uint8_t instance, mavlink_channel_t chan) const
{
auto *backend = get_instance(instance);
if (backend == nullptr) {
return;
}
backend->send_camera_capture_status(chan);
}

// get rangefinder distance. Returns true on success
bool AP_Mount::get_rangefinder_distance(uint8_t instance, float& distance_m) const
{
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_Mount/AP_Mount.h
Original file line number Diff line number Diff line change
Expand Up @@ -256,6 +256,9 @@ class AP_Mount
// send camera settings message to GCS
void send_camera_settings(uint8_t instance, mavlink_channel_t chan) const;

// send camera capture status message to GCS
void send_camera_capture_status(uint8_t instance, mavlink_channel_t chan) const;

//
// rangefinder
//
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_Mount/AP_Mount_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,9 @@ class AP_Mount_Backend
// send camera settings message to GCS
virtual void send_camera_settings(mavlink_channel_t chan) const {}

// send camera capture status message to GCS
virtual void send_camera_capture_status(mavlink_channel_t chan) const {}

#if AP_MOUNT_POI_TO_LATLONALT_ENABLED
// get poi information. Returns true on success and fills in gimbal attitude, location and poi location
bool get_poi(uint8_t instance, Quaternion &quat, Location &loc, Location &poi_loc);
Expand Down
11 changes: 11 additions & 0 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -999,6 +999,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
{ MAVLINK_MSG_ID_CAMERA_INFORMATION, MSG_CAMERA_INFORMATION},
{ MAVLINK_MSG_ID_CAMERA_SETTINGS, MSG_CAMERA_SETTINGS},
{ MAVLINK_MSG_ID_CAMERA_FOV_STATUS, MSG_CAMERA_FOV_STATUS},
{ MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, MSG_CAMERA_CAPTURE_STATUS},
#endif
#if HAL_MOUNT_ENABLED
{ MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS},
Expand Down Expand Up @@ -5785,6 +5786,16 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
}
break;
#endif
case MSG_CAMERA_CAPTURE_STATUS:
{
AP_Camera *camera = AP::camera();
if (camera == nullptr) {
break;
}
CHECK_PAYLOAD_SIZE(CAMERA_CAPTURE_STATUS);
rmackay9 marked this conversation as resolved.
Show resolved Hide resolved
camera->send_camera_capture_status(chan);
}
break;
#endif

case MSG_SYSTEM_TIME:
Expand Down
1 change: 1 addition & 0 deletions libraries/GCS_MAVLink/ap_message.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ enum ap_message : uint8_t {
MSG_CAMERA_INFORMATION,
MSG_CAMERA_SETTINGS,
MSG_CAMERA_FOV_STATUS,
MSG_CAMERA_CAPTURE_STATUS,
MSG_GIMBAL_DEVICE_ATTITUDE_STATUS,
MSG_GIMBAL_MANAGER_INFORMATION,
MSG_GIMBAL_MANAGER_STATUS,
Expand Down