41 #include <px4_platform_common/px4_config.h> 43 #include <sys/types.h> 52 #include <arch/board/board.h> 59 #include <board_config.h> 64 #define DIR_READ (1<<7) 65 #define DIR_WRITE (0<<7) 66 #define ADDR_INCREMENT (1<<6) 68 #define HMC_MAX_SEND_LEN 4 69 #define HMC_MAX_RCV_LEN 8 73 class QMC5883_SPI :
public device::SPI
76 QMC5883_SPI(
int bus, uint32_t
device);
77 virtual ~QMC5883_SPI() =
default;
80 virtual int read(
unsigned address,
void *
data,
unsigned count);
81 virtual int write(
unsigned address,
void *
data,
unsigned count);
83 virtual int ioctl(
unsigned operation,
unsigned &arg);
90 return new QMC5883_SPI(bus, PX4_SPIDEV_HMC);
93 QMC5883_SPI::QMC5883_SPI(
int bus, uint32_t
device) :
94 SPI(
"QMC5883_SPI", nullptr, bus, device,
SPIDEV_MODE3, 11 * 1000 * 1000 )
112 uint8_t
data[2] = {0, 0};
121 DEVICE_DEBUG(
"ID byte mismatch (%02x,%02x)", data[0], data[1]);
129 QMC5883_SPI::ioctl(
unsigned operation,
unsigned &arg)
143 case DEVIOCGDEVICEID:
144 return CDev::ioctl(
nullptr, operation, arg);
159 if (
sizeof(buf) < (count + 1)) {
164 memcpy(&buf[1], data, count);
166 return transfer(&buf[0], &buf[0], count + 1);
174 if (
sizeof(buf) < (count + 1)) {
180 int ret = transfer(&buf[0], &buf[0], count + 1);
181 memcpy(data, &buf[1], count);
#define MAGIOCGEXTERNAL
determine if mag is external or onboard
device::Device * QMC5883_SPI_interface(int bus)
Namespace encapsulating all device framework classes, functions and data.
Shared defines for the qmc5883 driver.
static void read(bootloader_app_shared_t *pshared)
Generic device / sensor interface.
virtual int read(unsigned address, void *data, unsigned count)
void init()
Activates/configures the hardware registers.
#define DRV_MAG_DEVTYPE_QMC5883
static void write(bootloader_app_shared_t *pshared)
Fundamental base class for all physical drivers (I2C, SPI).
#define DEVICE_DEBUG(FMT,...)