mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: remove incorrect and misleading comment
Wrong on several counts. detect calls this method. The constructor doesn't initialise the rangefinder. detect doesn't return boolean.
This commit is contained in:
parent
bebfef369f
commit
6febbcdc13
|
@ -56,11 +56,6 @@ static const uint8_t streamSequence[] = { 0 }; // List of 0 based stream Ids tha
|
|||
|
||||
static const uint8_t numStreamSequenceIndexes = sizeof(streamSequence)/sizeof(streamSequence[0]);
|
||||
|
||||
/*
|
||||
The constructor also initializes the rangefinder. Note that this
|
||||
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::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||
|
|
|
@ -30,11 +30,6 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/*
|
||||
The constructor also initializes the rangefinder. Note that this
|
||||
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::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||
|
|
|
@ -40,11 +40,6 @@ extern const AP_HAL::HAL& hal;
|
|||
// i2c address
|
||||
#define LL40LS_ADDR 0x62
|
||||
|
||||
/*
|
||||
The constructor also initializes the rangefinder. Note that this
|
||||
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::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
|
|
|
@ -28,11 +28,6 @@ extern const AP_HAL::HAL& hal;
|
|||
#define TR_WHOAMI 0x01
|
||||
#define TR_WHOAMI_VALUE 0xA1
|
||||
|
||||
/*
|
||||
The constructor also initializes the rangefinder. Note that this
|
||||
constructor is not called until detect() returns true, so we
|
||||
already know that we should setup the rangefinder
|
||||
*/
|
||||
AP_RangeFinder_TeraRangerI2C::AP_RangeFinder_TeraRangerI2C(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> i2c_dev)
|
||||
|
|
|
@ -211,11 +211,6 @@ const AP_RangeFinder_VL53L0X::RegData AP_RangeFinder_VL53L0X::tuning_data[] =
|
|||
{ 0x80, 0x00 },
|
||||
};
|
||||
|
||||
/*
|
||||
The constructor also initializes the rangefinder. Note that this
|
||||
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::RangeFinder_State &_state, AP_RangeFinder_Params &_params, AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev)
|
||||
: AP_RangeFinder_Backend(_state, _params)
|
||||
, dev(std::move(_dev)) {}
|
||||
|
|
|
@ -28,11 +28,6 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/*
|
||||
The constructor also initializes the rangefinder. Note that this
|
||||
constructor is not called until detect() returns true, so we
|
||||
already know that we should setup the rangefinder
|
||||
*/
|
||||
AP_RangeFinder_VL53L1X::AP_RangeFinder_VL53L1X(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params, AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev)
|
||||
: AP_RangeFinder_Backend(_state, _params)
|
||||
, dev(std::move(_dev)) {}
|
||||
|
|
Loading…
Reference in New Issue