40 #include <px4_platform_common/px4_config.h> 50 #define DIR_READ (1<<7) 51 #define DIR_WRITE (0<<7) 52 #define ADDR_INCREMENT (1<<6) 54 #define HMC_MAX_SEND_LEN 4 55 #define HMC_MAX_RCV_LEN 8 59 class HMC5883_SPI :
public device::SPI
62 HMC5883_SPI(
int bus, uint32_t
device);
63 virtual ~HMC5883_SPI() =
default;
66 virtual int read(
unsigned address,
void *
data,
unsigned count);
67 virtual int write(
unsigned address,
void *
data,
unsigned count);
69 virtual int ioctl(
unsigned operation,
unsigned &arg);
76 return new HMC5883_SPI(bus, PX4_SPIDEV_HMC);
79 HMC5883_SPI::HMC5883_SPI(
int bus, uint32_t
device) :
80 SPI(
"HMC5883_SPI", nullptr, bus, device,
SPIDEV_MODE3, 11 * 1000 * 1000 )
98 uint8_t
data[3] = {0, 0, 0};
109 DEVICE_DEBUG(
"ID byte mismatch (%02x,%02x,%02x)", data[0], data[1], data[2]);
117 HMC5883_SPI::ioctl(
unsigned operation,
unsigned &arg)
131 case DEVIOCGDEVICEID:
132 return CDev::ioctl(
nullptr, operation, arg);
147 if (
sizeof(buf) < (count + 1)) {
152 memcpy(&buf[1], data, count);
154 return transfer(&buf[0], &buf[0], count + 1);
162 if (
sizeof(buf) < (count + 1)) {
168 int ret = transfer(&buf[0], &buf[0], count + 1);
169 memcpy(data, &buf[1], count);
#define MAGIOCGEXTERNAL
determine if mag is external or onboard
#define DRV_MAG_DEVTYPE_HMC5883
Sensor type definitions.
Namespace encapsulating all device framework classes, functions and data.
static void read(bootloader_app_shared_t *pshared)
Generic device / sensor interface.
void init()
Activates/configures the hardware registers.
device::Device * HMC5883_SPI_interface(int bus)
Shared defines for the hmc5883 driver.
static void write(bootloader_app_shared_t *pshared)
Fundamental base class for all physical drivers (I2C, SPI).
#define DEVICE_DEBUG(FMT,...)