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_Hal_Linux: PCA9685: do not shutdown #19772

Merged
merged 1 commit into from Jan 18, 2022

Conversation

Williangalvani
Copy link
Contributor

@Williangalvani Williangalvani commented Jan 12, 2022

Sleeping causes the current pulses to be cut short, often causing ESCs to interpret this pulse and briefly spin thrusters (often pretty violently) when Ardupilot is stopped.

We can alternatively add a delay to wait until all the pulses are over, but that will delay the shutdown and depends on the current PWM frequency. Is there an issue in keeping the PCA running?

Before:
image (18)

After:
image (17)

credits to @jaxxzer for digging into this

Shutting down causes the pulses to be cut short, often causing
ESCs to interpret this pulse
Copy link
Contributor

@khancyr khancyr left a comment

Choose a reason for hiding this comment

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

I would said that keep it alive will just consum some current and not set the ESC in no signal mode ?
Can't you just said it to set 0 PWM before going to sleep instead of removing sleep ?

@Williangalvani
Copy link
Contributor Author

@khancyr _dev->write_register(PCA9685_RA_ALL_LED_OFF_H, PCA9685_ALL_LED_OFF_H_SHUT); sets all duty cycle to 0% (so 0 V), and is called in the datasheet of "orderly shutdown".

_dev->write_register(PCA9685_RA_MODE1, PCA9685_MODE1_SLEEP_BIT); sets some kind of power-saving feature in the IC, which I suspect doesn't matter for ardupilot, and if done too soon "breaks" the PWM pulse, which can cause negative thrust readings for Sub.

@jaxxzer
Copy link
Member

jaxxzer commented Jan 13, 2022

@khancyr the current consumed by the pca9685 is on the order of 10 uA and is insignificant. This change sets the pwm in no signal mode predictably. Prior to this patch, the behavior of the esc or servo is unpredictable

@HefnySco
Copy link
Member

@Williangalvani
do u think it is reliable to link the enable pin to a GPIO pin this will disable the board output ? I could not figured out the exact issue you faced, but I did face that motors spin very fast because the CHIP is out of control because the main board that run AP restarted and in linux this takes time. I hope this comment might be useful to you.

@Williangalvani
Copy link
Contributor Author

@HefnySco we hardly have that issue, if ardusub quits cleanly (either mavlink or sigterm), it disables the PCA (check #18635).

The issue in this PR is that the PCA can abruptly shutdown mid-pulse, so that the last pulse received by the ESC is 1100us instead of 1500us, for example, which causes some thrusters to (briefly but scaringly) spin at full power in reverse.

@khancyr
Copy link
Contributor

khancyr commented Jan 16, 2022

Yep, it seems like solving a real issue. So I don't think we should keep the old behavior.

Can you bring this to a devcall for a last review ?

@lucasdemarchi any experience on this that we may be missing ?

@tridge tridge merged commit b5de26c into ArduPilot:master Jan 18, 2022
@Williangalvani Williangalvani deleted the noshutdown branch March 3, 2022 15:16
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

6 participants