mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 15:48:29 -04:00
AP_HAL: support LPS25H on MPU AUX
This commit is contained in:
parent
75a262ebf9
commit
2b0a3272fd
@ -112,6 +112,7 @@
|
|||||||
#define HAL_BARO_20789_I2C_I2C 14
|
#define HAL_BARO_20789_I2C_I2C 14
|
||||||
#define HAL_BARO_20789_I2C_SPI 15
|
#define HAL_BARO_20789_I2C_SPI 15
|
||||||
#define HAL_BARO_LPS22H_SPI 16
|
#define HAL_BARO_LPS22H_SPI 16
|
||||||
|
#define HAL_BARO_LPS25H_IMU_I2C 17
|
||||||
|
|
||||||
/* Compass driver types */
|
/* Compass driver types */
|
||||||
#define HAL_COMPASS_NONE 0
|
#define HAL_COMPASS_NONE 0
|
||||||
|
@ -78,6 +78,12 @@ public:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Change device address. Note that this is the 7 bit address, it
|
||||||
|
* does not include the bit for read/write. Only works on I2C
|
||||||
|
*/
|
||||||
|
virtual void set_address(uint8_t address) {};
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Set the speed of future transfers. Depending on the bus the speed may
|
* Set the speed of future transfers. Depending on the bus the speed may
|
||||||
* be shared for all devices on the same bus.
|
* be shared for all devices on the same bus.
|
||||||
|
@ -30,12 +30,6 @@ public:
|
|||||||
|
|
||||||
virtual ~I2CDevice() { }
|
virtual ~I2CDevice() { }
|
||||||
|
|
||||||
/*
|
|
||||||
* Change device address. Note that this is the 7 bit address, it
|
|
||||||
* does not include the bit for read/write.
|
|
||||||
*/
|
|
||||||
virtual void set_address(uint8_t address) = 0;
|
|
||||||
|
|
||||||
/* Device implementation */
|
/* Device implementation */
|
||||||
|
|
||||||
/* See Device::set_speed() */
|
/* See Device::set_speed() */
|
||||||
|
Loading…
Reference in New Issue
Block a user