ardupilot/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat

34 lines
741 B
Plaintext
Raw Normal View History

include ../f303-periph/hwdef.inc
# mRo Location One CAN GPS
# M10070B
# start as DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "io.mrobotics.m10070_loc1"
# added rm3100 mag on SPI
SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
COMPASS RM3100 SPI:rm3100 false ROTATION_NONE
# an I2C baro (DPS310)
BARO DPS280 I2C:0:0x77
# GPS+MAG+LED+Baro
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_NCP5623_BGR_LED_WITHOUT_NOTIFY
define HAL_PERIPH_ENABLE_BARO
# Optional I2C Airspeed sensor connected to I2C connector
define HAL_PERIPH_ENABLE_AIRSPEED
# Safety button
PC13 SAFE_BUTTON INPUT PULLUP
# Button is active LOW
define HAL_SAFE_BUTTON_ON 0
define HAL_PROBE_EXTERNAL_I2C_COMPASSES