mirror of https://github.com/ArduPilot/ardupilot
Update AP_Airspeed_MS4525.cpp
update airspeed sensor to read and work with Pixhawk 4 adding { 3, MS4525D0_I2C_ADDR }, to the code
This commit is contained in:
parent
792fbc6240
commit
8d4215fd82
|
@ -44,6 +44,7 @@ bool AP_Airspeed_MS4525::init()
|
||||||
{ 1, MS4525D0_I2C_ADDR },
|
{ 1, MS4525D0_I2C_ADDR },
|
||||||
{ 0, MS4525D0_I2C_ADDR },
|
{ 0, MS4525D0_I2C_ADDR },
|
||||||
{ 2, MS4525D0_I2C_ADDR },
|
{ 2, MS4525D0_I2C_ADDR },
|
||||||
|
{ 3, MS4525D0_I2C_ADDR },
|
||||||
};
|
};
|
||||||
bool found = false;
|
bool found = false;
|
||||||
for (uint8_t i=0; i<ARRAY_SIZE(addresses); i++) {
|
for (uint8_t i=0; i<ARRAY_SIZE(addresses); i++) {
|
||||||
|
|
Loading…
Reference in New Issue