mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: set inbound bitrate correctly for bi-directional dshot1200
This commit is contained in:
parent
c18c4ad6ec
commit
f8a59a4a72
|
@ -521,7 +521,7 @@ uint32_t RCOutput::bdshot_get_output_rate_hz(const enum output_mode mode)
|
|||
case MODE_PWM_DSHOT600:
|
||||
return 600000U * 5 / 4;
|
||||
case MODE_PWM_DSHOT1200:
|
||||
return 120000U * 5 / 4;
|
||||
return 1200000U * 5 / 4;
|
||||
default:
|
||||
// use 1 to prevent a possible divide-by-zero
|
||||
return 1;
|
||||
|
|
Loading…
Reference in New Issue