51 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp> 54 #include <px4_platform_common/defines.h> 61 #define LIS3MDL_CONVERSION_INTERVAL (1000000 / 80) 63 #define NUM_BUS_OPTIONS (sizeof(lis3mdl::bus_options)/sizeof(lis3mdl::bus_options[0])) 65 #define ADDR_WHO_AM_I 0x0f 66 #define ID_WHO_AM_I 0x3d 68 #define ADDR_CTRL_REG1 0x20 69 #define ADDR_CTRL_REG2 0x21 70 #define ADDR_CTRL_REG3 0x22 71 #define ADDR_CTRL_REG4 0x23 72 #define ADDR_CTRL_REG5 0x24 74 #define ADDR_STATUS_REG 0x27 75 #define ADDR_OUT_X_L 0x28 76 #define ADDR_OUT_X_H 0x29 77 #define ADDR_OUT_Y_L 0x2a 78 #define ADDR_OUT_Y_H 0x2b 79 #define ADDR_OUT_Z_L 0x2c 80 #define ADDR_OUT_Z_H 0x2d 81 #define ADDR_OUT_T_L 0x2e 82 #define ADDR_OUT_T_H 0x2f 84 #define MODE_REG_CONTINOUS_MODE (0 << 0) 85 #define MODE_REG_SINGLE_MODE (1 << 0) 87 #define CNTL_REG1_DEFAULT 0xFC 88 #define CNTL_REG2_DEFAULT 0x00 89 #define CNTL_REG3_DEFAULT 0x00 90 #define CNTL_REG4_DEFAULT 0x0C 91 #define CNTL_REG5_DEFAULT 0x00 120 virtual int ioctl(
struct file *file_pointer,
int cmd,
unsigned long arg);
122 virtual int read(
struct file *file_pointer,
char *buffer,
size_t buffer_len);
274 int read_reg(uint8_t reg, uint8_t &val);
void print_info()
Diagnostics - print some basic information about the driver.
int reset()
Resets the device.
virtual int read(struct file *file_pointer, char *buffer, size_t buffer_len)
int read_reg(uint8_t reg, uint8_t &val)
Reads a register.
int write_reg(uint8_t reg, uint8_t val)
Writes a register.
enum OPERATING_MODE _mode
mag scaling factors; Vout = (Vin * Vscale) + Voffset
Device(const Device &)=delete
perf_counter_t _sample_perf
bool _continuous_mode_set
High-resolution timer with callouts and timekeeping.
perf_counter_t _comms_errors
Abstract class for any character device.
void stop()
Stop the automatic measurement state machine.
virtual int ioctl(struct file *file_pointer, int cmd, unsigned long arg)
int set_excitement(unsigned enable)
Performs the on-sensor scale calibration routine.
int measure()
Issue a measurement command.
void Run() override
Performs a poll cycle; collect from the previous measurement and start a new one. ...
Rotation
Enum for board and external compass rotations.
perf_counter_t _range_errors
uint8_t _temperature_counter
struct mag_calibration_s _scale
LIS3MDL(device::Device *interface, const char *path, enum Rotation rotation)
perf_counter_t _conf_errors
int check_offset()
Check the current offset calibration.
int set_range(unsigned range)
Sets the sensor internal range to handle at least the argument in Gauss.
LIS3MDL operator=(const LIS3MDL &)
void start()
Initialises the automatic measurement state machine and start it.
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
device::Device * LIS3MDL_SPI_interface(int bus)
int calibrate(struct file *file_pointer, unsigned enable)
Performs the on-sensor scale calibration routine.
uint8_t _temperature_error_count
int set_default_register_values()
Configures the device with default register values.
struct @83::@85::@87 file
Fundamental base class for all physical drivers (I2C, SPI).
int collect()
Collect the result of the most recent measurement.
bool _calibrated
the calibration is valid
device::Device * LIS3MDL_I2C_interface(int bus)
unsigned int _measure_interval
int check_scale()
Check the current scale calibration.
Performance measuring tools.
Base class for devices connected via I2C.
ringbuffer::RingBuffer * _reports