Skip to content
Open
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
23 changes: 23 additions & 0 deletions libraries/AP_Compass/AP_Compass.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1568,6 +1568,17 @@ void Compass::probe_ak8963_via_mpu9250(uint8_t imu_instance, Rotation rotation)
auto *backend = AP_Compass_AK8963::probe_mpu9250(imu_instance, rotation);
add_backend(DRIVER_AK8963, backend); // add_backend does nullptr check
}
void Compass::probe_ak8963_via_mpu9250(uint8_t i2c_bus, uint8_t ak8963_addr, Rotation rotation)
{
if (!_driver_enabled(DRIVER_AK8963)) {
return;
}
auto *backend = AP_Compass_AK8963::probe_mpu9250(
GET_I2C_DEVICE(i2c_bus, ak8963_addr),
rotation
);
add_backend(DRIVER_AK8963, backend); // add_backend does nullptr check
}
#endif // AP_COMPASS_AK8963_ENABLED

#if AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED
Expand Down Expand Up @@ -1613,6 +1624,18 @@ void Compass::probe_i2c_dev(DriverType driver_type, probe_i2c_dev_probefn_t prob
add_backend(driver_type, backend); // add_backend does nullptr check
}

// short-lived method which expectes a probe function that doesn't
// offer the ability to specify the compass as external:
void Compass::probe_i2c_dev(DriverType driver_type, probe_i2c_dev_noexternal_probefn_t probefn, uint8_t i2c_bus, uint8_t i2c_addr, Rotation rotation)
{
if (!_driver_enabled(driver_type)) {
return;
}
auto *backend = probefn(GET_I2C_DEVICE(i2c_bus, i2c_addr), rotation);

add_backend(driver_type, backend); // add_backend does nullptr check
}

void Compass::probe_spi_dev(DriverType driver_type, probe_spi_dev_probefn_t probefn, const char *name, bool external, Rotation rotation)
{
if (!_driver_enabled(driver_type)) {
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_Compass/AP_Compass.h
Original file line number Diff line number Diff line change
Expand Up @@ -506,11 +506,17 @@ friend class AP_Compass_DroneCAN;
// helper probe functions
void probe_ak09916_via_icm20948(uint8_t i2c_bus, uint8_t ak09916_addr, uint8_t icm20948_addr, bool external, Rotation rotation);
void probe_ak09916_via_icm20948(uint8_t ins_instance, Rotation rotation);
void probe_ak8963_via_mpu9250(uint8_t i2c_bus, uint8_t ak8963_addr, Rotation rotation);
void probe_ak8963_via_mpu9250(uint8_t imu_instance, Rotation rotation);

using probe_i2c_dev_probefn_t = AP_Compass_Backend* (*)(AP_HAL::OwnPtr<AP_HAL::Device>, bool, Rotation);
void probe_i2c_dev(DriverType driver_type, probe_i2c_dev_probefn_t probefn, uint8_t i2c_bus, uint8_t i2c_addr, bool external, Rotation rotation);

// short-lived method which expectes a probe function that doesn't
// offer the ability to specify the compass as external:
using probe_i2c_dev_noexternal_probefn_t = AP_Compass_Backend* (*)(AP_HAL::OwnPtr<AP_HAL::Device>, Rotation);
void probe_i2c_dev(DriverType driver_type, probe_i2c_dev_noexternal_probefn_t, uint8_t i2c_bus, uint8_t i2c_addr, Rotation rotation);

using probe_spi_dev_probefn_t = AP_Compass_Backend* (*)(AP_HAL::OwnPtr<AP_HAL::Device>, bool, Rotation);
void probe_spi_dev(DriverType driver_type, probe_spi_dev_probefn_t probefn, const char *name, bool external, Rotation rotation);
// short-lived method which expects a probe function that doesn't
Expand Down
70 changes: 51 additions & 19 deletions libraries/AP_HAL/hwdef/scripts/hwdef.py
Original file line number Diff line number Diff line change
Expand Up @@ -441,6 +441,10 @@ def process_line_COMPASS(self, line, depth, a):
if len(a) > 1 and a[1].startswith('probe'):
probe = a[1]

# these two are aliases:
if probe == 'probe_ICM20948_SPI':
probe = 'probe_ICM20948'

expected_device_count = 1
if driver == 'AK09916' and probe == 'probe_ICM20948':
expected_device_count = 1
Expand Down Expand Up @@ -510,30 +514,58 @@ def write_MAG_config(self, f):
n = len(devlist)+1
devlist.append('HAL_MAG_PROBE%u' % n)

def i2c_dev_as_arguments_string(dev):
if dev.buses_to_probe == 'SINGLE':
busnum = str(dev.busnum)
elif dev.buses_to_probe in {'ALL', 'ALL_EXTERNAL', 'ALL_INTERNAL'}:
busnum = 'b'
else:
raise ValueError("Unexpected {buses_to_probe=}")
return "%s, 0x%02x" % (busnum, dev.busaddr)

args = []
for dev in compass.devlist:
if isinstance(dev, I2CDev):
if dev.buses_to_probe == 'SINGLE':
busnum = str(dev.busnum)
elif dev.buses_to_probe in {'ALL', 'ALL_EXTERNAL', 'ALL_INTERNAL'}:
busnum = 'b'
if probe == "probe":
for dev in compass.devlist:
if isinstance(dev, I2CDev):
compass_probe_method = 'probe_i2c_dev'
args.append(f"DRIVER_{compass.driver}")
args.append(f'AP_Compass_{compass.driver}::probe')
args.append(i2c_dev_as_arguments_string(dev))
elif isinstance(dev, SPIDev):
compass_probe_method = 'probe_spi_dev'
args.append(f"DRIVER_{compass.driver}")
args.append(f'AP_Compass_{compass.driver}::probe')
args.append(f'"{dev.name}"')
elif dev.isdigit():
args.append(str(dev))
else:
raise ValueError("Unexpected {buses_to_probe=}")
args.extend(["GET_I2C_DEVICE(%s,0x%02x)" % (busnum, dev.busaddr)])
elif isinstance(dev, SPIDev):
args.extend([f'hal.spi->get_device("{dev.name}")'])
elif dev.isdigit():
args.extend([str(dev)])
raise ValueError("unexpected devbit {dev=}")

if compass.force_external is not None:
args.append(str(compass.force_external))
args.append(str(compass.rotation))
elif probe in {'probe_ICM20948', 'probe_mpu9250'}:
if probe == 'probe_ICM20948':
compass_probe_method = 'probe_ak09916_via_icm20948'
elif probe == 'probe_mpu9250':
compass_probe_method = 'probe_ak8963_via_mpu9250'
else:
raise ValueError(f"Invalid {probe=}")
if len(compass.devlist) != 1:
raise ValueError(f"Expected 0 arguments for {probe} ({compass.devlist=}")
if isinstance(compass.devlist[0], I2CDev):
devstring = i2c_dev_as_arguments_string(compass.devlist[0])
else:
raise ValueError("unexpected devbit {dev=}")
devstring = compass.devlist[0]
args.append(devstring)
if compass.force_external is not None:
args.append(str(compass.force_external))
args.append(str(compass.rotation))
else:
raise ValueError(f"Unknown probe method {probe=}")

if compass.force_external is not None:
args.append(str(compass.force_external))
args.append(str(compass.rotation))
f.write(f'#define HAL_MAG_PROBE{n} {wrapper} {{{compass_probe_method}({", ".join(args)});RETURN_IF_NO_SPACE;}}\n')

f.write(
'#define HAL_MAG_PROBE%u %s {add_backend(DRIVER_%s, AP_Compass_%s::%s(%s));RETURN_IF_NO_SPACE;}\n'
% (n, wrapper, driver, driver, probe, ','.join(args)))
f.write(f"#undef AP_COMPASS_{driver}_ENABLED\n#define AP_COMPASS_{driver}_ENABLED 1\n")
if len(devlist) > 0:
f.write('#define HAL_MAG_PROBE_LIST %s\n\n' % ';'.join(devlist))
Expand Down
Loading