mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
HAL_ChibiOS: added HAL_I2C_BUS_BASE
this allows fmuv4 to start at bus 1
This commit is contained in:
parent
c60c0b8ab1
commit
88f11f5a50
@ -33,6 +33,10 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
I2CBus I2CDeviceManager::businfo[ARRAY_SIZE_SIMPLE(I2CD)];
|
||||
|
||||
#ifndef HAL_I2C_BUS_BASE
|
||||
#define HAL_I2C_BUS_BASE 0
|
||||
#endif
|
||||
|
||||
// get a handle for DMA sharing DMA channels with other subsystems
|
||||
void I2CBus::dma_init(void)
|
||||
{
|
||||
@ -64,7 +68,7 @@ I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool u
|
||||
_timeout_ms(timeout_ms),
|
||||
bus(I2CDeviceManager::businfo[busnum])
|
||||
{
|
||||
set_device_bus(busnum);
|
||||
set_device_bus(busnum+HAL_I2C_BUS_BASE);
|
||||
set_device_address(address);
|
||||
asprintf(&pname, "I2C:%u:%02x",
|
||||
(unsigned)busnum, (unsigned)address);
|
||||
@ -205,6 +209,7 @@ I2CDeviceManager::get_device(uint8_t bus, uint8_t address,
|
||||
bool use_smbus,
|
||||
uint32_t timeout_ms)
|
||||
{
|
||||
bus -= HAL_I2C_BUS_BASE;
|
||||
if (bus >= ARRAY_SIZE_SIMPLE(I2CD)) {
|
||||
return AP_HAL::OwnPtr<AP_HAL::I2CDevice>(nullptr);
|
||||
}
|
||||
|
@ -30,6 +30,9 @@ USB_STRING_SERIAL "100"
|
||||
# only one I2C bus
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# to match px4 we make the first bus number 1
|
||||
define HAL_I2C_BUS_BASE 1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user