mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
HAL_ChibiOS: added f103-QiotekPeriph hwdef (#1)
HAL_ChibiOS: added f103-QiotekPeriph
This commit is contained in:
parent
4362b16f50
commit
1de3135d14
@ -0,0 +1,7 @@
|
||||
include ../f103-periph/hwdef-bl.dat
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.f103Qiotek_Periph"
|
||||
|
||||
# use DNA
|
||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
|
24
libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat
Normal file
24
libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat
Normal file
@ -0,0 +1,24 @@
|
||||
include ../f103-periph/hwdef.dat
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.f103Qiotek_Periph"
|
||||
|
||||
# use DNA
|
||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
|
||||
undef HAL_COMPASS_MAX_SENSORS 1
|
||||
define define HAL_COMPASS_MAX_SENSORS 2
|
||||
|
||||
define HAL_AIRSPEED_BUS_DEFAULT 0
|
||||
|
||||
# 15 ASP5033 sensor by default
|
||||
define HAL_AIRSPEED_TYPE_DEFAULT 15
|
||||
define AIRSPEED_MAX_SENSORS 1
|
||||
|
||||
define HAL_PERIPH_ENABLE_AIRSPEED
|
||||
define HAL_PERIPH_ENABLE_MAG
|
||||
COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180_YAW_270
|
||||
COMPASS QMC5883L I2C:0:0x0D false ROTATION_ROLL_180_YAW_270
|
||||
COMPASS RM3100 I2C:0:0x20 false ROTATION_NONE
|
||||
COMPASS RM3100 I2C:0:0x21 false ROTATION_NONE
|
||||
COMPASS RM3100 I2C:0:0x22 false ROTATION_NONE
|
||||
COMPASS RM3100 I2C:0:0x23 false ROTATION_NONE
|
Loading…
Reference in New Issue
Block a user