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_Periph: add ESC_RATE parameter to RC_OUT peripherals #27406

Merged
merged 1 commit into from
Jul 10, 2024

Conversation

tpwrules
Copy link
Contributor

@tpwrules tpwrules commented Jun 28, 2024

Like other vehicles (which use RC_SPEED), ESC_RATE is used to set the PWM output rate for outputs whose functions are set to MotorN so that ESCs can be driven at a fast speed (400Hz, same default as aerial vehicles) while servos still run at normal speed (50Hz, controlled by OUT_RATE).

Tested the PWM outputs with real devices and a scope. Also tested that PWM and DShot600 still fly well.

Copy link
Collaborator

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

This will need careful testing of dshot. set_freq() can easily mess with the DMA setup resulting in dshot issues. In particular the order of calls is important

@tpwrules
Copy link
Contributor Author

How would issues manifest?

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Jun 29, 2024
@magicrub
Copy link
Contributor

magicrub commented Jul 5, 2024

I'm not a fan of the param name. Feels like it needs a "PWM" in it instead of RC

@tpwrules
Copy link
Contributor Author

tpwrules commented Jul 5, 2024

It is slightly wonky but I took the name from the other vehicles. If we are changing the name I personally would call it ESC_SPEED to fit with the other parameters on periph.

@tpwrules tpwrules force-pushed the ap-periph-rc-speed branch from 6a60683 to 27b6db2 Compare July 8, 2024 18:12
@tpwrules
Copy link
Contributor Author

tpwrules commented Jul 8, 2024

Rebased on top of #27444 . It looks like the call to set_freq probably belongs before SRV_Channels::init as that function makes comments about doing late setup.

In any case, the new version has been tested in flight using both 400Hz Normal PWM and DShot600 with a BLHeli_S ESC and performed great in both cases. I also had a 50Hz servo attached to a different timer on the periph to make sure that functionality still worked. Verified the correct PWM waveforms on the scope too.

Like other vehicles (which use RC_SPEED), ESC_RATE is used to set the
PWM output rate for outputs whose functions are set to MotorN so that
ESCs can be driven at a fast speed (400Hz, same default as aerial
vehicles) while servos still run at normal speed (50Hz, controlled by
OUT_RATE).
@tpwrules tpwrules force-pushed the ap-periph-rc-speed branch from 27b6db2 to 4888500 Compare July 9, 2024 14:20
@tpwrules tpwrules changed the title AP_Periph: add RC_SPEED parameter to RC_OUT peripherals AP_Periph: add ESC_RATE parameter to RC_OUT peripherals Jul 9, 2024
@tpwrules tpwrules requested review from andyp1per and IamPete1 July 9, 2024 18:49
@tridge tridge merged commit dc58d04 into ArduPilot:master Jul 10, 2024
45 checks passed
@tpwrules tpwrules deleted the ap-periph-rc-speed branch July 10, 2024 13:29
@tpwrules tpwrules removed the WikiNeeded needs wiki update label Jul 29, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

7 participants