2019-12-19 02:19:56 -04:00
|
|
|
# PWM input to Hardpoint output trigger firmware
|
|
|
|
|
2021-05-19 23:17:46 -03:00
|
|
|
include ../f103-periph/hwdef.inc
|
2019-12-19 02:19:56 -04:00
|
|
|
|
2021-03-09 21:13:35 -04:00
|
|
|
# setup build for a peripheral firmware
|
|
|
|
env AP_PERIPH 1
|
|
|
|
|
2020-02-21 19:07:10 -04:00
|
|
|
# use DNA
|
|
|
|
define HAL_CAN_DEFAULT_NODE_ID 0
|
2019-12-19 02:19:56 -04:00
|
|
|
|
|
|
|
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_trigger"
|
|
|
|
|
|
|
|
# PWM input to hardpoint out
|
|
|
|
define HAL_PERIPH_ENABLE_PWM_HARDPOINT
|
|
|
|
|
|
|
|
define HAL_PWM_HARDPOINT_ID_DEFAULT 101
|
|
|
|
|
|
|
|
# we need 10us resolution for PWM capture
|
|
|
|
undef CH_CFG_ST_FREQUENCY
|
|
|
|
define CH_CFG_ST_FREQUENCY 100000
|
|
|
|
|
|
|
|
# use USART1_RX as input for PWM trigger
|
|
|
|
undef PA10
|
2019-12-19 03:51:46 -04:00
|
|
|
PA10 PWM_TRIGGER INPUT PULLDOWN GPIO(77)
|
2019-12-19 02:19:56 -04:00
|
|
|
define PWM_HARDPOINT_PIN 77
|
|
|
|
|
|
|
|
# no I2C
|
|
|
|
undef I2C_ORDER
|
|
|
|
|