AP_RangeFinder: TeraRangerI2C: use address from parameter instead of hardcoded

This commit is contained in:
Mateusz Sadowski 2017-07-28 14:20:10 +02:00 committed by Francisco Ferreira
parent 0993300506
commit eb56a010b3
3 changed files with 16 additions and 12 deletions

View File

@ -23,8 +23,6 @@
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
#define TRONE_I2C_ADDR 0x30
// registers // registers
#define TR_MEASURE 0x00 #define TR_MEASURE 0x00
#define TR_WHOAMI 0x01 #define TR_WHOAMI 0x01
@ -35,9 +33,10 @@ extern const AP_HAL::HAL& hal;
constructor is not called until detect() returns true, so we constructor is not called until detect() returns true, so we
already know that we should setup the rangefinder already know that we should setup the rangefinder
*/ */
AP_RangeFinder_TeraRangerI2C::AP_RangeFinder_TeraRangerI2C(uint8_t bus, RangeFinder::RangeFinder_State &_state) AP_RangeFinder_TeraRangerI2C::AP_RangeFinder_TeraRangerI2C(RangeFinder::RangeFinder_State &_state,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> i2c_dev)
: AP_RangeFinder_Backend(_state) : AP_RangeFinder_Backend(_state)
, dev(hal.i2c_mgr->get_device(bus, TRONE_I2C_ADDR)) , dev(std::move(i2c_dev))
{ {
} }
@ -46,10 +45,10 @@ AP_RangeFinder_TeraRangerI2C::AP_RangeFinder_TeraRangerI2C(uint8_t bus, RangeFin
trying to take a reading on I2C. If we get a result the sensor is trying to take a reading on I2C. If we get a result the sensor is
there. there.
*/ */
AP_RangeFinder_Backend *AP_RangeFinder_TeraRangerI2C::detect(uint8_t bus, AP_RangeFinder_Backend *AP_RangeFinder_TeraRangerI2C::detect(RangeFinder::RangeFinder_State &_state,
RangeFinder::RangeFinder_State &_state) AP_HAL::OwnPtr<AP_HAL::I2CDevice> i2c_dev)
{ {
AP_RangeFinder_TeraRangerI2C *sensor = new AP_RangeFinder_TeraRangerI2C(bus, _state); AP_RangeFinder_TeraRangerI2C *sensor = new AP_RangeFinder_TeraRangerI2C(_state, std::move(i2c_dev));
if (!sensor) { if (!sensor) {
return nullptr; return nullptr;
} }

View File

@ -8,8 +8,8 @@ class AP_RangeFinder_TeraRangerI2C : public AP_RangeFinder_Backend
{ {
public: public:
// static detection function // static detection function
static AP_RangeFinder_Backend *detect(uint8_t bus, static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state,
RangeFinder::RangeFinder_State &_state); AP_HAL::OwnPtr<AP_HAL::I2CDevice> i2c_dev);
// update state // update state
void update(void); void update(void);
@ -22,7 +22,8 @@ protected:
private: private:
// constructor // constructor
AP_RangeFinder_TeraRangerI2C(uint8_t bus, RangeFinder::RangeFinder_State &_state); AP_RangeFinder_TeraRangerI2C(RangeFinder::RangeFinder_State &_state,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> i2c_dev);
bool measure(void); bool measure(void);
bool collect(uint16_t &distance_cm); bool collect(uint16_t &distance_cm);

View File

@ -623,8 +623,12 @@ void RangeFinder::detect_instance(uint8_t instance)
} }
break; break;
case RangeFinder_TYPE_TRI2C: case RangeFinder_TYPE_TRI2C:
if (!_add_backend(AP_RangeFinder_TeraRangerI2C::detect(0, state[instance]))) { if (state[instance].address) {
_add_backend(AP_RangeFinder_TeraRangerI2C::detect(1, state[instance])); if (!_add_backend(AP_RangeFinder_TeraRangerI2C::detect(state[instance],
hal.i2c_mgr->get_device(1, state[instance].address)))) {
_add_backend(AP_RangeFinder_TeraRangerI2C::detect(state[instance],
hal.i2c_mgr->get_device(0, state[instance].address)));
}
} }
break; break;
case RangeFinder_TYPE_VL53L0X: case RangeFinder_TYPE_VL53L0X: