Skip to content

Commit

Permalink
AP_HAL_ChibiOS: use AP_PERIPH_MAG_ENABLED in place of HAL_PERIPH_ENAB…
Browse files Browse the repository at this point in the history
…LE_MAG
  • Loading branch information
shiv-tyagi committed Jan 29, 2025
1 parent 796ec9f commit b17ab8f
Show file tree
Hide file tree
Showing 55 changed files with 61 additions and 55 deletions.
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
define HAL_PERIPH_ENABLE_NOTIFY
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_BUZZER
define HAL_PERIPH_ENABLE_RC_OUT
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_BUZZER
define HAL_PERIPH_ENABLE_NOTIFY
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ define HAL_AIRSPEED_TYPE_DEFAULT 9
define AIRSPEED_MAX_SENSORS 1

define HAL_PERIPH_ENABLE_AIRSPEED
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
COMPASS QMC5883L I2C:0:0x0D false ROTATION_ROLL_180_YAW_90
COMPASS RM3100 I2C:0:0x20 false ROTATION_NONE
COMPASS RM3100 I2C:0:0x21 false ROTATION_NONE
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ define HAL_AIRSPEED_TYPE_DEFAULT 1
define AIRSPEED_MAX_SENSORS 1

define HAL_PERIPH_ENABLE_AIRSPEED
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
COMPASS QMC5883L I2C:0:0x0D false ROTATION_ROLL_180_YAW_90
COMPASS RM3100 I2C:0:0x20 false ROTATION_NONE
COMPASS RM3100 I2C:0:0x21 false ROTATION_NONE
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ define HAL_PERIPH_GPS_PORT_DEFAULT 0

# allow for F9P GPS modules with moving baseline
define GPS_MOVING_BASELINE 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_COMPASS_MAX_SENSORS 1

# QMC5883L for different board varients
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ define HAL_COMPASS_MAX_SENSORS 1
# RCOU+GPS+MAG+BARO+Buzzer+NeoPixels
define HAL_PERIPH_ENABLE_RC_OUT
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_BUZZER
define HAL_PERIPH_NEOPIXEL_COUNT 8
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/C-RTK2-HP/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ define GPS_MAX_INSTANCES 1
define AP_PERIPH_GPS_ENABLED 1
define GPS_MOVING_BASELINE 1

define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_COMPASS_MAX_SENSORS 1

define AP_GPS_BACKEND_DEFAULT_ENABLED 0
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ define HAL_COMPASS_MAX_SENSORS 1

# GPS+MAG+BARO+Buzzer+NeoPixels
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO

# do direct neopixel LED output to enable the 'rainbow' effect on
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ define HAL_NO_GCS

define AP_PARAM_MAX_EMBEDDED_PARAM 512

define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ define HAL_NO_GCS

define AP_PARAM_MAX_EMBEDDED_PARAM 512

define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ env AP_PERIPH 1


define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ env AP_PERIPH_HEAVY 1
define AP_CAN_SLCAN_ENABLED 1
define AP_PERIPH_BATTERY_ENABLED 1
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
define HAL_PERIPH_ENABLE_NOTIFY
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ env AP_PERIPH 1
define AP_CAN_SLCAN_ENABLED 1
define AP_PERIPH_BATTERY_ENABLED 1
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
define HAL_PERIPH_ENABLE_NOTIFY
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ define HAL_COMPASS_MAX_SENSORS 1

# GPS+MAG+BARO+Buzzer+NeoPixels
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
define HAL_PERIPH_ENABLE_NOTIFY
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ define HAL_COMPASS_MAX_SENSORS 1


define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG 1
define AP_PERIPH_MAG_ENABLED 1 1
define GPS_MOVING_BASELINE 1
define HAL_PERIPH_GPS_PORT_DEFAULT 3

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ env ROMFS_UNCOMPRESSED True


define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO

# septentrio on com 3
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Compass/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ define HAL_DEVICE_THREAD_STACK 768
define AP_PARAM_MAX_EMBEDDED_PARAM 256

# MAG
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1

# keep ROMFS uncompressed as we don't have enough RAM
# to uncompress the bootloader at runtime
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ define HAL_PERIPH_ENABLE_IMU

# GPS+MAG+LEDs
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_IMU
define HAL_PERIPH_ENABLE_NOTIFY
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ define HAL_COMPASS_MAX_SENSORS 1

# GPS+MAG+BARO+LEDs
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_NOTIFY
define HAL_PERIPH_ENABLE_RC_OUT
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/MFE_POS3_CAN/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ define GPS_MOVING_BASELINE 1

# GPS+MAG+BARO+LEDs
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1

# GPS on 1st port
define HAL_PERIPH_GPS_PORT_DEFAULT 1
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/MatekG474-GPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ define GPS_MOVING_BASELINE 1


# ----------- COMPASS
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1

SPIDEV rm3100 SPI2 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ define GPS_MOVING_BASELINE 1


# ----------- COMPASS
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1

SPIDEV rm3100 SPI2 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ env AP_PERIPH 1


define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_AIRSPEED
define HAL_PERIPH_ENABLE_ADSB
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ define HAL_PERIPH_GPS_PORT_DEFAULT 2
# allow for F9P GPS modules with moving baseline
define GPS_MOVING_BASELINE 1

define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PROBE_EXTERNAL_I2C_COMPASSES

define HAL_COMPASS_MAX_SENSORS 1
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
include ../MatekL431/hwdef.inc


define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1

SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ define AP_GPS_SBF_ENABLED 0
define AP_GPS_GSOF_ENABLED 0

# ---------------------- COMPASS ---------------------------
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1

SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 512
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_GPS_PORT_DEFAULT 0

define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ PA4 VSENSE ADC1 SCALE(2)
define AP_PARAM_MAX_EMBEDDED_PARAM 512

define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_AIRSPEED

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ define AIRSPEED_MAX_SENSORS 1
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_GPS_PORT_DEFAULT 3

define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO

define AP_PERIPH_BATTERY_ENABLED 1
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1

# ---------------------- COMPASS ---------------------------
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1

SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ define HAL_COMPASS_MAX_SENSORS 1
# GPS+MAG+BARO+Buzzer+NeoPixels
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_GPS_PORT_DEFAULT 3
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
define HAL_PERIPH_ENABLE_NOTIFY
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ define HAL_COMPASS_MAX_SENSORS 1

# GPS+MAG+BARO+Buzzer+NeoPixels
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
define HAL_PERIPH_ENABLE_NOTIFY
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ PA0 VDD_5V_SENS ADC1 SCALE(2)

define AP_PARAM_MAX_EMBEDDED_PARAM 512

define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_AIRSPEED
define AIRSPEED_MAX_SENSORS 1
define HAL_AIRSPEED_TYPE_DEFAULT 1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ define HAL_COMPASS_MAX_SENSORS 1

# GPS+MAG+BARO+NeoPixels
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
define HAL_PERIPH_ENABLE_NOTIFY
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavIC/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ env ROMFS_UNCOMPRESSED True
# enable GPS and compass
define AP_PERIPH_GPS_ENABLED 1
define GPS_MAX_RATE_MS 200
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO

# disable dual GPS and GPS blending to save flash space
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ define HAL_COMPASS_MAX_SENSORS 1

# GPS+MAG+BARO+LEDs
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY 0
define HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY 8
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ env ROMFS_UNCOMPRESSED True

# enable GPS and compass
define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
define HAL_PERIPH_ENABLE_NOTIFY
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNorth/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
env ROMFS_UNCOMPRESSED True

# enable compass and airspeed
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_COMPASS_MAX_SENSORS 1

# PWM, WS2812 LED
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueSpeed/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
env ROMFS_UNCOMPRESSED True

# enable compass and airspeed
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_AIRSPEED
define HAL_COMPASS_MAX_SENSORS 1
define AIRSPEED_MAX_SENSORS 1
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ BARO MS56XX SPI:ms5611
define HAL_BARO_ALLOW_INIT_NO_BARO

define AP_PERIPH_GPS_ENABLED 1
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
define HAL_PERIPH_ENABLE_BARO

# reduce the number of CAN RX Buffer
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -10,4 +10,4 @@ define AIRSPEED_MAX_SENSORS 1
define HAL_PERIPH_ADSB_PORT_DEFAULT 3
define HAL_PERIPH_ENABLE_ADSB
define HAL_PERIPH_ENABLE_AIRSPEED
# define HAL_PERIPH_ENABLE_MAG
# define AP_PERIPH_MAG_ENABLED 1
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,6 @@ define AP_GPS_SBF_ENABLED 0
define AP_GPS_GSOF_ENABLED 0

# MAG
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
#define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY
define HAL_PERIPH_ENABLE_TOSHIBA_LED_WITHOUT_NOTIFY
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ define HAL_AIRSPEED_TYPE_DEFAULT 15
define AIRSPEED_MAX_SENSORS 1

define HAL_PERIPH_ENABLE_AIRSPEED
define HAL_PERIPH_ENABLE_MAG
define AP_PERIPH_MAG_ENABLED 1
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
Expand Down
Loading

0 comments on commit b17ab8f

Please sign in to comment.