mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
HAL_ChibiOS: fixed orientation of compass on M10070B
This commit is contained in:
parent
3b7b2b89a5
commit
cb034c50a7
@ -1,7 +1,7 @@
|
||||
include ../f303-periph/hwdef.dat
|
||||
|
||||
# mRo Location One CAN GPS
|
||||
# M10084
|
||||
# M10070B
|
||||
|
||||
# start as DNA
|
||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
@ -10,7 +10,7 @@ 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_ROLL_180_YAW_90
|
||||
COMPASS RM3100 SPI:rm3100 false ROTATION_NONE
|
||||
|
||||
# an I2C baro (DPS310)
|
||||
BARO DPS280 I2C:0:0x77
|
||||
|
Loading…
Reference in New Issue
Block a user