mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL: make hal aware of oneshot125
this separates oneshot and oneshot125 at the HAL layer, allowing the HAL to properly handle the high timing resolution of oneshot125 (needed to use 125ns time steps, to get the full 1000 throttle steps)
This commit is contained in:
parent
67993d6e5c
commit
0bb2c4564d
@ -170,6 +170,7 @@ public:
|
||||
MODE_PWM_NONE,
|
||||
MODE_PWM_NORMAL,
|
||||
MODE_PWM_ONESHOT,
|
||||
MODE_PWM_ONESHOT125,
|
||||
MODE_PWM_BRUSHED,
|
||||
MODE_PWM_DSHOT150,
|
||||
MODE_PWM_DSHOT300,
|
||||
|
Loading…
Reference in New Issue
Block a user