PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <lis3mdl.h>
Classes | |
struct | _last_report |
used for info() More... | |
Public Member Functions | |
LIS3MDL (device::Device *interface, const char *path, enum Rotation rotation) | |
virtual | ~LIS3MDL () |
virtual int | init () |
virtual int | ioctl (struct file *file_pointer, int cmd, unsigned long arg) |
virtual int | read (struct file *file_pointer, char *buffer, size_t buffer_len) |
void | print_info () |
Diagnostics - print some basic information about the driver. More... | |
int | set_default_register_values () |
Configures the device with default register values. More... | |
void | stop () |
Stop the automatic measurement state machine. More... | |
Public Member Functions inherited from device::CDev | |
CDev (const char *name, const char *devname) | |
Constructor. More... | |
virtual | ~CDev ()=default |
virtual int | ioctl (file_t *filep, int cmd, unsigned long arg) |
Perform an ioctl operation on the device. More... | |
Public Member Functions inherited from device::Device | |
Device (const Device &)=delete | |
Device & | operator= (const Device &)=delete |
Device (Device &&)=delete | |
Device & | operator= (Device &&)=delete |
virtual | ~Device ()=default |
Destructor. More... | |
virtual int | read (unsigned address, void *data, unsigned count) |
Read directly from the device. More... | |
virtual int | write (unsigned address, void *data, unsigned count) |
Write directly to the device. More... | |
virtual int | ioctl (unsigned operation, unsigned &arg) |
Perform a device-specific operation. More... | |
uint32_t | get_device_id () const |
DeviceBusType | get_device_bus_type () const |
Return the bus type the device is connected to. More... | |
void | set_device_bus_type (DeviceBusType bus_type) |
uint8_t | get_device_bus () const |
Return the bus ID the device is connected to. More... | |
void | set_device_bus (uint8_t bus) |
uint8_t | get_device_address () const |
Return the bus address of the device. More... | |
void | set_device_address (int address) |
uint8_t | get_device_type () const |
Return the device type. More... | |
void | set_device_type (uint8_t devtype) |
virtual bool | external () const |
Public Member Functions inherited from cdev::CDev | |
CDev (const char *devname) | |
Constructor. More... | |
CDev (const CDev &)=delete | |
CDev & | operator= (const CDev &)=delete |
CDev (CDev &&)=delete | |
CDev & | operator= (CDev &&)=delete |
virtual int | open (file_t *filep) |
Handle an open of the device. More... | |
virtual int | close (file_t *filep) |
Handle a close of the device. More... | |
virtual ssize_t | read (file_t *filep, char *buffer, size_t buflen) |
Perform a read from the device. More... | |
virtual ssize_t | write (file_t *filep, const char *buffer, size_t buflen) |
Perform a write to the device. More... | |
virtual off_t | seek (file_t *filep, off_t offset, int whence) |
Perform a logical seek operation on the device. More... | |
virtual int | poll (file_t *filep, px4_pollfd_struct_t *fds, bool setup) |
Perform a poll setup/teardown operation. More... | |
const char * | get_devname () const |
Get the device name. More... | |
Protected Attributes | |
Device * | _interface |
Protected Attributes inherited from device::CDev | |
bool | _pub_blocked {false} |
true if publishing should be blocked More... | |
Protected Attributes inherited from device::Device | |
const char * | _name {nullptr} |
driver name More... | |
bool | _debug_enabled {false} |
if true, debug messages are printed More... | |
Protected Attributes inherited from cdev::CDev | |
px4_sem_t | _lock |
lock to protect access to all class members (also for derived classes) More... | |
Private Member Functions | |
int | calibrate (struct file *file_pointer, unsigned enable) |
Performs the on-sensor scale calibration routine. More... | |
int | collect () |
Collect the result of the most recent measurement. More... | |
int | check_scale () |
Check the current scale calibration. More... | |
int | check_offset () |
Check the current offset calibration. More... | |
void | Run () override |
Performs a poll cycle; collect from the previous measurement and start a new one. More... | |
int | measure () |
Issue a measurement command. More... | |
int | reset () |
Resets the device. More... | |
void | start () |
Initialises the automatic measurement state machine and start it. More... | |
int | set_excitement (unsigned enable) |
Performs the on-sensor scale calibration routine. More... | |
int | set_range (unsigned range) |
Sets the sensor internal range to handle at least the argument in Gauss. More... | |
int | read_reg (uint8_t reg, uint8_t &val) |
Reads a register. More... | |
int | write_reg (uint8_t reg, uint8_t val) |
Writes a register. More... | |
LIS3MDL (const LIS3MDL &) | |
LIS3MDL | operator= (const LIS3MDL &) |
Private Attributes | |
ringbuffer::RingBuffer * | _reports |
struct mag_calibration_s | _scale |
orb_advert_t | _mag_topic |
perf_counter_t | _comms_errors |
perf_counter_t | _conf_errors |
perf_counter_t | _range_errors |
perf_counter_t | _sample_perf |
bool | _calibrated |
the calibration is valid More... | |
bool | _continuous_mode_set |
enum OPERATING_MODE | _mode |
enum Rotation | _rotation |
unsigned int | _measure_interval |
int | _class_instance |
int | _orb_class_instance |
float | _range_ga |
float | _range_scale |
uint8_t | _check_state_cnt |
uint8_t | _cntl_reg1 |
uint8_t | _cntl_reg2 |
uint8_t | _cntl_reg3 |
uint8_t | _cntl_reg4 |
uint8_t | _cntl_reg5 |
uint8_t | _range_bits |
uint8_t | _temperature_counter |
uint8_t | _temperature_error_count |
Additional Inherited Members | |
Public Types inherited from device::Device | |
enum | DeviceBusType { DeviceBusType_UNKNOWN = 0, DeviceBusType_I2C = 1, DeviceBusType_SPI = 2, DeviceBusType_UAVCAN = 3, DeviceBusType_SIMULATION = 4 } |
Device bus types for DEVID. More... | |
Static Public Member Functions inherited from device::Device | |
static const char * | get_device_bus_string (DeviceBusType bus) |
static int | device_id_print_buffer (char *buffer, int length, uint32_t id) |
Print decoded device id string to a buffer. More... | |
Protected Member Functions inherited from device::Device | |
Device (const char *name) | |
Device (const char *name, DeviceBusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype=0) | |
Device (DeviceBusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype=0) | |
Protected Member Functions inherited from cdev::CDev | |
virtual pollevent_t | poll_state (file_t *filep) |
Check the current state of the device for poll events from the perspective of the file. More... | |
virtual void | poll_notify (pollevent_t events) |
Report new poll events. More... | |
virtual void | poll_notify_one (px4_pollfd_struct_t *fds, pollevent_t events) |
Internal implementation of poll_notify. More... | |
virtual int | open_first (file_t *filep) |
Notification of the first open. More... | |
virtual int | close_last (file_t *filep) |
Notification of the last close. More... | |
virtual int | register_class_devname (const char *class_devname) |
Register a class device name, automatically adding device class instance suffix if need be. More... | |
virtual int | unregister_class_devname (const char *class_devname, unsigned class_instance) |
Register a class device name, automatically adding device class instance suffix if need be. More... | |
void | lock () |
Take the driver lock. More... | |
void | unlock () |
Release the driver lock. More... | |
int | unregister_driver_and_memory () |
First, unregisters the driver. More... | |
Static Protected Attributes inherited from cdev::CDev | |
static const px4_file_operations_t | fops = {} |
Pointer to the default cdev file operations table; useful for registering clone devices etc. More... | |
LIS3MDL::LIS3MDL | ( | device::Device * | interface, |
const char * | path, | ||
enum Rotation | rotation | ||
) |
Definition at line 45 of file lis3mdl.cpp.
References _calibrated, _check_state_cnt, _class_instance, _cntl_reg1, _cntl_reg2, _cntl_reg3, _cntl_reg4, _cntl_reg5, _comms_errors, _conf_errors, _continuous_mode_set, _interface, _mag_topic, _measure_interval, _mode, _orb_class_instance, _range_bits, _range_errors, _range_ga, _range_scale, _rotation, _sample_perf, _scale, _temperature_counter, _temperature_error_count, CNTL_REG1_DEFAULT, CNTL_REG2_DEFAULT, CNTL_REG3_DEFAULT, CNTL_REG4_DEFAULT, CNTL_REG5_DEFAULT, CONTINUOUS, DRV_MAG_DEVTYPE_LIS3MDL, f(), PC_COUNT, PC_ELAPSED, perf_alloc, mag_calibration_s::x_offset, mag_calibration_s::x_scale, mag_calibration_s::y_offset, mag_calibration_s::y_scale, mag_calibration_s::z_offset, and mag_calibration_s::z_scale.
|
virtual |
Definition at line 92 of file lis3mdl.cpp.
References _class_instance, _comms_errors, _conf_errors, _mag_topic, _range_errors, _reports, _sample_perf, MAG_BASE_DEVICE_PATH, orb_unadvertise(), perf_free(), stop(), and cdev::CDev::unregister_class_devname().
|
private |
|
private |
Performs the on-sensor scale calibration routine.
enable | set to 1 to enable self-test strap, 0 to disable |
Definition at line 117 of file lis3mdl.cpp.
References f(), fd, ioctl(), mag_report, MAGIOCEXSTRAP, MAGIOCSRANGE, OK, cdev::CDev::poll(), read(), SENSORIOCSPOLLRATE, set_default_register_values(), set_range(), and warn.
Referenced by ioctl().
|
private |
Check the current offset calibration.
Definition at line 289 of file lis3mdl.cpp.
References _scale, f(), FLT_EPSILON, mag_calibration_s::x_offset, mag_calibration_s::y_offset, and mag_calibration_s::z_offset.
|
private |
Check the current scale calibration.
Definition at line 308 of file lis3mdl.cpp.
References _scale, f(), FLT_EPSILON, mag_calibration_s::x_scale, mag_calibration_s::y_scale, and mag_calibration_s::z_scale.
|
private |
Collect the result of the most recent measurement.
Silicon Bug: the X axis will be read instead of the temperature registers if you do a sequential read through XYZ. The temperature registers must be addressed directly.
RAW outputs
Definition at line 327 of file lis3mdl.cpp.
References _comms_errors, _interface, _mag_topic, _orb_class_instance, device::CDev::_pub_blocked, _range_scale, _reports, _rotation, _sample_perf, _scale, ADDR_OUT_T_L, ADDR_OUT_X_L, DEVICE_DEBUG, hrt_absolute_time(), mag_report, MAGIOCGEXTERNAL, OK, orb_advertise_multi(), ORB_ID, ORB_PRIO_HIGH, ORB_PRIO_MAX, orb_publish(), perf_begin(), perf_count(), perf_end(), perf_event_count(), cdev::CDev::poll_notify(), rotate_3f(), mag_calibration_s::x_offset, mag_calibration_s::x_scale, mag_calibration_s::y_offset, mag_calibration_s::y_scale, mag_calibration_s::z_offset, and mag_calibration_s::z_scale.
Referenced by read(), and Run().
|
virtual |
Reimplemented from device::CDev.
Definition at line 468 of file lis3mdl.cpp.
References _class_instance, _reports, DEVICE_DEBUG, ToneAlarmInterface::init(), MAG_BASE_DEVICE_PATH, mag_report, OK, cdev::CDev::register_class_devname(), and reset().
|
virtual |
Definition at line 495 of file lis3mdl.cpp.
References _interface, _measure_interval, _scale, calibrate(), DEVICE_DEBUG, LIS3MDL_CONVERSION_INTERVAL, MAGIOCCALIBRATE, MAGIOCEXSTRAP, MAGIOCGEXTERNAL, MAGIOCGSCALE, MAGIOCSRANGE, MAGIOCSSCALE, reset(), SENSOR_POLLRATE_DEFAULT, SENSORIOCRESET, SENSORIOCSPOLLRATE, set_excitement(), set_range(), and start().
Referenced by calibrate().
|
private |
Issue a measurement command.
Definition at line 579 of file lis3mdl.cpp.
References _comms_errors, _continuous_mode_set, _mode, ADDR_CTRL_REG3, CONTINUOUS, MODE_REG_CONTINOUS_MODE, MODE_REG_SINGLE_MODE, OK, perf_count(), SINGLE, and write_reg().
Referenced by read(), and Run().
void LIS3MDL::print_info | ( | ) |
Diagnostics - print some basic information about the driver.
Definition at line 602 of file lis3mdl.cpp.
References _comms_errors, _measure_interval, _reports, _sample_perf, and perf_print_counter().
Referenced by lis3mdl::info().
|
virtual |
Definition at line 632 of file lis3mdl.cpp.
References _measure_interval, _reports, collect(), LIS3MDL_CONVERSION_INTERVAL, mag_report, measure(), and OK.
Referenced by calibrate().
|
private |
Reads a register.
reg | The register to read. |
val | The value read. |
Definition at line 807 of file lis3mdl.cpp.
References _interface.
Referenced by set_excitement(), and set_range().
|
private |
Resets the device.
Definition at line 612 of file lis3mdl.cpp.
References _range_ga, OK, set_default_register_values(), and set_range().
Referenced by init(), and ioctl().
|
overrideprivate |
Performs a poll cycle; collect from the previous measurement and start a new one.
This is the heart of the measurement state machine. This function alternately starts a measurement, or collects the data from the previous measurement.
When the interval between measurements is greater than the minimum measurement interval, a gap is inserted between collection and measurement to provide the most recent measurement possible at the next interval.
Definition at line 441 of file lis3mdl.cpp.
References _measure_interval, collect(), DEVICE_DEBUG, LIS3MDL_CONVERSION_INTERVAL, measure(), OK, and start().
int LIS3MDL::set_default_register_values | ( | ) |
Configures the device with default register values.
Definition at line 690 of file lis3mdl.cpp.
References ADDR_CTRL_REG1, ADDR_CTRL_REG2, ADDR_CTRL_REG3, ADDR_CTRL_REG4, ADDR_CTRL_REG5, CNTL_REG1_DEFAULT, CNTL_REG2_DEFAULT, CNTL_REG3_DEFAULT, CNTL_REG4_DEFAULT, CNTL_REG5_DEFAULT, and write_reg().
Referenced by calibrate(), reset(), and start().
|
private |
Performs the on-sensor scale calibration routine.
enable | set to 1 to enable self-test positive strap, -1 to enable negative strap, 0 to set to normal mode |
Definition at line 702 of file lis3mdl.cpp.
References _cntl_reg1, _comms_errors, ADDR_CTRL_REG1, OK, perf_count(), read_reg(), and write_reg().
Referenced by ioctl().
|
private |
Sets the sensor internal range to handle at least the argument in Gauss.
range | The sensor range value to be set. |
Definition at line 735 of file lis3mdl.cpp.
References _comms_errors, _range_bits, _range_ga, _range_scale, ADDR_CTRL_REG2, OK, perf_count(), read_reg(), and write_reg().
Referenced by calibrate(), ioctl(), and reset().
|
private |
Initialises the automatic measurement state machine and start it.
Definition at line 785 of file lis3mdl.cpp.
References _reports, and set_default_register_values().
Referenced by ioctl(), and Run().
void LIS3MDL::stop | ( | ) |
Stop the automatic measurement state machine.
Definition at line 797 of file lis3mdl.cpp.
References _measure_interval.
Referenced by lis3mdl::stop(), and ~LIS3MDL().
|
private |
Writes a register.
reg | The register to write. |
val | The value to write. |
Definition at line 816 of file lis3mdl.cpp.
References _interface.
Referenced by measure(), set_default_register_values(), set_excitement(), and set_range().
|
private |
|
private |
|
private |
Definition at line 166 of file lis3mdl.h.
Referenced by init(), LIS3MDL(), and ~LIS3MDL().
|
private |
Definition at line 173 of file lis3mdl.h.
Referenced by LIS3MDL(), and set_excitement().
|
private |
|
private |
|
private |
|
private |
|
private |
Definition at line 152 of file lis3mdl.h.
Referenced by collect(), LIS3MDL(), measure(), print_info(), set_excitement(), set_range(), and ~LIS3MDL().
|
private |
Definition at line 153 of file lis3mdl.h.
Referenced by LIS3MDL(), and ~LIS3MDL().
|
private |
|
protected |
Definition at line 140 of file lis3mdl.h.
Referenced by collect(), ioctl(), LIS3MDL(), read_reg(), and write_reg().
|
private |
Definition at line 150 of file lis3mdl.h.
Referenced by collect(), LIS3MDL(), and ~LIS3MDL().
|
private |
|
private |
|
private |
|
private |
Definition at line 178 of file lis3mdl.h.
Referenced by LIS3MDL(), and set_range().
|
private |
Definition at line 154 of file lis3mdl.h.
Referenced by LIS3MDL(), and ~LIS3MDL().
|
private |
Definition at line 169 of file lis3mdl.h.
Referenced by LIS3MDL(), reset(), and set_range().
|
private |
Definition at line 170 of file lis3mdl.h.
Referenced by collect(), LIS3MDL(), and set_range().
|
private |
Definition at line 144 of file lis3mdl.h.
Referenced by collect(), init(), print_info(), read(), start(), and ~LIS3MDL().
|
private |
|
private |
Definition at line 155 of file lis3mdl.h.
Referenced by collect(), LIS3MDL(), print_info(), and ~LIS3MDL().
|
private |
Definition at line 146 of file lis3mdl.h.
Referenced by check_offset(), check_scale(), collect(), ioctl(), and LIS3MDL().
|
private |
|
private |