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

DroneCAN: fix dangerous bug for twin-motor Planes #27610

Merged
merged 3 commits into from
Sep 16, 2024

Conversation

robertlong13
Copy link
Collaborator

@robertlong13 robertlong13 commented Jul 22, 2024

Without this, twin motor planes with DroneCAN ESCs need to set a
dummy throttle channel for the scale_esc_to_unity to work correctly.

Worse yet, if you don't do this, your ESCs will receive a max throttle command while disarmed as soon as the safety switch is disengaged.

The first commit prevents the max-throttle symptom when esc scaling is unconfigured or misconfigured (costs 16 bytes). The second commit allows the left/right throttle servos to be used to configure esc scaling (costs 24 bytes).

Params to reproduce this bug on CubeOrange, disengage the safety switch and look at RawCommand coming out of the autopilot in DroneCAN GUI

CAN_D1_UC_ESC_BM 3
CAN_P1_DRIVER 1
CAN_P2_DRIVER 1
SERIAL6_PROTOCOL 2
SERVO1_FUNCTION 74
SERVO1_MAX 2000
SERVO1_MIN 1000
SERVO2_FUNCTION 73
SERVO2_MAX 2000
SERVO2_MIN 1000
SERVO3_FUNCTION 0
SERVO4_FUNCTION 0

Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

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

The whole scale to unity thing really should be removed at somepoint. It will cause issues if you were to set different ranges on your throttles, or PWM_MIN/PWM_MAX for quadplane.

We should calculate the scaled output per channel.

@robertlong13 robertlong13 force-pushed the pr/dronecan_escminmax_bugfix branch from 13271e7 to 2a65d03 Compare July 22, 2024 22:35
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'd like to AP_HAL/RCOutput.h change to init the min/max to 1000/2000

This prevents bugs and misconfigurations from causing DroneCAN ESCs to
spin at full speed while the vehicle is disarmed.
Without this, twin motor planes with DroneCAN ESCs need to set a
dummy throttle channel for scale_esc_to_unity to work.
Further protection from potential dangerous behavior when these do not
get initialized for some reason.
@robertlong13 robertlong13 force-pushed the pr/dronecan_escminmax_bugfix branch from 2a65d03 to 3534d3a Compare September 16, 2024 02:48
@robertlong13
Copy link
Collaborator Author

robertlong13 commented Sep 16, 2024

Finally got around to the testing to confirm that I haven't inadvertently messed with the math:

Params, all default except:

CAN_D1_UC_ESC_BM,4 # Servo 3 (throttle)
CAN_D1_UC_ESC_OF,2 # Offset by 2 (so only 3 comes in)
CAN_D1_UC_ESC_RV,4 # Servo 3 is reversable (turned this on and off to test both)
CAN_P1_DRIVER,1
CAN_P2_DRIVER,1
SERIAL6_PROTOCOL,2 # So I could have Planner and DroneCAN GUI connected simultaneously

Armed in manual and throttled up using vjoy through Mission Planner and looked at the RawCommand messages using DroneCAN GUI

Tested in/outs:
(edited: had the headers reversed)

RC3 % CMD (non-reversable) CMD (reversable)
0 0 -8191
25 2047 -4095
50 4095 0
75 6143 4095
100 8191 8191

Also, I've made the change the Tridge requested.

And of course I also tested that this PR does still in fact fix the bug.

@tridge
Copy link
Contributor

tridge commented Sep 16, 2024

@robertlong13 I do hope that table has swapped column headers for reversible/non-reversible?

@robertlong13
Copy link
Collaborator Author

@robertlong13 I do hope that table has swapped column headers for reversible/non-reversible?

Yup, swapped headers. Sorry. Editing the comment now

@tridge tridge merged commit 4a1e4eb into ArduPilot:master Sep 16, 2024
95 checks passed
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.

5 participants