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 RM3100_ADDRESS 0x20 64 class RM3100_I2C :
public device::I2C
68 virtual ~RM3100_I2C() =
default;
71 virtual int ioctl(
unsigned operation,
unsigned &arg);
72 virtual int read(
unsigned address,
void *
data,
unsigned count);
73 virtual int write(
unsigned address,
void *
data,
unsigned count);
86 return new RM3100_I2C(bus);
89 RM3100_I2C::RM3100_I2C(
int bus) :
90 I2C(
"RM300_I2C", nullptr, bus, RM3100_ADDRESS, 400000)
103 RM3100_I2C::ioctl(
unsigned operation,
unsigned &arg)
110 case DEVIOCGDEVICEID:
111 return CDev::ioctl(
nullptr, operation, arg);
143 uint8_t cmd = address;
147 ret = transfer(&cmd, 1,
nullptr, 0);
154 ret = transfer(
nullptr, 0, (uint8_t *)data, count);
164 if (
sizeof(buf) < (count + 1)) {
169 memcpy(&buf[1], data, count);
171 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)
device::Device * RM3100_I2C_interface(int bus)
static void read(bootloader_app_shared_t *pshared)
Generic device / sensor interface.
void init()
Activates/configures the hardware registers.
#define DRV_MAG_DEVTYPE_RM3100
virtual bool external() const
static void write(bootloader_app_shared_t *pshared)
Fundamental base class for all physical drivers (I2C, SPI).
Shared defines for the RM3100 driver.
#define DEVICE_DEBUG(FMT,...)
Base class for devices connected via I2C.