mirror of https://github.com/ArduPilot/ardupilot
AP_Rangefinder: Use default address for TFMiniPlus I2C unless configured
This fixes the issue #13419. If RNGFNDx_ADDR is not configured, it uses default address for TFmini i2c
This commit is contained in:
parent
04ba26a080
commit
e1a528213d
|
@ -414,15 +414,20 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case Type::BenewakeTFminiPlus:
|
case Type::BenewakeTFminiPlus: {
|
||||||
|
uint8_t addr = TFMINI_ADDR_DEFAULT;
|
||||||
|
if (params[instance].address != 0) {
|
||||||
|
addr = params[instance].address;
|
||||||
|
}
|
||||||
FOREACH_I2C(i) {
|
FOREACH_I2C(i) {
|
||||||
if (_add_backend(AP_RangeFinder_Benewake_TFMiniPlus::detect(state[instance], params[instance],
|
if (_add_backend(AP_RangeFinder_Benewake_TFMiniPlus::detect(state[instance], params[instance],
|
||||||
hal.i2c_mgr->get_device(i, params[instance].address)),
|
hal.i2c_mgr->get_device(i, addr)),
|
||||||
instance)) {
|
instance)) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
}
|
||||||
case Type::PX4_PWM:
|
case Type::PX4_PWM:
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
#ifndef HAL_BUILD_AP_PERIPH
|
#ifndef HAL_BUILD_AP_PERIPH
|
||||||
|
|
|
@ -2,6 +2,8 @@
|
||||||
|
|
||||||
#include "AP_RangeFinder_Benewake.h"
|
#include "AP_RangeFinder_Benewake.h"
|
||||||
|
|
||||||
|
#define TFMINI_ADDR_DEFAULT 0x10 // TFMini default device id
|
||||||
|
|
||||||
class AP_RangeFinder_Benewake_TFMini : public AP_RangeFinder_Benewake
|
class AP_RangeFinder_Benewake_TFMini : public AP_RangeFinder_Benewake
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
|
Loading…
Reference in New Issue