Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 0 additions & 5 deletions Tools/autotest/sim_vehicle.py
Original file line number Diff line number Diff line change
Expand Up @@ -258,11 +258,6 @@ def kill_tasks_pkill(victims):
run_cmd_blocking("pkill", cmd, quiet=True)


class BobException(Exception):
"""Handle Bob's Exceptions"""
pass


def kill_tasks():
"""Clean up stray processes by name. This is a shotgun approach"""
progress("Killing tasks")
Expand Down
51 changes: 26 additions & 25 deletions libraries/AP_Compass/AP_Compass.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1109,18 +1109,19 @@ bool Compass::_have_i2c_driver(uint8_t bus, uint8_t address) const
*/
void Compass::_probe_external_i2c_compasses(void)
{
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#if AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
bool all_external = (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2);
(void)all_external; // in case all backends using this are compiled out
#endif
#endif // AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED

#if AP_COMPASS_HMC5843_ENABLED
// external i2c bus
FOREACH_I2C_EXTERNAL(i) {
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
true, ROTATION_ROLL_180));
}

#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#if AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_MINDPXV2 &&
AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_AEROFC) {
// internal i2c bus
Expand All @@ -1129,7 +1130,7 @@ void Compass::_probe_external_i2c_compasses(void)
all_external, all_external?ROTATION_ROLL_180:ROTATION_YAW_270));
}
}
#endif // !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#endif // AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
#endif // AP_COMPASS_HMC5843_ENABLED

#if AP_COMPASS_QMC5883L_ENABLED
Expand All @@ -1140,7 +1141,7 @@ void Compass::_probe_external_i2c_compasses(void)
}

// internal i2c bus
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#if AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
if (all_external) {
// only probe QMC5883L on internal if we are treating internals as externals
FOREACH_I2C_INTERNAL(i) {
Expand All @@ -1149,7 +1150,7 @@ void Compass::_probe_external_i2c_compasses(void)
all_external?HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL));
}
}
#endif
#endif // AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
#endif // AP_COMPASS_QMC5883L_ENABLED

#if AP_COMPASS_QMC5883P_ENABLED
Expand All @@ -1160,7 +1161,7 @@ void Compass::_probe_external_i2c_compasses(void)
}

// internal i2c bus
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#if AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
if (all_external) {
// only probe QMC5883P on internal if we are treating internals as externals
FOREACH_I2C_INTERNAL(i) {
Expand All @@ -1169,7 +1170,7 @@ void Compass::_probe_external_i2c_compasses(void)
all_external?HAL_COMPASS_QMC5883P_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883P_ORIENTATION_INTERNAL));
}
}
#endif
#endif // AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
#endif // AP_COMPASS_QMC5883P_ENABLED

#if AP_COMPASS_IIS2MDC_ENABLED
Expand All @@ -1180,7 +1181,7 @@ void Compass::_probe_external_i2c_compasses(void)
}

// internal i2c bus
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#if AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
if (all_external) {
// only probe IIS2MDC on internal if we are treating internals as externals
FOREACH_I2C_INTERNAL(i) {
Expand All @@ -1189,7 +1190,7 @@ void Compass::_probe_external_i2c_compasses(void)
all_external?HAL_COMPASS_IIS2MDC_ORIENTATION_EXTERNAL:HAL_COMPASS_IIS2MDC_ORIENTATION_INTERNAL));
}
}
#endif
#endif // AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
#endif // AP_COMPASS_QMC5883P_ENABLED

// AK09916 on ICM20948
Expand All @@ -1203,7 +1204,7 @@ void Compass::_probe_external_i2c_compasses(void)
true, ROTATION_PITCH_180_YAW_90));
}

#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#if AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
FOREACH_I2C_INTERNAL(i) {
ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR),
Expand All @@ -1212,12 +1213,12 @@ void Compass::_probe_external_i2c_compasses(void)
GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR2),
all_external, ROTATION_PITCH_180_YAW_90));
}
#endif
#endif // AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
#endif // AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED

#if AP_COMPASS_LIS3MDL_ENABLED
// lis3mdl on bus 0 with default address
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#if AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
FOREACH_I2C_INTERNAL(i) {
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),
all_external, all_external?ROTATION_YAW_90:ROTATION_NONE));
Expand Down Expand Up @@ -1248,12 +1249,12 @@ void Compass::_probe_external_i2c_compasses(void)
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
true, ROTATION_YAW_270));
}
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#if AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
FOREACH_I2C_INTERNAL(i) {
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
all_external, all_external?ROTATION_YAW_270:ROTATION_NONE));
}
#endif
#endif // AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
#endif // AP_COMPASS_AK09916_ENABLED

#if AP_COMPASS_IST8310_ENABLED
Expand All @@ -1273,12 +1274,12 @@ void Compass::_probe_external_i2c_compasses(void)
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]),
true, default_rotation));
}
#if !defined(HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE) && !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#if AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED
FOREACH_I2C_INTERNAL(i) {
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]),
all_external, default_rotation));
}
#endif
#endif // AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED
}
}
#endif // AP_COMPASS_IST8310_ENABLED
Expand All @@ -1289,12 +1290,12 @@ void Compass::_probe_external_i2c_compasses(void)
ADD_BACKEND(DRIVER_IST8308, AP_Compass_IST8308::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8308_I2C_ADDR),
true, ROTATION_NONE));
}
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#if AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
FOREACH_I2C_INTERNAL(i) {
ADD_BACKEND(DRIVER_IST8308, AP_Compass_IST8308::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8308_I2C_ADDR),
all_external, ROTATION_NONE));
}
#endif
#endif // AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
#endif // AP_COMPASS_IST8308_ENABLED

#if AP_COMPASS_MMC3416_ENABLED
Expand All @@ -1303,12 +1304,12 @@ void Compass::_probe_external_i2c_compasses(void)
ADD_BACKEND(DRIVER_MMC3416, AP_Compass_MMC3416::probe(GET_I2C_DEVICE(i, HAL_COMPASS_MMC3416_I2C_ADDR),
true, ROTATION_NONE));
}
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#if AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
FOREACH_I2C_INTERNAL(i) {
ADD_BACKEND(DRIVER_MMC3416, AP_Compass_MMC3416::probe(GET_I2C_DEVICE(i, HAL_COMPASS_MMC3416_I2C_ADDR),
all_external, ROTATION_NONE));
}
#endif
#endif // AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
#endif // AP_COMPASS_MMC3416_ENABLED

#if AP_COMPASS_RM3100_ENABLED
Expand All @@ -1328,13 +1329,13 @@ void Compass::_probe_external_i2c_compasses(void)
}
}

#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#if AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
FOREACH_I2C_INTERNAL(i) {
for (uint8_t j=0; j<ARRAY_SIZE(rm3100_addresses); j++) {
ADD_BACKEND(DRIVER_RM3100, AP_Compass_RM3100::probe(GET_I2C_DEVICE(i, rm3100_addresses[j]), all_external, ROTATION_NONE));
}
}
#endif
#endif // AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
#endif // AP_COMPASS_RM3100_ENABLED

#if AP_COMPASS_BMM150_ENABLED
Expand All @@ -1355,13 +1356,13 @@ void Compass::_probe_external_i2c_compasses(void)
AP_Compass_BMM350::probe(GET_I2C_DEVICE(i, addr), true, ROTATION_NONE));
}
}
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
#if AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
FOREACH_I2C_INTERNAL(i) {
for (uint8_t addr=BMM350_I2C_ADDR_MIN; addr <= BMM350_I2C_ADDR_MAX; addr++) {
ADD_BACKEND(DRIVER_BMM350, AP_Compass_BMM350::probe(GET_I2C_DEVICE(i, addr), all_external, ROTATION_NONE));
}
}
#endif
#endif // AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
#endif // AP_COMPASS_BMM350_ENABLED
}

Expand Down
13 changes: 13 additions & 0 deletions libraries/AP_Compass/AP_Compass_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -132,3 +132,16 @@
// FIXME: vast majority of boards define this to 1!
#define AP_COMPASS_PROBING_ENABLED 0
#endif

// boards can specify that they do not want their internal buses
// probed for compasses - we default to probing them if we are probing
// any buses:
#ifndef AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED
#define AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED (AP_COMPASS_PROBING_ENABLED || AP_FEATURE_BOARD_DETECT)
#endif

// some boards do not want to probe the internal buses for IS8310 but
// *do* want to probe internal buses for other compasses:
#ifndef AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED
#define AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED (AP_COMPASS_IST8310_ENABLED && AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED)
#endif
2 changes: 2 additions & 0 deletions libraries/AP_HAL/hwdef/scripts/hwdef.py
Original file line number Diff line number Diff line change
Expand Up @@ -254,6 +254,8 @@ def get_stale_defines(self):
'HAL_DISABLE_LOOP_DELAY': 'HAL_DISABLE_LOOP_DELAY is no longer used; try "define HAL_SCHEDULER_LOOP_DELAY_ENABLED 0"', # noqa:E501
'HAL_EXTERNAL_AHRS_ENABLED': 'HAL_EXTERNAL_AHRS_ENABLED is no longer used; try "define AP_EXTERNAL_AHRS_ENABLED 1"', # noqa:E501
'HAL_PROBE_EXTERNAL_I2C_COMPASSES': 'HAL_PROBE_EXTERNAL_I2C_COMPASSES is no longer used; try "define AP_COMPASS_PROBING_ENABLED 1"', # noqa:E501
'HAL_SKIP_AUTO_INTERNAL_I2C_PROBE': 'HAL_SKIP_AUTO_INTERNAL_I2C_PROBE is no longer used; try "define AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED 0', # noqa:E501
'HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE': 'HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE is no longer used; try "define AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED 0"', # noqa:E501
}

def assert_good_define(self, name):
Expand Down
5 changes: 3 additions & 2 deletions libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 40
# compass
define AP_COMPASS_PROBING_ENABLED 1

define HAL_SKIP_AUTO_INTERNAL_I2C_PROBE
define AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED 0

define HAL_I2C_INTERNAL_MASK 1

Expand Down Expand Up @@ -233,4 +233,5 @@ define HAL_BATT_CURR_SCALE 40
define HAL_BATT2_VOLT_PIN 10
define HAL_BATT2_CURR_PIN 11
define HAL_BATT2_VOLT_SCALE 34
define HAL_BATT2_CURR_SCALE 40
define HAL_BATT2_CURR_SCALE 40

2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CORVON743V1/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ define HAL_BATT_VOLT_SCALE 21.12
define HAL_BATT_CURR_SCALE 40.2

# compass
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
define AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED 0
define AP_COMPASS_PROBING_ENABLED 1
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_NONE
COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_YAW_90
Expand Down
3 changes: 1 addition & 2 deletions libraries/AP_HAL_ChibiOS/hwdef/CUAV-7-Nano/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -265,8 +265,7 @@ BARO ICP201XX I2C:1:0x63

# compass
define AP_COMPASS_PROBING_ENABLED 1
define HAL_SKIP_AUTO_INTERNAL_I2C_PROBE
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
define AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED 0
define AP_COMPASS_IST8310_DEFAULT_ROTATION ROTATION_ROLL_180_YAW_90
COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_90_YAW_90
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CUAV-X25-EVO/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -308,7 +308,7 @@ BARO ICP201XX I2C:0:0x63

# compass
define AP_COMPASS_PROBING_ENABLED 1
define HAL_SKIP_AUTO_INTERNAL_I2C_PROBE
define AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED 0
COMPASS RM3100 SPI:rm3100 false ROTATION_NONE

# IMUs
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ undef I2C_ORDER
PF14 I2C4_SCL I2C4
PF15 I2C4_SDA I2C4

define HAL_SKIP_AUTO_INTERNAL_I2C_PROBE
define AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED 0
define HAL_I2C_INTERNAL_MASK 4

I2C_ORDER I2C2 I2C1 I2C4
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -279,7 +279,7 @@ NODMA I2C*
define STM32_I2C_USE_DMA FALSE

# builtin compass on JAE JFB110
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
define AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED 0
define AP_COMPASS_PROBING_ENABLED 1
COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_YAW_270
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ define HAL_BATT_VOLT_SCALE 21.12
define HAL_BATT_CURR_SCALE 40.2

# compass
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
define AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED 0
define AP_COMPASS_PROBING_ENABLED 1
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_NONE
COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_YAW_90
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,7 @@ define HAL_HEATER_MAG_OFFSET {AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TY


# we need to stop the probe of an IST8310 as an internal compass with PITCH_180
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
define AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED 0


# SPI devices
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/RadiolinkPIX6/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ define HAL_DEFAULT_INS_FAST_SAMPLE 1
define AP_COMPASS_PROBING_ENABLED 1

# we need to stop the probe of an IST8310 as an internal compass with PITCH_180
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
define AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED 0
COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_YAW_180

# one baro
Expand Down
3 changes: 1 addition & 2 deletions libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -248,8 +248,7 @@ define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1

# compass
define AP_COMPASS_PROBING_ENABLED 1
define HAL_SKIP_AUTO_INTERNAL_I2C_PROBE
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
define AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED 0
define AP_COMPASS_IST8310_DEFAULT_ROTATION ROTATION_ROLL_180_YAW_90
COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_90_YAW_90
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/SVehicle-E2/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -288,7 +288,7 @@ BARO ICP201XX I2C:2:0x63

# compass
define AP_COMPASS_PROBING_ENABLED 1
define HAL_SKIP_AUTO_INTERNAL_I2C_PROBE
define AP_COMPASS_INTERNAL_BUS_PROBING_ENABLED 0
COMPASS RM3100 I2C:0:0x20 false ROTATION_PITCH_180

# IMU devices for E2_Controller
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/X-MAV-AP-H743v2/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,7 @@ IMU BMI088 SPI:imu0_a SPI:imu0_g ROTATION_ROLL_180_YAW_90
IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180

# compasses
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
define AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED 0
define AP_COMPASS_PROBING_ENABLED 1
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_NONE
COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_YAW_90
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -201,7 +201,7 @@ BARO MS5611 SPI:ms5611
BARO ICP201XX I2C:0:0x64

# compass
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
define AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED 0
define AP_COMPASS_PROBING_ENABLED 1

COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -208,7 +208,7 @@ BARO MS5611 SPI:ms5611
BARO ICP201XX I2C:0:0x64

# compass
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
define AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED 0
define AP_COMPASS_PROBING_ENABLED 1

COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6Ultra/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,7 @@ BARO DPS310 SPI:dps310_1
BARO DPS310 SPI:dps310_2

# compass
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
define AP_COMPASS_IST8310_INTERNAL_BUS_PROBING_ENABLED 0
define AP_COMPASS_PROBING_ENABLED 1

COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
Expand Down
Loading