mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_RangeFinder: fix hard fault with LightWareI2C
This commit is contained in:
parent
556993d7f0
commit
6e47bed97d
@ -28,12 +28,7 @@ extern const AP_HAL::HAL& hal;
|
||||
*/
|
||||
AP_RangeFinder_LightWareI2C::AP_RangeFinder_LightWareI2C(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||
: AP_RangeFinder_Backend(_ranger, instance, _state)
|
||||
, _dev(std::move(dev))
|
||||
{
|
||||
// call timer() at 20Hz
|
||||
_dev->register_periodic_callback(50000,
|
||||
FUNCTOR_BIND_MEMBER(&AP_RangeFinder_LightWareI2C::timer, bool));
|
||||
}
|
||||
, _dev(std::move(dev)) {}
|
||||
|
||||
/*
|
||||
detect if a Lightware rangefinder is connected. We'll detect by
|
||||
@ -60,9 +55,18 @@ AP_RangeFinder_Backend *AP_RangeFinder_LightWareI2C::detect(RangeFinder &_ranger
|
||||
sensor->_dev->get_semaphore()->give();
|
||||
}
|
||||
|
||||
sensor->init();
|
||||
|
||||
return sensor;
|
||||
}
|
||||
|
||||
void AP_RangeFinder_LightWareI2C::init()
|
||||
{
|
||||
// call timer() at 20Hz
|
||||
_dev->register_periodic_callback(50000,
|
||||
FUNCTOR_BIND_MEMBER(&AP_RangeFinder_LightWareI2C::timer, bool));
|
||||
}
|
||||
|
||||
// read - return last value measured by sensor
|
||||
bool AP_RangeFinder_LightWareI2C::get_reading(uint16_t &reading_cm)
|
||||
{
|
||||
|
@ -18,6 +18,7 @@ private:
|
||||
// constructor
|
||||
AP_RangeFinder_LightWareI2C(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||
|
||||
void init();
|
||||
bool timer();
|
||||
|
||||
// get a reading
|
||||
|
Loading…
Reference in New Issue
Block a user