Browse Source

HAL_ChibiOS: added f303-PWM

for a PWM output node based on mRo f303 CAN node
gps-1.3.1
Andrew Tridgell 4 years ago
parent
commit
d29057a158
  1. 8
      libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/defaults.parm
  2. 6
      libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef-bl.dat
  3. 34
      libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef.dat

8
libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/defaults.parm

@ -0,0 +1,8 @@ @@ -0,0 +1,8 @@
OUT1_MIN 1000
OUT1_MAX 2000
OUT2_MIN 1000
OUT2_MAX 2000
OUT3_MIN 1000
OUT3_MAX 2000
OUT4_MIN 1000
OUT4_MAX 2000

6
libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef-bl.dat

@ -0,0 +1,6 @@ @@ -0,0 +1,6 @@
include ../f303-periph/hwdef-bl.inc
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_PWM"

34
libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef.dat

@ -0,0 +1,34 @@ @@ -0,0 +1,34 @@
include ../f303-periph/hwdef.inc
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_PWM"
undef PA2
undef PA3
undef PB14
undef PB15
undef USART2
undef PB6
undef PB7
undef I2C1
undef PA5
undef PA6
undef PA7
undef SPI1
SERIAL_ORDER USART1
I2C_ORDER
# setup for 4 PWM
PA2 TIM2_CH3 TIM2 PWM(1) GPIO(50)
PA3 TIM2_CH4 TIM2 PWM(2) GPIO(51)
PB14 TIM15_CH1 TIM15 PWM(3) GPIO(52)
PB15 TIM15_CH2 TIM15 PWM(4) GPIO(53)
# enable PWM
define HAL_PERIPH_ENABLE_RC_OUT
Loading…
Cancel
Save