AP_Airspeed: Allow specifying the MS5525 address

This commit is contained in:
Michael du Breuil 2017-11-28 12:25:19 -07:00 committed by Francisco Ferreira
parent e5813effff
commit 5fedc65efb
4 changed files with 23 additions and 4 deletions

View File

@ -53,7 +53,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @Param: TYPE
// @DisplayName: Airspeed type
// @Description: Type of airspeed sensor
// @Values: 0:None,1:I2C-MS4525D0,2:Analog,3:I2C-MS5525
// @Values: 0:None,1:I2C-MS4525D0,2:Analog,3:I2C-MS5525,4:I2C-MS5525 (0x76),5:I2C-MS5525 (0x77)
// @User: Standard
AP_GROUPINFO_FLAGS("TYPE", 0, AP_Airspeed, _type, ARSPD_DEFAULT_TYPE, AP_PARAM_FLAG_ENABLE),
@ -158,7 +158,13 @@ void AP_Airspeed::init()
sensor = new AP_Airspeed_Analog(*this);
break;
case TYPE_I2C_MS5525:
sensor = new AP_Airspeed_MS5525(*this);
sensor = new AP_Airspeed_MS5525(*this, AP_Airspeed_MS5525::MS5525_ADDR_AUTO);
break;
case TYPE_I2C_MS5525_ADDRESS_1:
sensor = new AP_Airspeed_MS5525(*this, AP_Airspeed_MS5525::MS5525_ADDR_1);
break;
case TYPE_I2C_MS5525_ADDRESS_2:
sensor = new AP_Airspeed_MS5525(*this, AP_Airspeed_MS5525::MS5525_ADDR_2);
break;
}
if (sensor && !sensor->init()) {

View File

@ -145,6 +145,8 @@ public:
TYPE_I2C_MS4525=1,
TYPE_ANALOG=2,
TYPE_I2C_MS5525=3,
TYPE_I2C_MS5525_ADDRESS_1=4,
TYPE_I2C_MS5525_ADDRESS_2=5,
};
private:

View File

@ -51,9 +51,10 @@ extern const AP_HAL::HAL &hal;
#define REG_CONVERT_PRESSURE REG_CONVERT_D1_OSR_1024
#define REG_CONVERT_TEMPERATURE REG_CONVERT_D2_OSR_1024
AP_Airspeed_MS5525::AP_Airspeed_MS5525(AP_Airspeed &_frontend) :
AP_Airspeed_MS5525::AP_Airspeed_MS5525(AP_Airspeed &_frontend, MS5525_ADDR address) :
AP_Airspeed_Backend(_frontend)
{
_address = address;
}
// probe and initialise the sensor
@ -62,6 +63,9 @@ bool AP_Airspeed_MS5525::init()
const uint8_t addresses[] = { MS5525D0_I2C_ADDR_1, MS5525D0_I2C_ADDR_2 };
bool found = false;
for (uint8_t i=0; i<ARRAY_SIZE(addresses); i++) {
if (_address != MS5525_ADDR_AUTO && i != (uint8_t)_address) {
continue;
}
dev = hal.i2c_mgr->get_device(get_bus(), addresses[i]);
if (!dev) {
continue;

View File

@ -30,7 +30,13 @@
class AP_Airspeed_MS5525 : public AP_Airspeed_Backend
{
public:
AP_Airspeed_MS5525(AP_Airspeed &frontend);
enum MS5525_ADDR {
MS5525_ADDR_1 = 0,
MS5525_ADDR_2 = 1,
MS5525_ADDR_AUTO = 255, // does not need to be 255, just needs to be out of the address array
};
AP_Airspeed_MS5525(AP_Airspeed &frontend, MS5525_ADDR address);
~AP_Airspeed_MS5525(void) {}
// probe and initialise the sensor
@ -67,6 +73,7 @@ private:
uint32_t command_send_us;
bool ignore_next;
uint8_t cmd_sent;
MS5525_ADDR _address;
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;
};