mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
AP_Rangefinder: search buses 0 and 1 for Maxbotix I2C driver
This commit is contained in:
parent
be1f0801a3
commit
02586b0a2e
@ -35,9 +35,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_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state)
|
AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state,
|
||||||
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||||
: AP_RangeFinder_Backend(_state)
|
: AP_RangeFinder_Backend(_state)
|
||||||
, _dev(hal.i2c_mgr->get_device(1, AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR))
|
, _dev(std::move(dev))
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -46,10 +47,11 @@ AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL(RangeFinder::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_MaxsonarI2CXL::detect(RangeFinder::RangeFinder_State &_state)
|
AP_RangeFinder_Backend *AP_RangeFinder_MaxsonarI2CXL::detect(RangeFinder::RangeFinder_State &_state,
|
||||||
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||||
{
|
{
|
||||||
AP_RangeFinder_MaxsonarI2CXL *sensor
|
AP_RangeFinder_MaxsonarI2CXL *sensor
|
||||||
= new AP_RangeFinder_MaxsonarI2CXL(_state);
|
= new AP_RangeFinder_MaxsonarI2CXL(_state, std::move(dev));
|
||||||
if (!sensor) {
|
if (!sensor) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
@ -17,7 +17,8 @@ class AP_RangeFinder_MaxsonarI2CXL : public AP_RangeFinder_Backend
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
// static detection function
|
// static detection function
|
||||||
static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state);
|
static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state,
|
||||||
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||||
|
|
||||||
// update state
|
// update state
|
||||||
void update(void);
|
void update(void);
|
||||||
@ -30,7 +31,8 @@ protected:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
// constructor
|
// constructor
|
||||||
AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state);
|
AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state,
|
||||||
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||||
|
|
||||||
bool _init(void);
|
bool _init(void);
|
||||||
void _timer(void);
|
void _timer(void);
|
||||||
|
@ -614,7 +614,11 @@ void RangeFinder::detect_instance(uint8_t instance)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case RangeFinder_TYPE_MBI2C:
|
case RangeFinder_TYPE_MBI2C:
|
||||||
_add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(state[instance]));
|
if (!_add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(state[instance],
|
||||||
|
hal.i2c_mgr->get_device(1, AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR)))) {
|
||||||
|
_add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(state[instance],
|
||||||
|
hal.i2c_mgr->get_device(0, AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR)));
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
case RangeFinder_TYPE_LWI2C:
|
case RangeFinder_TYPE_LWI2C:
|
||||||
if (state[instance].address) {
|
if (state[instance].address) {
|
||||||
|
Loading…
Reference in New Issue
Block a user