AP_HAL_ChibiOS:Default CAN Term to off on ARK GPS

This commit is contained in:
alexklimaj 2023-02-15 14:43:26 -07:00 committed by Tom Pittenger
parent 31de6fd0b5
commit 96ba25b144
4 changed files with 4 additions and 3 deletions

View File

@ -61,7 +61,7 @@ define HAL_DISABLE_LOOP_DELAY
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PB12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH
PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE

View File

@ -92,6 +92,7 @@ PB9 I2C2_SDA I2C2
PB10 I2C2_SCL I2C2
PB12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW
# magnetometer
COMPASS BMM150 I2C:0:0x10 false ROTATION_NONE

View File

@ -61,7 +61,7 @@ define HAL_DISABLE_LOOP_DELAY
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PB12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH
PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE

View File

@ -96,7 +96,7 @@ PB9 I2C2_SDA I2C2
PB10 I2C2_SCL I2C2
PB12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH
PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW
# magnetometer
COMPASS BMM150 I2C:0:0x10 false ROTATION_NONE