mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_RangeFinder: maxbotix: use i2c-address parameter
This commit is contained in:
parent
5e00f5ae48
commit
78b49a2c35
@ -350,15 +350,20 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
||||
}
|
||||
}
|
||||
break;
|
||||
case Type::MBI2C:
|
||||
case Type::MBI2C: {
|
||||
uint8_t addr = AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR;
|
||||
if (params[instance].address != 0) {
|
||||
addr = params[instance].address;
|
||||
}
|
||||
FOREACH_I2C(i) {
|
||||
if (_add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(state[instance], params[instance],
|
||||
hal.i2c_mgr->get_device(i, AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR)),
|
||||
hal.i2c_mgr->get_device(i, addr)),
|
||||
instance)) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
case Type::LWI2C:
|
||||
if (params[instance].address) {
|
||||
// the LW20 needs a long time to boot up, so we delay 1.5s here
|
||||
|
Loading…
Reference in New Issue
Block a user