ebelski / rust-copter

A quadcopter build using a Teensy running Rust and some other cool stuff that's yet to be determined.
MIT License
6 stars 1 forks source link

Implement additional ESC protocols #12

Closed mciantyre closed 4 years ago

mciantyre commented 4 years ago

Implementations just map to a PWM frequency. The ESC type then maps a throttle percentage to a duty cycle.

There's a constant at the top of the pwm-control demo, ESC_PROTOCOL, that lets you select from one of the three protocols:

https://github.com/ebelski/rust-copter/blob/9d1979d751020ce3d221a5920c763f9f11f0eb97/libs/esc-imxrt1062/src/lib.rs#L52-L71

mciantyre commented 4 years ago

Holding as a draft until I can test against my logic analyzer and verify timings.

ebelski commented 4 years ago

so is the idea behind this that we can select the protocol over usb?

mciantyre commented 4 years ago

Right now it's a compile-time selection. We use whatever Protocol value we set as ESC_PROTOCOL. There's no run-time selection; we can't change it over USB.

Change this value, rebuild using ./tasks demo pwm-control, and flash it to see it running:

https://github.com/ebelski/rust-copter/blob/9d1979d751020ce3d221a5920c763f9f11f0eb97/demos/pwm-control/src/main.rs#L74

mciantyre commented 4 years ago

Here's some tests and some results.

OneShot125

OneShot125 uses a 4KHz PWM period. 50% duty cycle maps to 0% throttle; 100% duty cycle maps to 100% throttle.

Commands:

[INFO demo_pwm_control]: SETTING 'A' = 90% throttle
[INFO demo_pwm_control]: SETTING 'B' = 75% throttle
[INFO demo_pwm_control]: SETTING 'C' = 40% throttle
[INFO demo_pwm_control]: SETTING 'D' = 0% throttle

Expected pulse width for each output is

Output Width (us)
A 237.5
B 218.75
C 175.0
D 125.0

Actual measurements are identified on the right, under "Annotations."

OneShot125

OneShot42

An even-faster protocol, OneShot42 uses a 12KHz PWM period. As before, 50% duty == 0% throttle; 100% duty == 100% throttle.

Commands:

[INFO demo_pwm_control]: SETTING 'A' = 87% throttle
[INFO demo_pwm_control]: SETTING 'B' = 63% throttle
[INFO demo_pwm_control]: SETTING 'C' = 33% throttle
[INFO demo_pwm_control]: SETTING 'D' = 11% throttle

Expected pulse width for each output is

Output Width (us)
A 77.91666
B 67.91666
C 55.41666
D 46.25

Actual measurements are identified on the right, under "Annotations."

OneShot42 If we read the values back, we observe the resolution and rounding limitations:

[INFO demo_pwm_control]: ESC_PROTOCOL = OneShot42
[INFO demo_pwm_control]: A = 86.70614
[INFO demo_pwm_control]: B = 62.66366
[INFO demo_pwm_control]: C = 32.99356
[INFO demo_pwm_control]: D = 10.489212
ebelski commented 4 years ago

I was able to test spinning the motor with OneShot125 and it performs phenomenally so far. Adjusting the throttle adjusts the speed with which the motor spins and additionally it is drawing much less current. I believe we had a bad ESC previously (it did burn out) or the PWM protocol we were using did not function well with the ESC.

I advocate for pushing forward using the OneShot125 protocol based on how well it did in the benchtop test tonight.