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: runcam backend #26887

Open
wants to merge 7 commits into
base: master
Choose a base branch
from

Conversation

andyp1per
Copy link
Collaborator

@andyp1per andyp1per commented Apr 25, 2024

RunCam as a proper camera backend.
Adds a couple of the mavlink info callbacks
Parameter conversion and operation verified on my RunCam split

@rmackay9
Copy link
Contributor

I like where this is going!

@peterbarker
Copy link
Contributor

@andyp1per where are you going with this one?

What advantages were you seeing from being a camera backend?

I'd note that the camera library, even in its most compact form is still going to be pretty chunky, and recent commits have shown we don't really care about keeping it absolutely tight space-wise.

Definitely not saying it's a bad idea!

@andyp1per
Copy link
Collaborator Author

The main thing is to get the mavlink and other support for free. People keep asking for runcam mission support

libraries/AP_Camera/AP_Camera.cpp Outdated Show resolved Hide resolved
libraries/AP_Camera/AP_Camera.cpp Outdated Show resolved Hide resolved
libraries/AP_Camera/AP_Camera.cpp Outdated Show resolved Hide resolved
libraries/AP_Camera/AP_Camera.cpp Show resolved Hide resolved
libraries/AP_Camera/AP_Camera_config.h Show resolved Hide resolved
libraries/AP_Camera/AP_RunCam.cpp Outdated Show resolved Hide resolved
libraries/AP_Camera/AP_RunCam.cpp Show resolved Hide resolved
@andyp1per
Copy link
Collaborator Author

@rmackay9 this is ready to go - any chance of a review?

@rmackay9 rmackay9 dismissed peterbarker’s stale review November 26, 2024 00:05

PeterB's requests have been addressed it seems

@@ -193,6 +209,8 @@ void AP_Camera::init()
return;
}

memset(_backends, 0, sizeof(void*)*AP_CAMERA_MAX_INSTANCES);
Copy link
Contributor

Choose a reason for hiding this comment

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

Why is this being done?!

Suggested change
memset(_backends, 0, sizeof(void*)*AP_CAMERA_MAX_INSTANCES);

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Because the array is not zeroed and we check whether the backend has been allocated.

libraries/AP_Camera/AP_Camera.cpp Outdated Show resolved Hide resolved
libraries/AP_Camera/AP_RunCam.cpp Show resolved Hide resolved
libraries/AP_Camera/AP_RunCam.cpp Show resolved Hide resolved
libraries/AP_Camera/AP_RunCam.cpp Show resolved Hide resolved
libraries/AP_Camera/AP_RunCam.cpp Show resolved Hide resolved
Copy link
Contributor

@rmackay9 rmackay9 left a comment

Choose a reason for hiding this comment

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

I guess we could rename the class to be AP_Camera_RunCam but I don't think we should slow-walk this any more. It's an improvement and it's the beginning of the 4.7 dev cycle so looks OK to me, thanks!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
WikiNeeded needs wiki update
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants