Browse Source

AP_RangeFinder: remove unused parameters from detect and constructors

master
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
0b1c67d170
  1. 6
      libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.cpp
  2. 4
      libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.h
  3. 7
      libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp
  4. 5
      libraries/AP_RangeFinder/AP_RangeFinder_Bebop.h
  5. 7
      libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp
  6. 4
      libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h
  7. 8
      libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp
  8. 5
      libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h
  9. 7
      libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp
  10. 4
      libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h
  11. 6
      libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp
  12. 4
      libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h
  13. 9
      libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp
  14. 6
      libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h
  15. 7
      libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp
  16. 4
      libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h
  17. 13
      libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.cpp
  18. 13
      libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.h
  19. 8
      libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp
  20. 4
      libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h
  21. 8
      libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp
  22. 4
      libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.h
  23. 8
      libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp
  24. 4
      libraries/AP_RangeFinder/AP_RangeFinder_analog.h
  25. 8
      libraries/AP_RangeFinder/AP_RangeFinder_trone.cpp
  26. 5
      libraries/AP_RangeFinder/AP_RangeFinder_trone.h
  27. 7
      libraries/AP_RangeFinder/AP_RangeFinder_uLanding.cpp
  28. 4
      libraries/AP_RangeFinder/AP_RangeFinder_uLanding.h
  29. 52
      libraries/AP_RangeFinder/RangeFinder.cpp
  30. 1
      libraries/AP_RangeFinder/RangeFinder.h
  31. 3
      libraries/AP_RangeFinder/RangeFinder_Backend.cpp
  32. 9
      libraries/AP_RangeFinder/RangeFinder_Backend.h

6
libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.cpp

@ -39,8 +39,8 @@ volatile struct range *rangerpru; @@ -39,8 +39,8 @@ volatile struct range *rangerpru;
constructor is not called until detect() returns true, so we
already know that we should setup the rangefinder
*/
AP_RangeFinder_BBB_PRU::AP_RangeFinder_BBB_PRU(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state) :
AP_RangeFinder_Backend(_ranger, instance, _state, MAV_DISTANCE_SENSOR_ULTRASOUND)
AP_RangeFinder_BBB_PRU::AP_RangeFinder_BBB_PRU(RangeFinder::RangeFinder_State &_state) :
AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_ULTRASOUND)
{
}
@ -48,7 +48,7 @@ AP_RangeFinder_BBB_PRU::AP_RangeFinder_BBB_PRU(RangeFinder &_ranger, uint8_t ins @@ -48,7 +48,7 @@ AP_RangeFinder_BBB_PRU::AP_RangeFinder_BBB_PRU(RangeFinder &_ranger, uint8_t ins
Stop PRU, load firmware (check if firmware is present), start PRU.
If we get a result the sensor seems to be there.
*/
bool AP_RangeFinder_BBB_PRU::detect(RangeFinder &_ranger, uint8_t instance)
bool AP_RangeFinder_BBB_PRU::detect()
{
bool result = true;
uint32_t mem_fd;

4
libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.h

@ -21,10 +21,10 @@ class AP_RangeFinder_BBB_PRU : public AP_RangeFinder_Backend @@ -21,10 +21,10 @@ class AP_RangeFinder_BBB_PRU : public AP_RangeFinder_Backend
{
public:
// constructor
AP_RangeFinder_BBB_PRU(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state);
AP_RangeFinder_BBB_PRU(RangeFinder::RangeFinder_State &_state);
// static detection function
static bool detect(RangeFinder &ranger, uint8_t instance);
static bool detect();
// update state
void update(void);

7
libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp

@ -62,9 +62,8 @@ static const uint16_t waveform_mode1[32] = { @@ -62,9 +62,8 @@ static const uint16_t waveform_mode1[32] = {
1675, 1540, 1492, 1374, 1292
};
AP_RangeFinder_Bebop::AP_RangeFinder_Bebop(RangeFinder &_ranger,
uint8_t instance, RangeFinder::RangeFinder_State &_state) :
AP_RangeFinder_Backend(_ranger, instance, _state, MAV_DISTANCE_SENSOR_ULTRASOUND),
AP_RangeFinder_Bebop::AP_RangeFinder_Bebop(RangeFinder::RangeFinder_State &_state) :
AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_ULTRASOUND),
_thread(new Linux::Thread(FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Bebop::_loop, void)))
{
_init();
@ -88,7 +87,7 @@ AP_RangeFinder_Bebop::~AP_RangeFinder_Bebop() @@ -88,7 +87,7 @@ AP_RangeFinder_Bebop::~AP_RangeFinder_Bebop()
_iio = nullptr;
}
bool AP_RangeFinder_Bebop::detect(RangeFinder &_ranger, uint8_t instance)
bool AP_RangeFinder_Bebop::detect()
{
return true;
}

5
libraries/AP_RangeFinder/AP_RangeFinder_Bebop.h

@ -88,11 +88,10 @@ struct adc_capture { @@ -88,11 +88,10 @@ struct adc_capture {
class AP_RangeFinder_Bebop : public AP_RangeFinder_Backend {
public:
AP_RangeFinder_Bebop(RangeFinder &ranger,
uint8_t instance, RangeFinder::RangeFinder_State &_state);
AP_RangeFinder_Bebop(RangeFinder::RangeFinder_State &_state);
~AP_RangeFinder_Bebop(void);
static bool detect(RangeFinder &ranger, uint8_t instance);
static bool detect();
void update(void);
private:

7
libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp

@ -24,10 +24,9 @@ extern const AP_HAL::HAL& hal; @@ -24,10 +24,9 @@ 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_LeddarOne::AP_RangeFinder_LeddarOne(RangeFinder &_ranger, uint8_t instance,
RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_LeddarOne::AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_State &_state,
AP_SerialManager &serial_manager) :
AP_RangeFinder_Backend(_ranger, instance, _state, MAV_DISTANCE_SENSOR_LASER)
AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_LASER)
{
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, 0);
if (uart != nullptr) {
@ -40,7 +39,7 @@ AP_RangeFinder_LeddarOne::AP_RangeFinder_LeddarOne(RangeFinder &_ranger, uint8_t @@ -40,7 +39,7 @@ AP_RangeFinder_LeddarOne::AP_RangeFinder_LeddarOne(RangeFinder &_ranger, uint8_t
trying to take a reading on Serial. If we get a result the sensor is
there.
*/
bool AP_RangeFinder_LeddarOne::detect(RangeFinder &_ranger, uint8_t instance, AP_SerialManager &serial_manager)
bool AP_RangeFinder_LeddarOne::detect(AP_SerialManager &serial_manager)
{
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, 0) != nullptr;
}

4
libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h

@ -42,11 +42,11 @@ class AP_RangeFinder_LeddarOne : public AP_RangeFinder_Backend @@ -42,11 +42,11 @@ class AP_RangeFinder_LeddarOne : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_LeddarOne(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_State &_state,
AP_SerialManager &serial_manager);
// static detection function
static bool detect(RangeFinder &ranger, uint8_t instance, AP_SerialManager &serial_manager);
static bool detect(AP_SerialManager &serial_manager);
// update state
void update(void);

8
libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp

@ -26,8 +26,8 @@ extern const AP_HAL::HAL& hal; @@ -26,8 +26,8 @@ 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_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, MAV_DISTANCE_SENSOR_LASER)
AP_RangeFinder_LightWareI2C::AP_RangeFinder_LightWareI2C(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
: AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_LASER)
, _dev(std::move(dev)) {}
/*
@ -35,10 +35,10 @@ AP_RangeFinder_LightWareI2C::AP_RangeFinder_LightWareI2C(RangeFinder &_ranger, u @@ -35,10 +35,10 @@ AP_RangeFinder_LightWareI2C::AP_RangeFinder_LightWareI2C(RangeFinder &_ranger, u
trying to take a reading on I2C. If we get a result the sensor is
there.
*/
AP_RangeFinder_Backend *AP_RangeFinder_LightWareI2C::detect(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
AP_RangeFinder_Backend *AP_RangeFinder_LightWareI2C::detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
{
AP_RangeFinder_LightWareI2C *sensor
= new AP_RangeFinder_LightWareI2C(_ranger, instance, _state, std::move(dev));
= new AP_RangeFinder_LightWareI2C(_state, std::move(dev));
if (!sensor) {
delete sensor;

5
libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h

@ -9,14 +9,15 @@ class AP_RangeFinder_LightWareI2C : public AP_RangeFinder_Backend @@ -9,14 +9,15 @@ class AP_RangeFinder_LightWareI2C : public AP_RangeFinder_Backend
public:
// static detection function
static AP_RangeFinder_Backend *detect(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
// update state
void update(void);
private:
// constructor
AP_RangeFinder_LightWareI2C(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
AP_RangeFinder_LightWareI2C(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
void init();
void timer();

7
libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp

@ -25,10 +25,9 @@ extern const AP_HAL::HAL& hal; @@ -25,10 +25,9 @@ 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_LightWareSerial::AP_RangeFinder_LightWareSerial(RangeFinder &_ranger, uint8_t instance,
RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_LightWareSerial::AP_RangeFinder_LightWareSerial(RangeFinder::RangeFinder_State &_state,
AP_SerialManager &serial_manager) :
AP_RangeFinder_Backend(_ranger, instance, _state, MAV_DISTANCE_SENSOR_LASER)
AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_LASER)
{
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, 0);
if (uart != nullptr) {
@ -41,7 +40,7 @@ AP_RangeFinder_LightWareSerial::AP_RangeFinder_LightWareSerial(RangeFinder &_ran @@ -41,7 +40,7 @@ AP_RangeFinder_LightWareSerial::AP_RangeFinder_LightWareSerial(RangeFinder &_ran
trying to take a reading on Serial. If we get a result the sensor is
there.
*/
bool AP_RangeFinder_LightWareSerial::detect(RangeFinder &_ranger, uint8_t instance, AP_SerialManager &serial_manager)
bool AP_RangeFinder_LightWareSerial::detect(AP_SerialManager &serial_manager)
{
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, 0) != nullptr;
}

4
libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h

@ -8,11 +8,11 @@ class AP_RangeFinder_LightWareSerial : public AP_RangeFinder_Backend @@ -8,11 +8,11 @@ class AP_RangeFinder_LightWareSerial : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_LightWareSerial(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_LightWareSerial(RangeFinder::RangeFinder_State &_state,
AP_SerialManager &serial_manager);
// static detection function
static bool detect(RangeFinder &ranger, uint8_t instance, AP_SerialManager &serial_manager);
static bool detect(AP_SerialManager &serial_manager);
// update state
void update(void);

6
libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp

@ -25,8 +25,8 @@ extern const AP_HAL::HAL& hal; @@ -25,8 +25,8 @@ 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_MAVLink::AP_RangeFinder_MAVLink(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state) :
AP_RangeFinder_Backend(_ranger, instance, _state, MAV_DISTANCE_SENSOR_UNKNOWN)
AP_RangeFinder_MAVLink::AP_RangeFinder_MAVLink(RangeFinder::RangeFinder_State &_state) :
AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_UNKNOWN)
{
last_update_ms = AP_HAL::millis();
distance_cm = 0;
@ -36,7 +36,7 @@ AP_RangeFinder_MAVLink::AP_RangeFinder_MAVLink(RangeFinder &_ranger, uint8_t ins @@ -36,7 +36,7 @@ AP_RangeFinder_MAVLink::AP_RangeFinder_MAVLink(RangeFinder &_ranger, uint8_t ins
detect if a MAVLink rangefinder is connected. We'll detect by
checking a parameter.
*/
bool AP_RangeFinder_MAVLink::detect(RangeFinder &_ranger, uint8_t instance)
bool AP_RangeFinder_MAVLink::detect()
{
// Assume that if the user set the RANGEFINDER_TYPE parameter to MAVLink,
// there is an attached MAVLink rangefinder

4
libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h

@ -11,10 +11,10 @@ class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend @@ -11,10 +11,10 @@ class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_MAVLink(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state);
AP_RangeFinder_MAVLink(RangeFinder::RangeFinder_State &_state);
// static detection function
static bool detect(RangeFinder &ranger, uint8_t instance);
static bool detect();
// update state
void update(void);

9
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp

@ -35,8 +35,8 @@ extern const AP_HAL::HAL& hal; @@ -35,8 +35,8 @@ 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_Backend(_ranger, instance, _state, MAV_DISTANCE_SENSOR_ULTRASOUND)
AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state)
: AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_ULTRASOUND)
, _dev(hal.i2c_mgr->get_device(1, AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR))
{
}
@ -46,11 +46,10 @@ AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL(RangeFinder &_ranger, @@ -46,11 +46,10 @@ AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL(RangeFinder &_ranger,
trying to take a reading on I2C. If we get a result the sensor is
there.
*/
AP_RangeFinder_Backend *AP_RangeFinder_MaxsonarI2CXL::detect(RangeFinder &_ranger, uint8_t instance,
RangeFinder::RangeFinder_State &_state)
AP_RangeFinder_Backend *AP_RangeFinder_MaxsonarI2CXL::detect(RangeFinder::RangeFinder_State &_state)
{
AP_RangeFinder_MaxsonarI2CXL *sensor
= new AP_RangeFinder_MaxsonarI2CXL(_ranger, instance, _state);
= new AP_RangeFinder_MaxsonarI2CXL(_state);
if (!sensor) {
return nullptr;
}

6
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h

@ -17,16 +17,14 @@ class AP_RangeFinder_MaxsonarI2CXL : public AP_RangeFinder_Backend @@ -17,16 +17,14 @@ 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);
static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state);
// update state
void update(void);
private:
// constructor
AP_RangeFinder_MaxsonarI2CXL(RangeFinder &ranger, uint8_t instance,
RangeFinder::RangeFinder_State &_state);
AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state);
bool _init(void);
void _timer(void);

7
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp

@ -29,10 +29,9 @@ extern const AP_HAL::HAL& hal; @@ -29,10 +29,9 @@ 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_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(RangeFinder &_ranger, uint8_t instance,
RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state,
AP_SerialManager &serial_manager) :
AP_RangeFinder_Backend(_ranger, instance, _state, MAV_DISTANCE_SENSOR_ULTRASOUND)
AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_ULTRASOUND)
{
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, 0);
if (uart != nullptr) {
@ -45,7 +44,7 @@ AP_RangeFinder_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(RangeFinder &_r @@ -45,7 +44,7 @@ AP_RangeFinder_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(RangeFinder &_r
trying to take a reading on Serial. If we get a result the sensor is
there.
*/
bool AP_RangeFinder_MaxsonarSerialLV::detect(RangeFinder &_ranger, uint8_t instance, AP_SerialManager &serial_manager)
bool AP_RangeFinder_MaxsonarSerialLV::detect(AP_SerialManager &serial_manager)
{
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, 0) != nullptr;
}

4
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h

@ -8,11 +8,11 @@ class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend @@ -8,11 +8,11 @@ class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_MaxsonarSerialLV(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state,
AP_SerialManager &serial_manager);
// static detection function
static bool detect(RangeFinder &ranger, uint8_t instance, AP_SerialManager &serial_manager);
static bool detect(AP_SerialManager &serial_manager);
// update state
void update(void);

13
libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.cpp

@ -43,13 +43,10 @@ extern "C" { @@ -43,13 +43,10 @@ extern "C" {
constructor is not called until detect() returns true, so we
already know that we should setup the rangefinder
*/
AP_RangeFinder_PX4_PWM::AP_RangeFinder_PX4_PWM(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state) :
AP_RangeFinder_Backend(_ranger, instance, _state, MAV_DISTANCE_SENSOR_UNKNOWN),
_last_timestamp(0),
_last_pulse_time_ms(0),
_disable_time_ms(0),
_good_sample_count(0),
_last_sample_distance_cm(0)
AP_RangeFinder_PX4_PWM::AP_RangeFinder_PX4_PWM(RangeFinder::RangeFinder_State &_state, AP_Int16 &powersave_range, float &_estimated_terrain_height) :
AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_UNKNOWN),
_powersave_range(powersave_range),
estimated_terrain_height(_estimated_terrain_height)
{
_fd = open(PWMIN0_DEVICE_PATH, O_RDONLY);
if (_fd == -1) {
@ -83,7 +80,7 @@ AP_RangeFinder_PX4_PWM::~AP_RangeFinder_PX4_PWM() @@ -83,7 +80,7 @@ AP_RangeFinder_PX4_PWM::~AP_RangeFinder_PX4_PWM()
/*
see if the PX4 driver is available
*/
bool AP_RangeFinder_PX4_PWM::detect(RangeFinder &_ranger, uint8_t instance)
bool AP_RangeFinder_PX4_PWM::detect()
{
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1) && \
!defined(CONFIG_ARCH_BOARD_AEROFC_V1)

13
libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.h

@ -21,13 +21,13 @@ class AP_RangeFinder_PX4_PWM : public AP_RangeFinder_Backend @@ -21,13 +21,13 @@ class AP_RangeFinder_PX4_PWM : public AP_RangeFinder_Backend
{
public:
// constructor
AP_RangeFinder_PX4_PWM(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state);
AP_RangeFinder_PX4_PWM(RangeFinder::RangeFinder_State &_state, AP_Int16 &powersave_range, float &_estimated_terrain_height);
// destructor
~AP_RangeFinder_PX4_PWM(void);
// static detection function
static bool detect(RangeFinder &ranger, uint8_t instance);
static bool detect();
// update state
void update(void);
@ -39,4 +39,13 @@ private: @@ -39,4 +39,13 @@ private:
uint32_t _disable_time_ms;
uint32_t _good_sample_count;
float _last_sample_distance_cm;
AP_Int16 &_powersave_range;
float &estimated_terrain_height;
// return true if we are beyond the power saving range
bool out_of_range(void) const {
return _powersave_range > 0 && estimated_terrain_height > _powersave_range;
}
};

8
libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp

@ -44,10 +44,10 @@ extern const AP_HAL::HAL& hal; @@ -44,10 +44,10 @@ 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_PulsedLightLRF::AP_RangeFinder_PulsedLightLRF(uint8_t bus, RangeFinder &_ranger, uint8_t instance,
AP_RangeFinder_PulsedLightLRF::AP_RangeFinder_PulsedLightLRF(uint8_t bus,
RangeFinder::RangeFinder_State &_state,
RangeFinder::RangeFinder_Type _rftype)
: AP_RangeFinder_Backend(_ranger, instance, _state, MAV_DISTANCE_SENSOR_LASER)
: AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_LASER)
, _dev(hal.i2c_mgr->get_device(bus, LL40LS_ADDR))
, rftype(_rftype)
{
@ -57,12 +57,12 @@ AP_RangeFinder_PulsedLightLRF::AP_RangeFinder_PulsedLightLRF(uint8_t bus, RangeF @@ -57,12 +57,12 @@ AP_RangeFinder_PulsedLightLRF::AP_RangeFinder_PulsedLightLRF(uint8_t bus, RangeF
detect if a PulsedLight rangefinder is connected. We'll detect by
look for the version registers
*/
AP_RangeFinder_Backend *AP_RangeFinder_PulsedLightLRF::detect(uint8_t bus, RangeFinder &_ranger, uint8_t instance,
AP_RangeFinder_Backend *AP_RangeFinder_PulsedLightLRF::detect(uint8_t bus,
RangeFinder::RangeFinder_State &_state,
RangeFinder::RangeFinder_Type rftype)
{
AP_RangeFinder_PulsedLightLRF *sensor
= new AP_RangeFinder_PulsedLightLRF(bus, _ranger, instance, _state, rftype);
= new AP_RangeFinder_PulsedLightLRF(bus, _state, rftype);
if (!sensor ||
!sensor->init()) {
delete sensor;

4
libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h

@ -19,7 +19,7 @@ class AP_RangeFinder_PulsedLightLRF : public AP_RangeFinder_Backend @@ -19,7 +19,7 @@ class AP_RangeFinder_PulsedLightLRF : public AP_RangeFinder_Backend
public:
// static detection function
static AP_RangeFinder_Backend *detect(uint8_t bus, RangeFinder &ranger, uint8_t instance,
static AP_RangeFinder_Backend *detect(uint8_t bus,
RangeFinder::RangeFinder_State &_state,
RangeFinder::RangeFinder_Type rftype);
@ -29,7 +29,7 @@ public: @@ -29,7 +29,7 @@ public:
private:
// constructor
AP_RangeFinder_PulsedLightLRF(uint8_t bus, RangeFinder &ranger, uint8_t instance,
AP_RangeFinder_PulsedLightLRF(uint8_t bus,
RangeFinder::RangeFinder_State &_state,
RangeFinder::RangeFinder_Type rftype);

8
libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp

@ -216,8 +216,8 @@ const AP_RangeFinder_VL53L0X::RegData AP_RangeFinder_VL53L0X::tuning_data[] = @@ -216,8 +216,8 @@ const AP_RangeFinder_VL53L0X::RegData AP_RangeFinder_VL53L0X::tuning_data[] =
constructor is not called until detect() returns true, so we
already know that we should setup the rangefinder
*/
AP_RangeFinder_VL53L0X::AP_RangeFinder_VL53L0X(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev)
: AP_RangeFinder_Backend(_ranger, instance, _state, MAV_DISTANCE_SENSOR_LASER)
AP_RangeFinder_VL53L0X::AP_RangeFinder_VL53L0X(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev)
: AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_LASER)
, dev(std::move(_dev)) {}
@ -226,10 +226,10 @@ AP_RangeFinder_VL53L0X::AP_RangeFinder_VL53L0X(RangeFinder &_ranger, uint8_t ins @@ -226,10 +226,10 @@ AP_RangeFinder_VL53L0X::AP_RangeFinder_VL53L0X(RangeFinder &_ranger, uint8_t ins
trying to take a reading on I2C. If we get a result the sensor is
there.
*/
AP_RangeFinder_Backend *AP_RangeFinder_VL53L0X::detect(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
AP_RangeFinder_Backend *AP_RangeFinder_VL53L0X::detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
{
AP_RangeFinder_VL53L0X *sensor
= new AP_RangeFinder_VL53L0X(_ranger, instance, _state, std::move(dev));
= new AP_RangeFinder_VL53L0X(_state, std::move(dev));
if (!sensor) {
delete sensor;

4
libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.h

@ -9,14 +9,14 @@ class AP_RangeFinder_VL53L0X : public AP_RangeFinder_Backend @@ -9,14 +9,14 @@ class AP_RangeFinder_VL53L0X : public AP_RangeFinder_Backend
public:
// static detection function
static AP_RangeFinder_Backend *detect(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
// update state
void update(void);
private:
// constructor
AP_RangeFinder_VL53L0X(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
AP_RangeFinder_VL53L0X(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
void init();
void timer();

8
libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp

@ -31,8 +31,8 @@ extern const AP_HAL::HAL& hal; @@ -31,8 +31,8 @@ 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_analog::AP_RangeFinder_analog(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state) :
AP_RangeFinder_Backend(_ranger, instance, _state, MAV_DISTANCE_SENSOR_UNKNOWN)
AP_RangeFinder_analog::AP_RangeFinder_analog(RangeFinder::RangeFinder_State &_state) :
AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_UNKNOWN)
{
source = hal.analogin->channel(_state.pin);
if (source == nullptr) {
@ -50,9 +50,9 @@ AP_RangeFinder_analog::AP_RangeFinder_analog(RangeFinder &_ranger, uint8_t insta @@ -50,9 +50,9 @@ AP_RangeFinder_analog::AP_RangeFinder_analog(RangeFinder &_ranger, uint8_t insta
can do is check if the pin number is valid. If it is, then assume
that the device is connected
*/
bool AP_RangeFinder_analog::detect(RangeFinder &_ranger, uint8_t instance)
bool AP_RangeFinder_analog::detect(RangeFinder::RangeFinder_State &_state)
{
if (_ranger.state[instance].pin != -1) {
if (_state.pin != -1) {
return true;
}
return false;

4
libraries/AP_RangeFinder/AP_RangeFinder_analog.h

@ -7,10 +7,10 @@ class AP_RangeFinder_analog : public AP_RangeFinder_Backend @@ -7,10 +7,10 @@ class AP_RangeFinder_analog : public AP_RangeFinder_Backend
{
public:
// constructor
AP_RangeFinder_analog(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state);
AP_RangeFinder_analog(RangeFinder::RangeFinder_State &_state);
// static detection function
static bool detect(RangeFinder &ranger, uint8_t instance);
static bool detect(RangeFinder::RangeFinder_State &_state);
// update state
void update(void);

8
libraries/AP_RangeFinder/AP_RangeFinder_trone.cpp

@ -35,8 +35,8 @@ extern const AP_HAL::HAL& hal; @@ -35,8 +35,8 @@ 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_trone::AP_RangeFinder_trone(uint8_t bus, RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state)
: AP_RangeFinder_Backend(_ranger, instance, _state, MAV_DISTANCE_SENSOR_LASER)
AP_RangeFinder_trone::AP_RangeFinder_trone(uint8_t bus, RangeFinder::RangeFinder_State &_state)
: AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_LASER)
, dev(hal.i2c_mgr->get_device(bus, TRONE_I2C_ADDR))
{
}
@ -46,10 +46,10 @@ AP_RangeFinder_trone::AP_RangeFinder_trone(uint8_t bus, RangeFinder &_ranger, ui @@ -46,10 +46,10 @@ AP_RangeFinder_trone::AP_RangeFinder_trone(uint8_t bus, RangeFinder &_ranger, ui
trying to take a reading on I2C. If we get a result the sensor is
there.
*/
AP_RangeFinder_Backend *AP_RangeFinder_trone::detect(uint8_t bus, RangeFinder &_ranger, uint8_t instance,
AP_RangeFinder_Backend *AP_RangeFinder_trone::detect(uint8_t bus,
RangeFinder::RangeFinder_State &_state)
{
AP_RangeFinder_trone *sensor = new AP_RangeFinder_trone(bus, _ranger, instance, _state);
AP_RangeFinder_trone *sensor = new AP_RangeFinder_trone(bus, _state);
if (!sensor) {
return nullptr;
}

5
libraries/AP_RangeFinder/AP_RangeFinder_trone.h

@ -8,7 +8,7 @@ class AP_RangeFinder_trone : public AP_RangeFinder_Backend @@ -8,7 +8,7 @@ class AP_RangeFinder_trone : public AP_RangeFinder_Backend
{
public:
// static detection function
static AP_RangeFinder_Backend *detect(uint8_t bus, RangeFinder &ranger, uint8_t instance,
static AP_RangeFinder_Backend *detect(uint8_t bus,
RangeFinder::RangeFinder_State &_state);
// update state
@ -16,8 +16,7 @@ public: @@ -16,8 +16,7 @@ public:
private:
// constructor
AP_RangeFinder_trone(uint8_t bus, RangeFinder &ranger, uint8_t instance,
RangeFinder::RangeFinder_State &_state);
AP_RangeFinder_trone(uint8_t bus, RangeFinder::RangeFinder_State &_state);
bool measure(void);
bool collect(uint16_t &distance_cm);

7
libraries/AP_RangeFinder/AP_RangeFinder_uLanding.cpp

@ -25,10 +25,9 @@ extern const AP_HAL::HAL& hal; @@ -25,10 +25,9 @@ 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_uLanding::AP_RangeFinder_uLanding(RangeFinder &_ranger, uint8_t instance,
RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_uLanding::AP_RangeFinder_uLanding(RangeFinder::RangeFinder_State &_state,
AP_SerialManager &serial_manager) :
AP_RangeFinder_Backend(_ranger, instance, _state, MAV_DISTANCE_SENSOR_RADAR)
AP_RangeFinder_Backend(_state, MAV_DISTANCE_SENSOR_RADAR)
{
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Aerotenna_uLanding, 0);
if (uart != nullptr) {
@ -41,7 +40,7 @@ AP_RangeFinder_uLanding::AP_RangeFinder_uLanding(RangeFinder &_ranger, uint8_t i @@ -41,7 +40,7 @@ AP_RangeFinder_uLanding::AP_RangeFinder_uLanding(RangeFinder &_ranger, uint8_t i
trying to take a reading on Serial. If we get a result the sensor is
there.
*/
bool AP_RangeFinder_uLanding::detect(RangeFinder &_ranger, uint8_t instance, AP_SerialManager &serial_manager)
bool AP_RangeFinder_uLanding::detect(AP_SerialManager &serial_manager)
{
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Aerotenna_uLanding, 0) != nullptr;
}

4
libraries/AP_RangeFinder/AP_RangeFinder_uLanding.h

@ -8,11 +8,11 @@ class AP_RangeFinder_uLanding : public AP_RangeFinder_Backend @@ -8,11 +8,11 @@ class AP_RangeFinder_uLanding : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_uLanding(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_uLanding(RangeFinder::RangeFinder_State &_state,
AP_SerialManager &serial_manager);
// static detection function
static bool detect(RangeFinder &ranger, uint8_t instance, AP_SerialManager &serial_manager);
static bool detect(AP_SerialManager &serial_manager);
// update state
void update(void);

52
libraries/AP_RangeFinder/RangeFinder.cpp

@ -609,91 +609,91 @@ void RangeFinder::detect_instance(uint8_t instance) @@ -609,91 +609,91 @@ void RangeFinder::detect_instance(uint8_t instance)
switch (_type) {
case RangeFinder_TYPE_PLI2C:
case RangeFinder_TYPE_PLI2CV3:
if (!_add_backend(AP_RangeFinder_PulsedLightLRF::detect(1, *this, instance, state[instance], _type))) {
_add_backend(AP_RangeFinder_PulsedLightLRF::detect(0, *this, instance, state[instance], _type));
if (!_add_backend(AP_RangeFinder_PulsedLightLRF::detect(1, state[instance], _type))) {
_add_backend(AP_RangeFinder_PulsedLightLRF::detect(0, state[instance], _type));
}
break;
case RangeFinder_TYPE_MBI2C:
_add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(*this, instance, state[instance]));
_add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(state[instance]));
break;
case RangeFinder_TYPE_LWI2C:
if (state[instance].address) {
_add_backend(AP_RangeFinder_LightWareI2C::detect(*this, instance, state[instance],
_add_backend(AP_RangeFinder_LightWareI2C::detect(state[instance],
hal.i2c_mgr->get_device(HAL_RANGEFINDER_LIGHTWARE_I2C_BUS, state[instance].address)));
}
break;
case RangeFinder_TYPE_TRONE:
if (!_add_backend(AP_RangeFinder_trone::detect(0, *this, instance, state[instance]))) {
_add_backend(AP_RangeFinder_trone::detect(1, *this, instance, state[instance]));
if (!_add_backend(AP_RangeFinder_trone::detect(0, state[instance]))) {
_add_backend(AP_RangeFinder_trone::detect(1, state[instance]));
}
break;
case RangeFinder_TYPE_VL53L0X:
if (!_add_backend(AP_RangeFinder_VL53L0X::detect(*this, instance, state[instance],
if (!_add_backend(AP_RangeFinder_VL53L0X::detect(state[instance],
hal.i2c_mgr->get_device(1, 0x29)))) {
_add_backend(AP_RangeFinder_VL53L0X::detect(*this, instance, state[instance],
_add_backend(AP_RangeFinder_VL53L0X::detect(state[instance],
hal.i2c_mgr->get_device(0, 0x29)));
}
break;
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
case RangeFinder_TYPE_PX4_PWM:
if (AP_RangeFinder_PX4_PWM::detect(*this, instance)) {
if (AP_RangeFinder_PX4_PWM::detect()) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_PX4_PWM(*this, instance, state[instance]);
drivers[instance] = new AP_RangeFinder_PX4_PWM(state[instance], _powersave_range, estimated_terrain_height);
}
break;
#endif
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
case RangeFinder_TYPE_BBB_PRU:
if (AP_RangeFinder_BBB_PRU::detect(*this, instance)) {
if (AP_RangeFinder_BBB_PRU::detect()) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_BBB_PRU(*this, instance, state[instance]);
drivers[instance] = new AP_RangeFinder_BBB_PRU(state[instance]);
}
break;
#endif
case RangeFinder_TYPE_LWSER:
if (AP_RangeFinder_LightWareSerial::detect(*this, instance, serial_manager)) {
if (AP_RangeFinder_LightWareSerial::detect(serial_manager)) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_LightWareSerial(*this, instance, state[instance], serial_manager);
drivers[instance] = new AP_RangeFinder_LightWareSerial(state[instance], serial_manager);
}
break;
case RangeFinder_TYPE_LEDDARONE:
if (AP_RangeFinder_LeddarOne::detect(*this, instance, serial_manager)) {
if (AP_RangeFinder_LeddarOne::detect(serial_manager)) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_LeddarOne(*this, instance, state[instance], serial_manager);
drivers[instance] = new AP_RangeFinder_LeddarOne(state[instance], serial_manager);
}
break;
case RangeFinder_TYPE_ULANDING:
if (AP_RangeFinder_uLanding::detect(*this, instance, serial_manager)) {
if (AP_RangeFinder_uLanding::detect(serial_manager)) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_uLanding(*this, instance, state[instance], serial_manager);
drivers[instance] = new AP_RangeFinder_uLanding(state[instance], serial_manager);
}
break;
#if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO)
case RangeFinder_TYPE_BEBOP:
if (AP_RangeFinder_Bebop::detect(*this, instance)) {
if (AP_RangeFinder_Bebop::detect()) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_Bebop(*this, instance, state[instance]);
drivers[instance] = new AP_RangeFinder_Bebop(state[instance]);
}
break;
#endif
case RangeFinder_TYPE_MAVLink:
if (AP_RangeFinder_MAVLink::detect(*this, instance)) {
if (AP_RangeFinder_MAVLink::detect()) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_MAVLink(*this, instance, state[instance]);
drivers[instance] = new AP_RangeFinder_MAVLink(state[instance]);
}
break;
case RangeFinder_TYPE_MBSER:
if (AP_RangeFinder_MaxsonarSerialLV::detect(*this, instance, serial_manager)) {
if (AP_RangeFinder_MaxsonarSerialLV::detect(serial_manager)) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_MaxsonarSerialLV(*this, instance, state[instance], serial_manager);
drivers[instance] = new AP_RangeFinder_MaxsonarSerialLV(state[instance], serial_manager);
}
break;
case RangeFinder_TYPE_ANALOG:
// note that analog will always come back as present if the pin is valid
if (AP_RangeFinder_analog::detect(*this, instance)) {
if (AP_RangeFinder_analog::detect(state[instance])) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_analog(*this, instance, state[instance]);
drivers[instance] = new AP_RangeFinder_analog(state[instance]);
}
break;
default:

1
libraries/AP_RangeFinder/RangeFinder.h

@ -32,7 +32,6 @@ class RangeFinder @@ -32,7 +32,6 @@ class RangeFinder
{
public:
friend class AP_RangeFinder_Backend;
friend class AP_RangeFinder_analog; // bodgy detect function
RangeFinder(AP_SerialManager &_serial_manager, enum Rotation orientation_default);

3
libraries/AP_RangeFinder/RangeFinder_Backend.cpp

@ -24,8 +24,7 @@ extern const AP_HAL::HAL& hal; @@ -24,8 +24,7 @@ extern const AP_HAL::HAL& hal;
base class constructor.
This incorporates initialisation as well.
*/
AP_RangeFinder_Backend::AP_RangeFinder_Backend(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state, MAV_DISTANCE_SENSOR _sensor_type) :
ranger(_ranger),
AP_RangeFinder_Backend::AP_RangeFinder_Backend(RangeFinder::RangeFinder_State &_state, MAV_DISTANCE_SENSOR _sensor_type) :
state(_state),
sensor_type(_sensor_type)
{

9
libraries/AP_RangeFinder/RangeFinder_Backend.h

@ -22,7 +22,8 @@ class AP_RangeFinder_Backend @@ -22,7 +22,8 @@ class AP_RangeFinder_Backend
{
public:
// constructor. This incorporates initialisation as well.
AP_RangeFinder_Backend(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state, MAV_DISTANCE_SENSOR _sensor_type);
AP_RangeFinder_Backend(RangeFinder::RangeFinder_State &_state,
MAV_DISTANCE_SENSOR _sensor_type);
// we declare a virtual destructor so that RangeFinder drivers can
// override with a custom destructor if need be
@ -31,11 +32,6 @@ public: @@ -31,11 +32,6 @@ public:
// update the state structure
virtual void update() = 0;
// return true if we are beyond the power saving range
bool out_of_range(void) const {
return ranger._powersave_range > 0 && ranger.estimated_terrain_height > ranger._powersave_range;
}
MAV_DISTANCE_SENSOR get_sensor_type() const {
return sensor_type;
}
@ -50,7 +46,6 @@ protected: @@ -50,7 +46,6 @@ protected:
// set status and update valid_count
void set_status(RangeFinder::RangeFinder_Status status);
RangeFinder &ranger;
RangeFinder::RangeFinder_State &state;
MAV_DISTANCE_SENSOR sensor_type;

Loading…
Cancel
Save