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

Implement support for the RunCam protocol #12810

Merged
merged 34 commits into from
Dec 30, 2019

Conversation

andyp1per
Copy link
Collaborator

@andyp1per andyp1per commented Nov 10, 2019

Implement support for the RunCam protocol.

CAM_RC_FEATURES - manually set RunCam features, but should be determined automatically
CAM_RC_BT_DELAY - time it takes for the runcam to boot
CAM_RC_BTN_DELAY - time to wait between button presses
CAM_RC_MDE_DELAY - time to wait between mode button presses
CAM_RC_TYPE - device type
CAM_RC_CONTROL - control access to OSD menu, bit 1 is yaw right, bit 2 is middle position of a 
3-button switch (rc option 78), bit 3 is a two-position switch (rc option 79). All can be enabled at the 
same time

In order to enable the support you need something like:

RC8_OPTION = 78
SERIALn_PROTOCOL = 26

You can also use option 79 to control OSD menu entry/exit rather than stick control.
This now all works:

  • Video start/stop is now working off the switch defined by RC option 78
  • The OSD menu can be entered by right yaw when throttle in in mid point and exited via left yaw when throttle in mid point
  • Menus are navigated up/down via pitch and enter/exit/change via roll

It turns out I don't have a RunCam that implements the 5 key OSD protocol, so I cannot test that aspect. I have implemented the simpler 2 key OSD protocol. This requires firmware 2.4.4 on a split micro to work properly.

@andyp1per
Copy link
Collaborator Author

Fixes #10103

@peterbarker
Copy link
Contributor

Not following this PR - 'though it sounds awesome.

Is there any reason this is Copter-specific?

@andyp1per
Copy link
Collaborator Author

@peterbarker no, other than the fact that I have a copter with a RunCam 🙂
When I have it working I will make sure I add in support for other platforms as well.

@peterbarker
Copy link
Contributor

peterbarker commented Nov 14, 2019 via email

@andyp1per
Copy link
Collaborator Author

andyp1per commented Nov 15, 2019

@peterbarker the BF code allows camera OSD control via RC commands when not armed. How do I access the main RC channels in a sensible way without depending on copter? (Copter has specific member variables for roll/pitch/yaw/throttle)

I guess I could do rc().channel(0-3), but that seems a little tacky

@andyp1per
Copy link
Collaborator Author

Video start/stop is now working.

@andyp1per andyp1per force-pushed the pr-runcam-protocol branch 2 times, most recently from 4edb835 to 8d37429 Compare November 17, 2019 20:50
@andyp1per
Copy link
Collaborator Author

I am successfully able to navigate OSD menus now, but it seems there is a bug in the protocol such that you can't actually change any settings this way. I have raised a support ticket with RunCam so we shall see. The split micro (what I have) does not support the 5-Key OSD simulation.

@andyp1per
Copy link
Collaborator Author

I've bricked my runcam trying beta firmware. Development will be stopped for a while as I try and recover ☹️

@andyp1per
Copy link
Collaborator Author

Incredibly, I have unbricked my runcam. This was really involved - I'll jot down the steps here in case anyone else has the same issues:

  • Find a Windows 7 machine. I abjectly failed to get this to work on Windows 10.
  • Install the Windows drivers only from https://support.runcam.com/hc/en-us/articles/360035371854-Flash-firmware-via-computer-for-Split-mini-2-if-it-is-bricked-during-firmware-updating- on Windows 7 this should work without having to do any messing with driver signing, but if you are not prompted to install three device drivers then something went wrong so you should follow the instructions in firmware-reflash-manual.pdf to disable driver signing
  • Solder the USB port on your runcam, this involves wiring up the regular VCC and GND and then D- and D+ as shown here:
    image
    Note that on my device at least the color coding was what is documented in the article above (D- white, D+ green) which is opposite to some articles on the internet.
  • Connect the runcam to a USB 2.0 port (USB 3.0 does not work)
  • Wait for the 3 devices to be installed. On my device this took a long time and I only ended up with 2:
    image
    I then had to manually install the spca6350 camera driver for the unrecognized device in device manager.
  • Follow the rest of the instructions in firmware-reflash-manual.pdf but do not use the software in that download directory instead use the beta firmware package for the software: https://runcam.zendesk.com/attachments/token/Sq9AkN6bHCWTTKCG21y2ndQzv/?name=AQY006_V2.4.4_20191009.7z When I tried the older software I kept getting the error "ISP Core Error!"
  • Even then I got a verify error but things seemed to be working and I was able to update to the regular firmware after that.

@andyp1per
Copy link
Collaborator Author

And, Eureka! The beta runcam firmware 2.4.4 allows the settings to be changed. Pretty close to publishing this now.

@andyp1per andyp1per force-pushed the pr-runcam-protocol branch 3 times, most recently from ca033ae to 3f9c9ae Compare November 30, 2019 17:09
@andyp1per andyp1per marked this pull request as ready for review November 30, 2019 17:14
Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

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

Initial pass only.

Does RunCam have a page outlining which devices support this protocol?

We shouldn't really add too many parameters if there is a sensible default. There are issues having too many parameters (vehicle connect times etc)

That queue-of-responses stuff seems over-complicated. Unless there's a reason to parse them out, we could just leave them in the uart until we're ready to handle another response.

ArduCopter/Copter.cpp Outdated Show resolved Hide resolved
ArduCopter/Copter.h Outdated Show resolved Hide resolved
libraries/AP_Camera/AP_RunCam.cpp Outdated Show resolved Hide resolved
libraries/AP_Camera/AP_RunCam.cpp Outdated Show resolved Hide resolved
libraries/AP_Camera/AP_RunCam.cpp Outdated Show resolved Hide resolved
libraries/AP_Camera/AP_RunCam.h Outdated Show resolved Hide resolved
libraries/AP_OSD/AP_OSD.cpp Show resolved Hide resolved
libraries/AP_OSD/AP_OSD.h Outdated Show resolved Hide resolved
libraries/RC_Channel/RC_Channel.cpp Outdated Show resolved Hide resolved
libraries/RC_Channel/RC_Channel.cpp Outdated Show resolved Hide resolved
Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

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

Initial pass only.

Does RunCam have a page outlining which devices support this protocol?

We shouldn't really add too many parameters if there is a sensible default. There are issues having too many parameters (vehicle connect times etc)

That queue-of-responses stuff seems over-complicated. Unless there's a reason to parse them out, we could just leave them in the uart until we're ready to handle another response.

@peterbarker
Copy link
Contributor

I take it we need to create an ObjectQeue for some reason, rather than just leaving them in the uart 'til we're good and ready?

Copy link
Collaborator Author

@andyp1per andyp1per left a comment

Choose a reason for hiding this comment

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

I take it we need to create an ObjectQeue for some reason, rather than just leaving them in the uart 'til we're good and ready?

Yes, the protocol is incredible flaky and stuff gets dropped very easily. We have to keep a record of what we have sent so that we can send again if we don't get back a response. Also this is part of the code that the 5-Key simulation relies on a lot and I don't have a device that I can test it on, so wary of fundamentally changing the operation from the way BF does it.

libraries/AP_Camera/AP_RunCam.h Show resolved Hide resolved
#include <AP_Logger/AP_Logger.h>
#include <AP_OSD/AP_OSD.h>

const AP_Param::GroupInfo AP_RunCam::var_info[] = {
Copy link
Contributor

Choose a reason for hiding this comment

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

Maybe add an enable param for this, so that people who aren't using runcams don't have the parameters coming down?

Copy link
Collaborator Author

@andyp1per andyp1per Dec 6, 2019

Choose a reason for hiding this comment

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

I considered this, but nothing is enabled unless you specify the runcam protocol on a serial device. If I add enable you have to both enable and select the protocol to get stuff working - which seems a little onerous, but happy to do this if that's the way we configure things. For comparison blheli protcol support does not have an enable flag.

Copy link
Contributor

Choose a reason for hiding this comment

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

I think you could move the TYPE param to be the first param, make type 0 mean disabled, and set it as an enable parameter. I know we don't do this for all libraries, but I think it is good practice for libraries that are less commonly used to reduce the number of downloaded parameters

Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

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

really nice work!
I've pushed a commit to your branc to fix the Replay changes. The only other thing I'd like to see is for CAM_RC_TYPE to be an enable parameter and first in the param list (index 1).

#include <AP_Logger/AP_Logger.h>
#include <AP_OSD/AP_OSD.h>

const AP_Param::GroupInfo AP_RunCam::var_info[] = {
Copy link
Contributor

Choose a reason for hiding this comment

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

I think you could move the TYPE param to be the first param, make type 0 mean disabled, and set it as an enable parameter. I know we don't do this for all libraries, but I think it is good practice for libraries that are less commonly used to reduce the number of downloaded parameters

@tridge tridge dismissed peterbarker’s stale review December 30, 2019 01:22

discussed with Peter, he's happy with changes

@tridge
Copy link
Contributor

tridge commented Dec 30, 2019

@andyp1per as we discussed, I've changed CAM_RC_TYPE to be an enable parameter, but made it auto-enable if you have the SERIAL protocol setup.
I've happy for this PR to be merged once it passes CI. Many thanks for you efforts on this!
I know that the runcam support isn't yet proven to work for everyone, but that can be worked on after we have it in master. I want to merge this early so we can start to use the new AP_Vehicle parameter and scheduling components

@tridge tridge merged commit f1dfb2e into ArduPilot:master Dec 30, 2019
@andyp1per andyp1per deleted the pr-runcam-protocol branch December 30, 2019 09:01
@rmackay9
Copy link
Contributor

rmackay9 commented Feb 12, 2020

I think we've introduced a small issue here by adding a 17th bit to the ArmingChecks enum without increasing the get_enabled_checks() return value (a uint16_t) and we also need to increase the size of the log_Arm_Disarm log structure.

I'll create a PR with a fix shortly.

@andyp1per
Copy link
Collaborator Author

@rmackay9 good catch!

@ItsMeAubey
Copy link

ItsMeAubey commented Jun 5, 2020

My apologies if this should be in a separate issue:

It seems that there are some strange issues with this implementation.

The runcam menu ignores RC reversals in ardupilot. in my case, pitch stick up moved the menu selection down. Reversing in ardupilot did not work. I had to use radio reversal to fix the runcam menu and then undo that reversal (to make my sticks work properly) in ardupilot.

Rolling hard-right does not always enter the camera menu, while yawing hard right always does. In some cases, seemingly randomly, I get the "remote mode" popup from the camera after using roll to enter the menu, but the only way to get to the actual camera menu is to use yaw.

Sometimes, repeatedly pushing roll hard left makes ardupilot think that it is no longer connected to the camera, while the camera menu is still definitely active, and thus the outgoing connection to the camera is broken, making it impossible to close the menu without power cycling or unplugging the camera. When in the home menu of the camera, selecting any option and yawing left makes the ardupilot osd turn back on and makes ardupilot disconnect from the camera (without actually exiting from the camera menu). This specific yaw issue happens 100% of the time for me. Tried with a second camera and this seems camera-specific.

I can provide video examples of all of these issues if that would be helpful.

@andyp1per
Copy link
Collaborator Author

Hi @aaaaaaudrey can you raise a github issue for this?

Please can you describe:

  • Your settings / parameters
  • Which runcam camera you are using
  • What sequence of commands from boot causes the problem (it's a state machine so I need the exact sequence of commands from the time you boot the board to reproduce the issue).

It looks like you are using a bare camera with the remote protocol. I'm afraid this got less testing than the split version and is even more timing sensitive because my copters all have splits on them.

@ItsMeAubey
Copy link

@andyp1per #14540

@wcfung
Copy link

wcfung commented Apr 21, 2021

Not sure if there is anyone still following this thread.

I am trying to conenct a Runcam Split (1st version) to Pixhawk (running Arduplane v4.0.7) in order to start/stop video. Have already connected the Split module Gnd, Rx Tx to Pixhawk UART Gnd, Tx, Rx respectively. Mission Planner (1.3.74) Serialn_PROTOCOL is also set to 26 (for Runcam). I am not sure why 26 is not an option in the parameter list. Serialn_BAUD is left at 57600.

After power up, the Runcam Split is not recognized in the initialization (shown in message tab) as indicated in ardupilot wiki. I tried reversing the signal wires as suggested in wiki. This did not change anything. The camera should be in UART control mode, which is usually the default mode for Split camera. However I cannot confirm this as I had difficulty connecting the camera to Runcam App. The camera recording function is normal.

Pls suggest any possible causes that prevent Pixhawk from recognising the Runcam Split.

@andyp1per
Copy link
Collaborator Author

@wcfung this feature is only supported in Ardupilot 4.1 which is now out in beta

@wcfung
Copy link

wcfung commented Apr 21, 2021

Thank you for yr reply. I am glad you are still following this thread. But you did mention on Nov 16, 2019 in this thread that "video start/stop is now working". In 2019, it was before Ardupilot 4.0.7. Did I miss something ?

Appreciate your help.

@andyp1per
Copy link
Collaborator Author

It would have had to have been before 4.0.0 to have made it into 4.0, anything after that is bugfixes only

@wcfung
Copy link

wcfung commented Apr 22, 2021 via email

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.

None yet

9 participants