diff --git a/libraries/AP_HAL_Linux/hwdef/aero/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/aero/hwdef.dat new file mode 100644 index 0000000000..b11ed8328d --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/aero/hwdef.dat @@ -0,0 +1,5 @@ +# Intel Aero board + +define HAL_RCOUTPUT_TAP_DEVICE "/dev/ttyS1" + +define HAL_NUM_CAN_IFACES 1 diff --git a/libraries/AP_HAL_Linux/hwdef/bbbmini/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/bbbmini/hwdef.dat new file mode 100644 index 0000000000..531f1d6424 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/bbbmini/hwdef.dat @@ -0,0 +1,11 @@ +# BeagleBoneBlue mini + +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 +define HAL_GPIO_A_LED_PIN 69 +define HAL_GPIO_B_LED_PIN 68 +define HAL_GPIO_C_LED_PIN 45 + +define HAL_BUZZER_PIN 11 +define HAL_OPTFLOW_PX4FLOW_I2C_BUS 2 +define HAL_RANGEFINDER_LIGHTWARE_I2C_BUS 2 +define HAL_NUM_CAN_IFACES 1 diff --git a/libraries/AP_HAL_Linux/hwdef/bebop/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/bebop/hwdef.dat new file mode 100644 index 0000000000..ac9da3dcdd --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/bebop/hwdef.dat @@ -0,0 +1,46 @@ +# Parrot Bebop multirotor + +define HAL_BOARD_LOG_DIRECTORY "/data/ftp/internal_000/ardupilot/logs" +define HAL_BOARD_TERRAIN_DIRECTORY "/data/ftp/internal_000/ardupilot/terrain" +define HAL_BOARD_STORAGE_DIRECTORY "/data/ftp/internal_000/ardupilot" + +# Heater support +define HAL_HAVE_IMU_HEATER 1 +define HAL_IMU_TEMP_DEFAULT 55 +define HAL_UTILS_HEAT HAL_LINUX_HEAT_PWM +define HAL_LINUX_HEAT_PWM_NUM 6 +define HAL_LINUX_HEAT_KP 20000 +define HAL_LINUX_HEAT_KI 6 +define HAL_LINUX_HEAT_PERIOD_NS 125000 +define HAL_LINUX_HEAT_TARGET_TEMP 50 + +define BEBOP_CAMV_PWM 9 +define BEBOP_CAMV_PWM_FREQ 43333333 + +# in-built optical flow support: +define OPTICAL_FLOW_TYPE_DEFAULT Type::BEBOP +define HAL_OPTFLOW_ONBOARD_VDEV_PATH "/dev/video0" +define HAL_OPTFLOW_ONBOARD_SUBDEV_PATH "/dev/v4l-subdev0" +define HAL_OPTFLOW_ONBOARD_SENSOR_WIDTH 320 +define HAL_OPTFLOW_ONBOARD_SENSOR_HEIGHT 240 +define HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH 64 +define HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT 64 +define HAL_OPTFLOW_ONBOARD_CROP_WIDTH 240 +define HAL_OPTFLOW_ONBOARD_CROP_HEIGHT 240 +define HAL_OPTFLOW_ONBOARD_NBUFS 8 +define HAL_FLOW_PX4_MAX_FLOW_PIXEL 4 +define HAL_FLOW_PX4_BOTTOM_FLOW_FEATURE_THRESHOLD 30 +define HAL_FLOW_PX4_BOTTOM_FLOW_VALUE_THRESHOLD 5000 + +define HAL_PARAM_DEFAULTS_PATH "/data/ftp/internal_000/ardupilot/bebop.parm" + +define HAL_RCOUT_BEBOP_BLDC_I2C_BUS 1 +define HAL_RCOUT_BEBOP_BLDC_I2C_ADDR 0x08 + +# focal length 2.21mm pixel size 3.6 um, 2x binning in each direction +# 240x240 crop rescaled to 64x64 +define HAL_FLOW_PX4_FOCAL_LENGTH_MILLIPX (2.21 / (3.6 * 2.0 * 240 / 64)) + +define HAL_RANGEFINDER_LIGHTWARE_I2C_BUS 0 + +define HAL_BATT_MONITOR_DEFAULT AP_BattMonitor::Type::BEBOP diff --git a/libraries/AP_HAL_Linux/hwdef/bhat/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/bhat/hwdef.dat new file mode 100644 index 0000000000..4963f315d2 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/bhat/hwdef.dat @@ -0,0 +1,11 @@ +# Board from 2016?! + +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 +define HAL_GPIO_A_LED_PIN 17 +define HAL_GPIO_B_LED_PIN 18 +define HAL_GPIO_C_LED_PIN 22 + +define AP_NOTIFY_RCOUTPUTRGBLED_LED_ENABLED 1 +define HAL_RCOUT_RGBLED_RED 13 +define HAL_RCOUT_RGBLED_GREEN 14 +define HAL_RCOUT_RGBLED_BLUE 15 diff --git a/libraries/AP_HAL_Linux/hwdef/blue/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/blue/hwdef.dat new file mode 100644 index 0000000000..c51f7130a7 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/blue/hwdef.dat @@ -0,0 +1,12 @@ +# BeagleBone Blue + +define AP_NOTIFY_GPIO_LED_2_ENABLED 1 +define HAL_GPIO_A_LED_PIN 66 +define HAL_GPIO_B_LED_PIN 67 +define HAL_GPIO_LED_ON 1 + +define HAL_OPTFLOW_PX4FLOW_I2C_BUS 1 + +define HAL_RANGEFINDER_LIGHTWARE_I2C_BUS 1 + +define HAL_NUM_CAN_IFACES 1 diff --git a/libraries/AP_HAL_Linux/hwdef/canzero/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/canzero/hwdef.dat new file mode 100644 index 0000000000..9e549923b2 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/canzero/hwdef.dat @@ -0,0 +1,17 @@ +# mRo CanZero support + +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +define HAL_NUM_CAN_IFACES 1 +define HAL_CAN_DRIVER_DEFAULT 1 + +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 +define HAL_GPIO_A_LED_PIN 22 +define HAL_GPIO_B_LED_PIN 27 +define HAL_GPIO_C_LED_PIN 6 + +define HAL_BOARD_LOG_DIRECTORY "/home/pi/ardupilot/logs" +define HAL_BOARD_TERRAIN_DIRECTORY "/home/pi/ardupilot/terrain" +define HAL_BOARD_STORAGE_DIRECTORY "/home/pi/ardupilot" + +define HAL_DEFAULT_INS_FAST_SAMPLE 0 diff --git a/libraries/AP_HAL_Linux/hwdef/dark/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/dark/hwdef.dat new file mode 100644 index 0000000000..c05c949fc0 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/dark/hwdef.dat @@ -0,0 +1,6 @@ +# ancient unknown board? + +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 +define HAL_GPIO_A_LED_PIN 24 +define HAL_GPIO_B_LED_PIN 25 +define HAL_GPIO_C_LED_PIN 16 diff --git a/libraries/AP_HAL_Linux/hwdef/disco/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/disco/hwdef.dat new file mode 100644 index 0000000000..a0239a4b53 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/disco/hwdef.dat @@ -0,0 +1,48 @@ +# Parrot Disco fixed-wing + +define HAL_BOARD_LOG_DIRECTORY "/data/ftp/internal_000/ardupilot/logs" +define HAL_BOARD_TERRAIN_DIRECTORY "/data/ftp/internal_000/ardupilot/terrain" +define HAL_BOARD_STORAGE_DIRECTORY "/data/ftp/internal_000/ardupilot" + +# heater support: +define HAL_UTILS_HEAT HAL_LINUX_HEAT_PWM +define HAL_LINUX_HEAT_PWM_NUM 10 +define HAL_LINUX_HEAT_KP 20000 +define HAL_LINUX_HEAT_KI 6 +define HAL_LINUX_HEAT_PERIOD_NS 125000 +define HAL_LINUX_HEAT_TARGET_TEMP 50 + +define BEBOP_CAMV_PWM 9 +define BEBOP_CAMV_PWM_FREQ 43333333 + +# in-built optical flow support: +define HAL_OPTFLOW_ONBOARD_VDEV_PATH "/dev/video0" +define HAL_OPTFLOW_ONBOARD_SUBDEV_PATH "/dev/v4l-subdev0" +define HAL_OPTFLOW_ONBOARD_SENSOR_WIDTH 320 +define HAL_OPTFLOW_ONBOARD_SENSOR_HEIGHT 240 +define HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH 64 +define HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT 64 +define HAL_OPTFLOW_ONBOARD_CROP_WIDTH 240 +define HAL_OPTFLOW_ONBOARD_CROP_HEIGHT 240 +define HAL_OPTFLOW_ONBOARD_NBUFS 8 +define HAL_FLOW_PX4_MAX_FLOW_PIXEL 4 +define HAL_FLOW_PX4_BOTTOM_FLOW_FEATURE_THRESHOLD 30 +define HAL_FLOW_PX4_BOTTOM_FLOW_VALUE_THRESHOLD 5000 + +define HAL_RCOUT_DISCO_BLDC_I2C_BUS 1 +define HAL_RCOUT_DISCO_BLDC_I2C_ADDR 0x08 + +define HAL_PARAM_DEFAULTS_PATH "/data/ftp/internal_000/ardupilot/disco.parm" + +# focal length 2.21mm pixel size 3.6 um, 2x binning in each direction +# 240x240 crop rescaled to 64x64 +#define HAL_FLOW_PX4_FOCAL_LENGTH_MILLIPX (2.21 / (3.6 * 2.0 * 240 / 64)) + +#define HAL_RANGEFINDER_LIGHTWARE_I2C_BUS 0 + +# the disco has challenges with its magnetic setup +define AP_COMPASS_OFFSETS_MAX_DEFAULT 2200 +define HAL_BATT_MONITOR_DEFAULT AP_BattMonitor::Type::BEBOP +define HAL_GPIO_SCRIPT "/data/ftp/internal_000/ardupilot/gpio.sh" + +define AP_NOTIFY_DISCO_LED_ENABLED 1 diff --git a/libraries/AP_HAL_Linux/hwdef/edge/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/edge/hwdef.dat new file mode 100644 index 0000000000..ed8cad25f1 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/edge/hwdef.dat @@ -0,0 +1,26 @@ +# Emlid Edge board + +define HAL_BOARD_LOG_DIRECTORY "/edge/ardupilot/logs" +define HAL_BOARD_TERRAIN_DIRECTORY "/edge/ardupilot/terrain" +define HAL_BOARD_STORAGE_DIRECTORY "/edge/ardupilot" + +define HAL_NUM_CAN_IFACES 1 + +# heater support +define HAL_IMU_TEMP_DEFAULT 55 +define HAL_HAVE_IMU_HEATER 1 +define HAL_UTILS_HEAT HAL_LINUX_HEAT_PWM +define HAL_LINUX_HEAT_PWM_NUM 15 +define HAL_LINUX_HEAT_KP 20000 +define HAL_LINUX_HEAT_KI 6 +define HAL_LINUX_HEAT_PERIOD_NS 2040816 + +# default to DroneCAN GPS: +define HAL_GPS1_TYPE_DEFAULT 9 + +define HAL_CAN_DRIVER_DEFAULT 1 + +# this looks suspect: +define AP_NOTIFY_RCOUTPUTRGBLEDINVERTED_LED_ENABLED 1 + +define AP_RCPROTOCOL_EMLID_RCIO_ENABLED 1 diff --git a/libraries/AP_HAL_Linux/hwdef/erleboard/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/erleboard/hwdef.dat new file mode 100644 index 0000000000..67c158d63b --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/erleboard/hwdef.dat @@ -0,0 +1,6 @@ +# board from Erle robotics + +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 +define HAL_GPIO_A_LED_PIN 61 +define HAL_GPIO_B_LED_PIN 48 +define HAL_GPIO_C_LED_PIN 117 diff --git a/libraries/AP_HAL_Linux/hwdef/erlebrain2/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/erlebrain2/hwdef.dat new file mode 100644 index 0000000000..1f7741d3b9 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/erlebrain2/hwdef.dat @@ -0,0 +1,6 @@ +# Erle Robotics Brain 2 + +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 +define HAL_GPIO_A_LED_PIN 24 +define HAL_GPIO_B_LED_PIN 25 +define HAL_GPIO_C_LED_PIN 16 diff --git a/libraries/AP_HAL_Linux/hwdef/linux/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/linux/hwdef.dat new file mode 100644 index 0000000000..c1b215f50a --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/linux/hwdef.dat @@ -0,0 +1,7 @@ +# hwdef for generic Linux configuration option, eg. running on your laptop + +define HAL_BOARD_LOG_DIRECTORY "logs" +define HAL_BOARD_TERRAIN_DIRECTORY "terrain" +define HAL_BOARD_STORAGE_DIRECTORY "." +define HAL_INS_DEFAULT HAL_INS_NONE +define HAL_BARO_DEFAULT HAL_BARO_NONE diff --git a/libraries/AP_HAL_Linux/hwdef/navigator/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/navigator/hwdef.dat new file mode 100644 index 0000000000..c437b4b12b --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/navigator/hwdef.dat @@ -0,0 +1,8 @@ +# BlueRobotics Navigator + +# I2C6 is the only i2c one exposed on a header +define HAL_LINUX_I2C_EXTERNAL_BUS_MASK 1 << 6 + +# We don't want any probing on the internal buses +define HAL_LINUX_I2C_INTERNAL_BUS_MASK 0 +define AP_NOTIFY_NAVIGATOR_LED_ENABLED 1 diff --git a/libraries/AP_HAL_Linux/hwdef/navigator64/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/navigator64/hwdef.dat new file mode 100644 index 0000000000..eb6ef82e5c --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/navigator64/hwdef.dat @@ -0,0 +1 @@ +include ../navigator/hwdef.dat diff --git a/libraries/AP_HAL_Linux/hwdef/navio/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/navio/hwdef.dat new file mode 100644 index 0000000000..9b789dc4ae --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/navio/hwdef.dat @@ -0,0 +1,7 @@ +# Emlid NaviO + +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 +define HAL_GPIO_LED_ON 1 diff --git a/libraries/AP_HAL_Linux/hwdef/navio2/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/navio2/hwdef.dat new file mode 100644 index 0000000000..5c51a528c6 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/navio2/hwdef.dat @@ -0,0 +1,5 @@ +# Emlid NaviO2 + +define HAL_HAVE_SERVO_VOLTAGE 1 +define AP_NOTIFY_SYSFS_LED_ENABLED 1 +define AP_RCPROTOCOL_EMLID_RCIO_ENABLED 1 diff --git a/libraries/AP_HAL_Linux/hwdef/obal/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/obal/hwdef.dat new file mode 100644 index 0000000000..5664017e58 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/obal/hwdef.dat @@ -0,0 +1,17 @@ +# Open Board Architecture for Linux + +define HAL_BOARD_LOG_DIRECTORY "/home/pi/ardupilot/logs" +define HAL_BOARD_TERRAIN_DIRECTORY "/home/pi/ardupilot/terrain" +define HAL_BOARD_STORAGE_DIRECTORY "/home/pi/ardupilot" +define HAL_PARAM_DEFAULTS_PATH "/home/pi/ardupilot.parm" + +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 +define HAL_GPIO_A_LED_PIN 27 // You can choose between 27,22,4,12 +define HAL_GPIO_C_LED_PIN 22 // You can choose between 27,22,4,12 +define HAL_GPIO_B_LED_PIN 4 // You can choose between 27,22,4,12 +define HAL_GPIO_LED_ON 1 + +define HAL_BUZZER_PIN 12 // You can choose between 27,22,4,12 +define OBAL_ALLOW_ADC 1 + +define HAL_BOARD_SUBTYPE_LINUX_OBAL_V1_MPU_9250_SPI 1 diff --git a/libraries/AP_HAL_Linux/hwdef/ocpoc_zynq/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/ocpoc_zynq/hwdef.dat new file mode 100644 index 0000000000..e69de29bb2 diff --git a/libraries/AP_HAL_Linux/hwdef/pocket/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/pocket/hwdef.dat new file mode 100644 index 0000000000..bd34123d06 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/pocket/hwdef.dat @@ -0,0 +1,15 @@ +# PocketPilot + +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 +define HAL_GPIO_A_LED_PIN 59 +define HAL_GPIO_B_LED_PIN 58 +define HAL_GPIO_C_LED_PIN 57 +define HAL_GPIO_LED_ON 1 + +define HAL_BUZZER_PIN 28 + +define HAL_OPTFLOW_PX4FLOW_I2C_BUS 2 + +define HAL_RANGEFINDER_LIGHTWARE_I2C_BUS 2 + +define HAL_NUM_CAN_IFACES 1 diff --git a/libraries/AP_HAL_Linux/hwdef/pxf/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/pxf/hwdef.dat new file mode 100644 index 0000000000..459b11d47a --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/pxf/hwdef.dat @@ -0,0 +1,8 @@ +# hwdef for Pixhawk firecape + +define AP_NOTIFY_TONEALARM_ENABLED 1 + +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 +define HAL_GPIO_A_LED_PIN 61 +define HAL_GPIO_B_LED_PIN 48 +define HAL_GPIO_C_LED_PIN 117 diff --git a/libraries/AP_HAL_Linux/hwdef/pxfmini/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/pxfmini/hwdef.dat new file mode 100644 index 0000000000..8cda165293 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/pxfmini/hwdef.dat @@ -0,0 +1,6 @@ +# Pixhawk FireCape Mini + +define AP_NOTIFY_GPIO_LED_3_ENABLED 1 +define HAL_GPIO_A_LED_PIN 24 +define HAL_GPIO_B_LED_PIN 25 +define HAL_GPIO_C_LED_PIN 16 diff --git a/libraries/AP_HAL_Linux/hwdef/rst_zynq/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/rst_zynq/hwdef.dat new file mode 100644 index 0000000000..809d6d4322 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/rst_zynq/hwdef.dat @@ -0,0 +1,3 @@ +# Aerotenna Zynq board + +define HAL_OPTFLOW_PX4FLOW_I2C_BUS 0 diff --git a/libraries/AP_HAL_Linux/hwdef/scripts/linux_hwdef.py b/libraries/AP_HAL_Linux/hwdef/scripts/linux_hwdef.py new file mode 100644 index 0000000000..b7c5956b2d --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/scripts/linux_hwdef.py @@ -0,0 +1,45 @@ +#!/usr/bin/env python +''' +setup board.h for Linux + +AP_FLAKE8_CLEAN + +''' + +import argparse +import sys +import os + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../../../libraries/AP_HAL/hwdef/scripts')) +import hwdef # noqa:E402 + + +class LinuxHWDef(hwdef.HWDef): + + def __init__(self, quiet=False, outdir=None, hwdef=[]): + super(LinuxHWDef, self).__init__(quiet=quiet, outdir=outdir, hwdef=hwdef) + + def write_hwdef_header_content(self, f): + for d in self.alllines: + if d.startswith('define '): + f.write('#define %s\n' % d[7:]) + + +if __name__ == '__main__': + + parser = argparse.ArgumentParser("linux_hwdef.py") + parser.add_argument( + '-D', '--outdir', type=str, default="/tmp", help='Output directory') + parser.add_argument( + 'hwdef', type=str, nargs='+', default=None, help='hardware definition file') + parser.add_argument( + '--quiet', action='store_true', default=False, help='quiet running') + + args = parser.parse_args() + + c = LinuxHWDef( + outdir=args.outdir, + hwdef=args.hwdef, + quiet=args.quiet, + ) + c.run() diff --git a/libraries/AP_HAL_Linux/hwdef/vnav/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/vnav/hwdef.dat new file mode 100644 index 0000000000..98948b3c86 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/vnav/hwdef.dat @@ -0,0 +1,7 @@ +# linux SBC with VectorNav AHRS + +define HAL_EXTERNAL_AHRS_DEFAULT 1 +define DEFAULT_SERIAL3_PROTOCOL 36 +define HAL_AIRSPEED_TYPE_DEFAULT 0 +define HAL_GPS1_TYPE_DEFAULT 21 +define HAL_AHRS_EKF_TYPE_DEFAULT 11 diff --git a/libraries/AP_HAL_Linux/hwdef/zynq/hwdef.dat b/libraries/AP_HAL_Linux/hwdef/zynq/hwdef.dat new file mode 100644 index 0000000000..edcb4b84a2 --- /dev/null +++ b/libraries/AP_HAL_Linux/hwdef/zynq/hwdef.dat @@ -0,0 +1,6 @@ +# Stub the sensors out for now, at least we can build and run +define HAL_INS_DEFAULT HAL_INS_NONE +define HAL_BARO_DEFAULT HAL_BARO_NONE + +# only external compasses +define HAL_PROBE_EXTERNAL_I2C_COMPASSES