From 6febbcdc138871e7670a8d26374e46039a972944 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 12 Feb 2020 13:13:36 +1100 Subject: [PATCH] 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. --- libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp | 5 ----- libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp | 5 ----- libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp | 5 ----- libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp | 5 ----- libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp | 5 ----- libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp | 5 ----- 6 files changed, 30 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp index f953def399..02b850c116 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp @@ -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 dev) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp index 1a1b81706d..d4812776ae 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp @@ -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 dev) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp index bc870c0282..cf500a6bb0 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp @@ -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, diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp index 911823e5bb..4509c07e46 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp @@ -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 i2c_dev) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp index d0382c764b..4bd032d4b4 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp @@ -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 _dev) : AP_RangeFinder_Backend(_state, _params) , dev(std::move(_dev)) {} diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp index df3f3a6c6a..7b218c1707 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp @@ -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 _dev) : AP_RangeFinder_Backend(_state, _params) , dev(std::move(_dev)) {}