40 #include <px4_platform_common/px4_config.h> 48 #include <sys/types.h> 51 #include <arch/board/board.h> 57 #include "board_config.h" 60 #if defined(PX4_I2C_BUS_ONBOARD) || defined(PX4_I2C_BUS_EXPANSION) 62 #define LIS3MDLL_ADDRESS 0x1e 64 class LIS3MDL_I2C :
public device::I2C
68 virtual ~LIS3MDL_I2C() =
default;
70 virtual int ioctl(
unsigned operation,
unsigned &arg);
71 virtual int read(
unsigned address,
void *
data,
unsigned count);
72 virtual int write(
unsigned address,
void *
data,
unsigned count);
85 return new LIS3MDL_I2C(bus);
88 LIS3MDL_I2C::LIS3MDL_I2C(
int bus) :
89 I2C(
"LIS3MDL_I2C", nullptr, bus, LIS3MDLL_ADDRESS, 400000)
95 LIS3MDL_I2C::ioctl(
unsigned operation,
unsigned &arg)
102 case DEVIOCGDEVICEID:
103 return CDev::ioctl(
nullptr, operation, arg);
135 uint8_t cmd = address;
136 return transfer(&cmd, 1, (uint8_t *)data, count);
144 if (
sizeof(buf) < (count + 1)) {
149 memcpy(&buf[1], data, count);
151 return transfer(&buf[0], count + 1,
nullptr, 0);
#define MAGIOCGEXTERNAL
determine if mag is external or onboard
virtual int read(struct file *file_pointer, char *buffer, size_t buffer_len)
#define DRV_MAG_DEVTYPE_LIS3MDL
static void read(bootloader_app_shared_t *pshared)
Generic device / sensor interface.
Shared defines for the LIS3MDL driver.
virtual bool external() const
static void write(bootloader_app_shared_t *pshared)
Fundamental base class for all physical drivers (I2C, SPI).
device::Device * LIS3MDL_I2C_interface(int bus)
#define DEVICE_DEBUG(FMT,...)
Base class for devices connected via I2C.