forked from Archive/PX4-Autopilot
boards: arkv6x fix wrong pwm output values
This commit is contained in:
parent
d3d5b582fc
commit
c6287a8a89
|
@ -247,7 +247,6 @@
|
|||
/* PWM
|
||||
*/
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||
#define BOARD_PWM_FREQ 1024000
|
||||
|
||||
#define GPIO_FMU_CH1 /* PI0 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTI|GPIO_PIN0)
|
||||
#define GPIO_FMU_CH2 /* PH12 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN12)
|
||||
|
|
|
@ -82,9 +82,7 @@
|
|||
#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET)
|
||||
#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET)
|
||||
|
||||
#if !defined(BOARD_PWM_FREQ)
|
||||
#define BOARD_PWM_FREQ 1000000
|
||||
#endif
|
||||
#define BOARD_SPIX_SYNC_PWM_FREQ 1024000
|
||||
|
||||
unsigned
|
||||
spix_sync_timer_get_period(unsigned timer)
|
||||
|
@ -129,11 +127,11 @@ static void spix_sync_timer_init_timer(unsigned timer, unsigned rate)
|
|||
* Otherwise, other frequencies are attainable by adjusting .clock_freq accordingly.
|
||||
*/
|
||||
|
||||
rPSC(timer) = (spix_sync_timers[timer].clock_freq / BOARD_PWM_FREQ) - 1;
|
||||
rPSC(timer) = (spix_sync_timers[timer].clock_freq / BOARD_SPIX_SYNC_PWM_FREQ) - 1;
|
||||
|
||||
/* configure the timer to update at the desired rate */
|
||||
|
||||
rARR(timer) = (BOARD_PWM_FREQ / rate) - 1;
|
||||
rARR(timer) = (BOARD_SPIX_SYNC_PWM_FREQ / rate) - 1;
|
||||
|
||||
/* generate an update event; reloads the counter and all registers */
|
||||
rEGR(timer) = GTIM_EGR_UG;
|
||||
|
|
Loading…
Reference in New Issue