AP_RangeFinder: correct creation/use of TFMINI_ADDR_DEFAULT

Named incorrectly and defined in wrong file...
This commit is contained in:
Peter Barker 2022-03-13 09:19:38 +11:00 committed by Andrew Tridgell
parent 05131853d8
commit deba0b712b
3 changed files with 3 additions and 3 deletions

View File

@ -432,7 +432,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
break;
case Type::BenewakeTFminiPlus: {
#if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED
uint8_t addr = TFMINI_ADDR_DEFAULT;
uint8_t addr = TFMINIPLUS_ADDR_DEFAULT;
if (params[instance].address != 0) {
addr = params[instance].address;
}

View File

@ -8,8 +8,6 @@
#if AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED
#define TFMINI_ADDR_DEFAULT 0x10 // TFMini default device id
class AP_RangeFinder_Benewake_TFMini : public AP_RangeFinder_Benewake
{
public:

View File

@ -25,6 +25,8 @@
#if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED
#define TFMINIPLUS_ADDR_DEFAULT 0x10 // TFMini default device id
#include <AP_HAL/utility/sparse-endian.h>
#include <AP_HAL/I2CDevice.h>