forked from Archive/PX4-Autopilot
[DO NOT MERGE] px4_i2c_device_external hacks
This commit is contained in:
parent
b922307ddb
commit
a47895e809
|
@ -269,6 +269,8 @@
|
|||
|
||||
#define PX4_I2C_BUS_MTD 4,5
|
||||
|
||||
#define BOARD_OVERRIDE_I2C_DEVICE_EXTERNAL
|
||||
|
||||
|
||||
#define BOARD_NUM_IO_TIMERS 5
|
||||
|
||||
|
|
|
@ -33,8 +33,47 @@
|
|||
|
||||
#include <px4_arch/i2c_hw_description.h>
|
||||
|
||||
#include <lib/drivers/device/Device.hpp>
|
||||
#include <px4_platform_common/i2c.h>
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusExternal(1),
|
||||
initI2CBusExternal(2),
|
||||
initI2CBusExternal(4),
|
||||
};
|
||||
|
||||
bool px4_i2c_device_external(const uint32_t device_id)
|
||||
{
|
||||
{
|
||||
// The internal baro and mag on Pixhawk 6C are on an external
|
||||
// bus. On rev 0, the bus is actually exposed externally, on
|
||||
// rev 1+, it is properly internal, however, still marked as
|
||||
// external for compatibility.
|
||||
|
||||
// device_id: 4028193
|
||||
device::Device::DeviceId device_id_baro{};
|
||||
device_id_baro.devid_s.bus_type = device::Device::DeviceBusType_I2C;
|
||||
device_id_baro.devid_s.bus = 4;
|
||||
device_id_baro.devid_s.address = 0x77;
|
||||
device_id_baro.devid_s.devtype = DRV_BARO_DEVTYPE_MS5611;
|
||||
|
||||
if (device_id_baro.devid == device_id) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// device_id: 396321
|
||||
device::Device::DeviceId device_id_mag{};
|
||||
device_id_mag.devid_s.bus_type = device::Device::DeviceBusType_I2C;
|
||||
device_id_mag.devid_s.bus = 4;
|
||||
device_id_mag.devid_s.address = 0xc;
|
||||
device_id_mag.devid_s.devtype = DRV_MAG_DEVTYPE_IST8310;
|
||||
|
||||
if (device_id_mag.devid == device_id) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
device::Device::DeviceId dev_id{};
|
||||
dev_id.devid = device_id;
|
||||
return px4_i2c_bus_external(dev_id.devid_s.bus);
|
||||
}
|
||||
|
|
|
@ -42,7 +42,17 @@ bool px4_i2c_bus_external(const px4_i2c_bus_t &bus)
|
|||
{
|
||||
return bus.is_external;
|
||||
}
|
||||
#endif
|
||||
#endif // BOARD_OVERRIDE_I2C_BUS_EXTERNAL
|
||||
|
||||
#ifndef BOARD_OVERRIDE_I2C_DEVICE_EXTERNAL
|
||||
#include <drivers/device/Device.hpp>
|
||||
bool px4_i2c_device_external(const uint32_t device_id)
|
||||
{
|
||||
device::Device::DeviceId dev_id{};
|
||||
dev_id.devid = device_id;
|
||||
return px4_i2c_bus_external(dev_id.devid_s.bus);
|
||||
}
|
||||
#endif // BOARD_OVERRIDE_I2C_DEVICE_EXTERNAL
|
||||
|
||||
bool I2CBusIterator::next()
|
||||
{
|
||||
|
|
|
@ -66,6 +66,11 @@ static inline bool px4_i2c_bus_external(int bus)
|
|||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* runtime-check if a board has a specific device as external.
|
||||
* This can be overridden by a board to add run-time checks.
|
||||
*/
|
||||
__EXPORT bool px4_i2c_device_external(const uint32_t device_id);
|
||||
|
||||
/**
|
||||
* @class I2CBusIterator
|
||||
|
|
|
@ -108,7 +108,7 @@ protected:
|
|||
*/
|
||||
int transfer(const uint8_t *send, const unsigned send_len, uint8_t *recv, const unsigned recv_len);
|
||||
|
||||
bool external() const override { return px4_i2c_bus_external(_device_id.devid_s.bus); }
|
||||
bool external() const override { return px4_i2c_device_external(_device_id.devid); }
|
||||
|
||||
private:
|
||||
static unsigned int _bus_clocks[PX4_NUMBER_I2C_BUSES];
|
||||
|
|
|
@ -104,7 +104,7 @@ protected:
|
|||
*/
|
||||
int transfer(const uint8_t *send, const unsigned send_len, uint8_t *recv, const unsigned recv_len);
|
||||
|
||||
virtual bool external() const override { return px4_i2c_bus_external(_device_id.devid_s.bus); }
|
||||
virtual bool external() const override { return px4_i2c_device_external(_device_id.devid); }
|
||||
|
||||
private:
|
||||
int _fd{-1};
|
||||
|
|
|
@ -250,7 +250,7 @@ bool DeviceExternal(uint32_t device_id)
|
|||
switch (bus_type) {
|
||||
case device::Device::DeviceBusType_I2C:
|
||||
#if defined(CONFIG_I2C)
|
||||
external = px4_i2c_bus_external(id.devid_s.bus);
|
||||
external = px4_i2c_device_external(device_id);
|
||||
#endif // CONFIG_I2C
|
||||
break;
|
||||
|
||||
|
|
Loading…
Reference in New Issue