AP_Rangefinder: search buses 0 and 1 for Maxbotix I2C driver

This commit is contained in:
Francisco Ferreira 2017-09-23 23:33:04 +01:00 committed by Randy Mackay
parent edd8fb5293
commit 594edc1929
3 changed files with 16 additions and 7 deletions

View File

@ -35,9 +35,11 @@ extern const AP_HAL::HAL& hal;
constructor is not called until detect() returns true, so we
already know that we should setup the rangefinder
*/
AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state)
AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL(RangeFinder &_ranger, uint8_t instance,
RangeFinder::RangeFinder_State &_state,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
: AP_RangeFinder_Backend(_ranger, instance, _state)
, _dev(hal.i2c_mgr->get_device(1, AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR))
, _dev(std::move(dev))
{
}
@ -47,10 +49,11 @@ AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL(RangeFinder &_ranger,
there.
*/
AP_RangeFinder_Backend *AP_RangeFinder_MaxsonarI2CXL::detect(RangeFinder &_ranger, uint8_t instance,
RangeFinder::RangeFinder_State &_state)
RangeFinder::RangeFinder_State &_state,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
{
AP_RangeFinder_MaxsonarI2CXL *sensor
= new AP_RangeFinder_MaxsonarI2CXL(_ranger, instance, _state);
= new AP_RangeFinder_MaxsonarI2CXL(_ranger, instance, _state, std::move(dev));
if (!sensor) {
return nullptr;
}

View File

@ -18,7 +18,8 @@ class AP_RangeFinder_MaxsonarI2CXL : public AP_RangeFinder_Backend
public:
// static detection function
static AP_RangeFinder_Backend *detect(RangeFinder &ranger, uint8_t instance,
RangeFinder::RangeFinder_State &_state);
RangeFinder::RangeFinder_State &_state,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
// update state
void update(void);
@ -26,7 +27,8 @@ public:
private:
// constructor
AP_RangeFinder_MaxsonarI2CXL(RangeFinder &ranger, uint8_t instance,
RangeFinder::RangeFinder_State &_state);
RangeFinder::RangeFinder_State &_state,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
bool _init(void);
void _timer(void);

View File

@ -617,7 +617,11 @@ void RangeFinder::detect_instance(uint8_t instance)
}
break;
case RangeFinder_TYPE_MBI2C:
_add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(*this, instance, state[instance]));
if (!_add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(*this, instance, state[instance],
hal.i2c_mgr->get_device(1, AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR)))) {
_add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(*this, instance, state[instance],
hal.i2c_mgr->get_device(0, AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR)));
}
break;
case RangeFinder_TYPE_LWI2C:
if (_address[instance]) {