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

Conversation

nexton-winjeel
Copy link
Contributor

QGroundControl uses the CAMERA_CAPTURE_STATUS message to update the camera control UI. This PR adds support for this message to AP_Camera and AP_Mount.

FYI: @rmackay9, @peterbarker

@nexton-winjeel
Copy link
Contributor Author

I have a second branch to add support for the CAMERA_CAPTURE_STATUS message to the Siyi driver, but it's blocked on #24808.

// 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.

@nexton-winjeel nexton-winjeel force-pushed the upstream/camera-handle-CAMERA_CAPTURE_STATUS branch 2 times, most recently from f46c9d9 to 221f36d Compare September 12, 2023 12:01
@nexton-winjeel nexton-winjeel force-pushed the upstream/camera-handle-CAMERA_CAPTURE_STATUS branch from 221f36d to 37e2611 Compare September 20, 2023 23:29
@nexton-winjeel nexton-winjeel force-pushed the upstream/camera-handle-CAMERA_CAPTURE_STATUS branch from 37e2611 to 62f4ace Compare October 13, 2023 00:00
@nexton-winjeel nexton-winjeel force-pushed the upstream/camera-handle-CAMERA_CAPTURE_STATUS branch from 62f4ace to acc910b Compare November 8, 2023 03:26
@nexton-winjeel
Copy link
Contributor Author

@rmackay9: Anything else you need for this PR?

// Image capture interval (s)
const float image_interval = static_cast<float>(time_interval_settings.time_interval_ms) / 1000.0;
// Total number of images captured
const int32_t image_count = this->image_index;
Copy link
Contributor

Choose a reason for hiding this comment

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

It's just a style thing but maybe we can get rid of some of these intermediate variables and just directly place them in the "camera_capture_status_send(" section below? Then put the comments beside each field. "image_status" is the only one that is complex enough to be worth breaking out I think.

mavlink_msg_camera_capture_status_send(
    chan,
    AP_HAL::millis(),
    image_status,
    0,                                // current state of video capturing (0: idle, 1: capture in progress)
    time_interval_settings.time_interval_ms / 1000.0,  // Image capture interval (s)
    0,                                // time since recording started (ms)
    NaN,                           // available storage capacity (MiB), NaN if unknown
    image_index);             // total number of images captured

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Updated.

// Image capture interval (s)
const float image_interval = static_cast<float>(time_interval_settings.time_interval_ms) / 1000.0;
// Total number of images captured
const int32_t image_count = this->image_index;
Copy link
Contributor

Choose a reason for hiding this comment

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

In any case, no need the the, "this->" I think.

@rmackay9
Copy link
Contributor

rmackay9 commented Nov 8, 2023

@nexton-winjeel,

If you're happy making the mentioned style changes above then I think we can merge. You've tested this of course? I'm sure you have but just need to check.

@nexton-winjeel nexton-winjeel force-pushed the upstream/camera-handle-CAMERA_CAPTURE_STATUS branch from acc910b to cd7c20d Compare November 8, 2023 22:25
@nexton-winjeel
Copy link
Contributor Author

@rmackay9:

You've tested this of course? I'm sure you have but just need to check.

Yep, tested with a Siyi and QGC. I've got a follow-up branch that overrides send_camera_capture_status() in the Siyi driver to populate more fields.

@nexton-winjeel
Copy link
Contributor Author

@rmackay9: Re. the Siyi updates: It's a single commit -- do you want it in this PR, or a separate one?

@rmackay9
Copy link
Contributor

rmackay9 commented Nov 8, 2023

@nexton-winjeel,

Either is fine with me but maybe a follow-up PR would be better so we can merge this now.

@rmackay9 rmackay9 merged commit 3ba63d3 into ArduPilot:master Nov 9, 2023
86 checks passed
@rmackay9
Copy link
Contributor

rmackay9 commented Nov 9, 2023

Merged, thanks!

@nexton-winjeel nexton-winjeel deleted the upstream/camera-handle-CAMERA_CAPTURE_STATUS branch November 9, 2023 04:30
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants