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

Support reversible mask in iomcu #27828

Merged
merged 8 commits into from
Sep 4, 2024
Merged

Conversation

andyp1per
Copy link
Collaborator

We were sending the command but not coping when actually sending the dshot packet

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.

I think we also need the armed state? so we can send dshot value 0 when disarmed. Not doing that for 3D ESCs is dangerous
We have the flag P_SETUP_ARMING_FMU_ARMED left over from earlier versions of IOMCU but we don't seem to use it, I think we need to check hal.util->get_soft_armed() and send that flag over to the IOMCU, otherwise reversible ESCs are too dangerous

Note we do this:
image
so on FMU we do send 0 always when not armed, on IOMCU we don't as far as I can see

@andyp1per
Copy link
Collaborator Author

I think we also need the armed state? so we can send dshot value 0 when disarmed. Not doing that for 3D ESCs is dangerous We have the flag P_SETUP_ARMING_FMU_ARMED left over from earlier versions of IOMCU but we don't seem to use it, I think we need to check hal.util->get_soft_armed() and send that flag over to the IOMCU, otherwise reversible ESCs are too dangerous

Note we do this: image so on FMU we do send 0 always when not armed, on IOMCU we don't as far as I can see

Good catch! Now I understand why @bugobliterator commented this out on IOMCU. It's a little more subtle as the armed state needs to be propagated as well, but certainly doable.

@andyp1per
Copy link
Collaborator Author

I verified with a Saleae that:

  • disarmed + safety - no output
  • disarmed + safety disabled - zeros output
  • armed - zero throttle output

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.

minor changes, but main problem is that the resulting DShot signal is wrong on IOMCU, it is idle high whereas DShot is supposed to be idle low

libraries/AP_IOMCU/AP_IOMCU.cpp Outdated Show resolved Hide resolved
libraries/AP_IOMCU/iofirmware/iofirmware.cpp Outdated Show resolved Hide resolved
@tridge
Copy link
Contributor

tridge commented Aug 18, 2024

testing on Pixhawk6x-bdshot with Sub, with 10% throttle:
image
OUT1 is IOMCU, OUT9 is FMU
note that the signal is idle-high on IOMCU, and AM32 doesn't recognise it:
image

@andyp1per andyp1per force-pushed the pr-iomcu-3d branch 2 times, most recently from 992e491 to e3bf00a Compare August 20, 2024 17:16
@andyp1per
Copy link
Collaborator Author

I have now tested this successfully on a CubeOrangePlus

@andyp1per andyp1per requested a review from tridge August 20, 2024 17:19
@tridge tridge removed the DevCallEU label Aug 21, 2024
@tridge
Copy link
Contributor

tridge commented Aug 29, 2024

@andyp1per I've been testing this with both BLHeli32 and AM32 ESCs on a Pixhawk6X-bdshot board, testing with rover
It all works on FMU, but on IOMCU we never send the command code to set the ESC to 3D mode.

@tridge tridge merged commit 8b5db8f into ArduPilot:master Sep 4, 2024
93 checks passed
@rmackay9
Copy link
Contributor

I discussed with @andyp1per and it only affects rover and sub and he thinks it's best that we wait for 4.6 which will start beta testing soon anyway

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