40 #include <px4_platform_common/px4_config.h> 48 #include <sys/types.h> 51 #include <arch/board/board.h> 57 #include "board_config.h" 63 #define DIR_READ (1<<7) 64 #define DIR_WRITE (0<<7) 65 #define ADDR_INCREMENT (1<<6) 67 class LIS3MDL_SPI :
public device::SPI
70 LIS3MDL_SPI(
int bus, uint32_t
device);
71 virtual ~LIS3MDL_SPI() =
default;
74 virtual int ioctl(
unsigned operation,
unsigned &arg);
75 virtual int read(
unsigned address,
void *
data,
unsigned count);
76 virtual int write(
unsigned address,
void *
data,
unsigned count);
85 return new LIS3MDL_SPI(bus, PX4_SPIDEV_LIS);
88 LIS3MDL_SPI::LIS3MDL_SPI(
int bus, uint32_t
device) :
89 SPI(
"LIS3MDL_SPI", nullptr, bus, device,
SPIDEV_MODE3, 11 * 1000 * 1000 )
122 LIS3MDL_SPI::ioctl(
unsigned operation,
unsigned &arg)
136 case DEVIOCGDEVICEID:
137 return CDev::ioctl(
nullptr, operation, arg);
152 if (
sizeof(buf) < (count + 1)) {
158 int ret = transfer(&buf[0], &buf[0], count + 1);
159 memcpy(data, &buf[1], count);
168 if (
sizeof(buf) < (count + 1)) {
173 memcpy(&buf[1], data, count);
175 return transfer(&buf[0], &buf[0], count + 1);
#define MAGIOCGEXTERNAL
determine if mag is external or onboard
Namespace encapsulating all device framework classes, functions and data.
#define DRV_MAG_DEVTYPE_LIS3MDL
static void read(bootloader_app_shared_t *pshared)
Generic device / sensor interface.
void init()
Activates/configures the hardware registers.
Shared defines for the LIS3MDL driver.
device::Device * LIS3MDL_SPI_interface(int bus)
static void write(bootloader_app_shared_t *pshared)
Fundamental base class for all physical drivers (I2C, SPI).
#define DEVICE_DEBUG(FMT,...)