mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_HAL_ChibiOS:Default CAN Term to off on ARK GPS
This commit is contained in:
parent
31de6fd0b5
commit
96ba25b144
@ -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
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user