PX4 Firmware
PX4 Autopilot Software http://px4.io
HMC5883 Class Reference

#include <HMC5883.hpp>

Inheritance diagram for HMC5883:
Collaboration diagram for HMC5883:

Classes

struct  _last_report
 used for info() More...
 

Public Member Functions

 HMC5883 (device::Device *interface, const char *path, enum Rotation rotation)
 
virtual ~HMC5883 ()
 
virtual int init ()
 
virtual ssize_t read (cdev::file_t *filp, char *buffer, size_t buflen)
 Perform a read from the device. More...
 
virtual int ioctl (cdev::file_t *filp, int cmd, unsigned long arg)
 Perform an ioctl operation on the device. More...
 
void stop ()
 Stop the automatic measurement state machine. More...
 
void print_info ()
 Diagnostics - print some basic information about the driver. More...
 
- Public Member Functions inherited from device::CDev
 CDev (const char *name, const char *devname)
 Constructor. More...
 
virtual ~CDev ()=default
 
- Public Member Functions inherited from device::Device
 Device (const Device &)=delete
 
Deviceoperator= (const Device &)=delete
 
 Device (Device &&)=delete
 
Deviceoperator= (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
 
CDevoperator= (const CDev &)=delete
 
 CDev (CDev &&)=delete
 
CDevoperator= (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 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

void start ()
 Initialise the automatic measurement state machine and start it. More...
 
int reset ()
 Reset the device. More...
 
int calibrate (cdev::file_t *filp, unsigned enable)
 Perform the on-sensor scale calibration routine. More...
 
int set_excitement (unsigned enable)
 Perform the on-sensor scale calibration routine. More...
 
int set_temperature_compensation (unsigned enable)
 enable hmc5983 temperature compensation More...
 
int set_range (unsigned range)
 Set the sensor range. More...
 
void check_range (void)
 check the sensor range. More...
 
void check_conf (void)
 check the sensor configuration. More...
 
void Run () override
 Perform a poll cycle; collect from the previous measurement and start a new one. More...
 
int write_reg (uint8_t reg, uint8_t val)
 Write a register. More...
 
int read_reg (uint8_t reg, uint8_t &val)
 Read a register. More...
 
int measure ()
 Issue a measurement command. More...
 
int collect ()
 Collect the result of the most recent measurement. More...
 
float meas_to_float (uint8_t in[2])
 Convert a big-endian signed 16-bit value to a float. More...
 
int check_scale ()
 Check the current scale calibration. More...
 
int check_offset ()
 Check the current offset calibration. More...
 

Private Attributes

unsigned _measure_interval {0}
 
ringbuffer::RingBuffer * _reports
 
struct mag_calibration_s _scale
 
float _range_scale
 
float _range_ga
 
bool _collect_phase
 
int _class_instance
 
int _orb_class_instance
 
orb_advert_t _mag_topic
 
perf_counter_t _sample_perf
 
perf_counter_t _comms_errors
 
perf_counter_t _range_errors
 
perf_counter_t _conf_errors
 
bool _sensor_ok
 sensor was found and reports ok More...
 
enum Rotation _rotation
 
uint8_t _range_bits
 
uint8_t _conf_reg
 
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...
 

Detailed Description

Definition at line 113 of file HMC5883.hpp.

Constructor & Destructor Documentation

◆ HMC5883()

HMC5883::HMC5883 ( device::Device interface,
const char *  path,
enum Rotation  rotation 
)

◆ ~HMC5883()

HMC5883::~HMC5883 ( )
virtual

Definition at line 74 of file HMC5883.cpp.

References _class_instance, _comms_errors, _conf_errors, _range_errors, _reports, _sample_perf, MAG_BASE_DEVICE_PATH, perf_free(), stop(), and cdev::CDev::unregister_class_devname().

Here is the call graph for this function:

Member Function Documentation

◆ calibrate()

int HMC5883::calibrate ( cdev::file_t filp,
unsigned  enable 
)
private

Perform the on-sensor scale calibration routine.

Note
The sensor will continue to provide measurements, these will however reflect the uncalibrated sensor state until the calibration routine has been completed.
Parameters
enableset to 1 to enable self-test strap, 0 to disable

Definition at line 679 of file HMC5883.cpp.

References check_scale(), f(), fd, ioctl(), MAGIOCEXSTRAP, MAGIOCGSCALE, MAGIOCSRANGE, MAGIOCSSCALE, OK, px4_ioctl(), px4_poll(), px4_read(), SENSORIOCSPOLLRATE, warn, warnx, 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 ioctl().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ check_conf()

void HMC5883::check_conf ( void  )
private

check the sensor configuration.

check that the configuration register has the right value.

checks that the config of the sensor is correctly set, to cope with communication errors causing the configuration to change

This is done periodically to cope with I2C bus noise causing the configuration of the compass to change.

Definition at line 221 of file HMC5883.cpp.

References _comms_errors, _conf_errors, _conf_reg, ADDR_CONF_A, OK, perf_count(), read_reg(), and write_reg().

Referenced by collect().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ check_offset()

int HMC5883::check_offset ( )
private

Check the current offset calibration.

Returns
0 if offset calibration is ok, 1 else

Definition at line 873 of file HMC5883.cpp.

References _scale, f(), FLT_EPSILON, mag_calibration_s::x_offset, mag_calibration_s::y_offset, and mag_calibration_s::z_offset.

Here is the call graph for this function:

◆ check_range()

void HMC5883::check_range ( void  )
private

check the sensor range.

check that the range register has the right value.

checks that the range of the sensor is correctly set, to cope with communication errors causing the range to change

This is done periodically to cope with I2C bus noise causing the range of the compass changing.

Definition at line 194 of file HMC5883.cpp.

References _comms_errors, _range_bits, _range_errors, ADDR_CONF_B, OK, perf_count(), read_reg(), and write_reg().

Referenced by collect().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ check_scale()

int HMC5883::check_scale ( )
private

Check the current scale calibration.

Returns
0 if scale calibration is ok, 1 else

Definition at line 855 of file HMC5883.cpp.

References _scale, f(), FLT_EPSILON, mag_calibration_s::x_scale, mag_calibration_s::y_scale, and mag_calibration_s::z_scale.

Referenced by calibrate().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ collect()

int HMC5883::collect ( )
private

Collect the result of the most recent measurement.

Definition at line 484 of file HMC5883.cpp.

References _comms_errors, _conf_reg, _interface, _mag_topic, _orb_class_instance, device::CDev::_pub_blocked, _range_scale, _reports, _rotation, _sample_perf, _scale, _temperature_counter, _temperature_error_count, matrix::abs(), ADDR_DATA_OUT_X_MSB, ADDR_TEMP_OUT_MSB, check_conf(), check_range(), DEVICE_DEBUG, HMC5983_TEMP_SENSOR_ENABLE, 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(), set_temperature_compensation(), 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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init()

int HMC5883::init ( )
virtual

Reimplemented from device::CDev.

Definition at line 95 of file HMC5883.cpp.

References _class_instance, _reports, _sensor_ok, DEVICE_DEBUG, ToneAlarmInterface::init(), MAG_BASE_DEVICE_PATH, mag_report, OK, cdev::CDev::register_class_devname(), and reset().

Referenced by DfHmc5883Wrapper::start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ ioctl()

int HMC5883::ioctl ( cdev::file_t filep,
int  cmd,
unsigned long  arg 
)
virtual

Perform an ioctl operation on the device.

The default implementation handles DIOC_GETPRIV, and otherwise returns -ENOTTY. Subclasses should call the default implementation for any command they do not handle themselves.

Parameters
filepPointer to the NuttX file structure.
cmdThe ioctl command value.
argThe ioctl argument value.
Returns
OK on success, or -errno otherwise.

Reimplemented from device::CDev.

Definition at line 302 of file HMC5883.cpp.

References _interface, _measure_interval, _scale, calibrate(), DEVICE_DEBUG, HMC5883_CONVERSION_INTERVAL, MAGIOCCALIBRATE, MAGIOCEXSTRAP, MAGIOCGEXTERNAL, MAGIOCGSCALE, MAGIOCSRANGE, MAGIOCSSCALE, MAGIOCSTEMPCOMP, OK, reset(), SENSOR_POLLRATE_DEFAULT, SENSORIOCRESET, SENSORIOCSPOLLRATE, set_excitement(), set_range(), set_temperature_compensation(), and start().

Referenced by calibrate().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ meas_to_float()

float HMC5883::meas_to_float ( uint8_t  in[2])
private

Convert a big-endian signed 16-bit value to a float.

Parameters
inA signed 16-bit big-endian value.
Returns
The floating-point representation of the value.

Definition at line 1000 of file HMC5883.cpp.

◆ measure()

int HMC5883::measure ( )
private

Issue a measurement command.

Returns
OK if the measurement command was successful.

Definition at line 467 of file HMC5883.cpp.

References _comms_errors, ADDR_MODE, MODE_REG_SINGLE_MODE, OK, perf_count(), and write_reg().

Referenced by read(), and Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_info()

void HMC5883::print_info ( )

Diagnostics - print some basic information about the driver.

Definition at line 1014 of file HMC5883.cpp.

References _comms_errors, _measure_interval, _reports, _sample_perf, and perf_print_counter().

Referenced by hmc5883::info().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read()

ssize_t HMC5883::read ( cdev::file_t filep,
char *  buffer,
size_t  buflen 
)
virtual

Perform a read from the device.

The default implementation returns -ENOSYS.

Parameters
filepPointer to the NuttX file structure.
bufferPointer to the buffer into which data should be placed.
buflenThe number of bytes to be read.
Returns
The number of bytes read or -errno otherwise.

Reimplemented from cdev::CDev.

Definition at line 244 of file HMC5883.cpp.

References _measure_interval, _reports, collect(), HMC5883_CONVERSION_INTERVAL, mag_report, measure(), and OK.

Here is the call graph for this function:

◆ read_reg()

int HMC5883::read_reg ( uint8_t  reg,
uint8_t &  val 
)
private

Read a register.

Parameters
regThe register to read.
valThe value read.
Returns
OK on read success.

Definition at line 991 of file HMC5883.cpp.

References _interface.

Referenced by check_conf(), check_range(), set_excitement(), set_range(), and set_temperature_compensation().

Here is the caller graph for this function:

◆ reset()

int HMC5883::reset ( )
private

Reset the device.

Definition at line 413 of file HMC5883.cpp.

References _range_ga, f(), and set_range().

Referenced by init(), and ioctl().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Run()

void HMC5883::Run ( )
overrideprivate

Perform 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 420 of file HMC5883.cpp.

References _collect_phase, _measure_interval, collect(), DEVICE_DEBUG, HMC5883_CONVERSION_INTERVAL, measure(), OK, and start().

Here is the call graph for this function:

◆ set_excitement()

int HMC5883::set_excitement ( unsigned  enable)
private

Perform the on-sensor scale calibration routine.

Note
The sensor will continue to provide measurements, these will however reflect the uncalibrated sensor state until the calibration routine has been completed.
Parameters
enableset to 1 to enable self-test positive strap, -1 to enable negative strap, 0 to set to normal mode

Definition at line 891 of file HMC5883.cpp.

References _comms_errors, _conf_reg, ADDR_CONF_A, OK, perf_count(), read_reg(), and write_reg().

Referenced by ioctl().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_range()

int HMC5883::set_range ( unsigned  range)
private

Set the sensor range.

Sets the internal range to handle at least the argument in Gauss.

Definition at line 125 of file HMC5883.cpp.

References _comms_errors, _range_bits, _range_ga, _range_scale, ADDR_CONF_B, f(), OK, perf_count(), read_reg(), and write_reg().

Referenced by ioctl(), and reset().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_temperature_compensation()

int HMC5883::set_temperature_compensation ( unsigned  enable)
private

enable hmc5983 temperature compensation

Definition at line 948 of file HMC5883.cpp.

References _comms_errors, _conf_reg, ADDR_CONF_A, HMC5983_TEMP_SENSOR_ENABLE, OK, perf_count(), read_reg(), and write_reg().

Referenced by collect(), and ioctl().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start()

void HMC5883::start ( )
private

Initialise the automatic measurement state machine and start it.

Note
This function is called at open and error time. It might make sense to make it more aggressive about resetting the bus in case of errors.

Definition at line 392 of file HMC5883.cpp.

References _collect_phase, and _reports.

Referenced by ioctl(), Run(), and DfHmc5883Wrapper::start().

Here is the caller graph for this function:

◆ stop()

void HMC5883::stop ( )

Stop the automatic measurement state machine.

Definition at line 403 of file HMC5883.cpp.

References _measure_interval.

Referenced by DfHmc5883Wrapper::stop(), hmc5883::stop(), and ~HMC5883().

Here is the caller graph for this function:

◆ write_reg()

int HMC5883::write_reg ( uint8_t  reg,
uint8_t  val 
)
private

Write a register.

Parameters
regThe register to write.
valThe value to write.
Returns
OK on write success.

Definition at line 984 of file HMC5883.cpp.

References _interface.

Referenced by check_conf(), check_range(), measure(), set_excitement(), set_range(), and set_temperature_compensation().

Here is the caller graph for this function:

Member Data Documentation

◆ _class_instance

int HMC5883::_class_instance
private

Definition at line 146 of file HMC5883.hpp.

Referenced by HMC5883(), init(), and ~HMC5883().

◆ _collect_phase

bool HMC5883::_collect_phase
private

Definition at line 145 of file HMC5883.hpp.

Referenced by HMC5883(), Run(), and start().

◆ _comms_errors

◆ _conf_errors

perf_counter_t HMC5883::_conf_errors
private

Definition at line 154 of file HMC5883.hpp.

Referenced by check_conf(), HMC5883(), and ~HMC5883().

◆ _conf_reg

uint8_t HMC5883::_conf_reg
private

◆ _interface

Device* HMC5883::_interface
protected

Definition at line 135 of file HMC5883.hpp.

Referenced by collect(), HMC5883(), ioctl(), read_reg(), and write_reg().

◆ _mag_topic

orb_advert_t HMC5883::_mag_topic
private

Definition at line 149 of file HMC5883.hpp.

Referenced by collect(), and HMC5883().

◆ _measure_interval

unsigned HMC5883::_measure_interval {0}
private

Definition at line 139 of file HMC5883.hpp.

Referenced by ioctl(), print_info(), read(), Run(), and stop().

◆ _orb_class_instance

int HMC5883::_orb_class_instance
private

Definition at line 147 of file HMC5883.hpp.

Referenced by collect(), and HMC5883().

◆ _range_bits

uint8_t HMC5883::_range_bits
private

Definition at line 163 of file HMC5883.hpp.

Referenced by check_range(), HMC5883(), and set_range().

◆ _range_errors

perf_counter_t HMC5883::_range_errors
private

Definition at line 153 of file HMC5883.hpp.

Referenced by check_range(), HMC5883(), and ~HMC5883().

◆ _range_ga

float HMC5883::_range_ga
private

Definition at line 144 of file HMC5883.hpp.

Referenced by HMC5883(), reset(), and set_range().

◆ _range_scale

float HMC5883::_range_scale
private

Definition at line 143 of file HMC5883.hpp.

Referenced by collect(), HMC5883(), and set_range().

◆ _reports

ringbuffer::RingBuffer* HMC5883::_reports
private

Definition at line 141 of file HMC5883.hpp.

Referenced by collect(), init(), print_info(), read(), start(), and ~HMC5883().

◆ _rotation

enum Rotation HMC5883::_rotation
private

Definition at line 159 of file HMC5883.hpp.

Referenced by collect(), and HMC5883().

◆ _sample_perf

perf_counter_t HMC5883::_sample_perf
private

Definition at line 151 of file HMC5883.hpp.

Referenced by collect(), HMC5883(), print_info(), and ~HMC5883().

◆ _scale

struct mag_calibration_s HMC5883::_scale
private

Definition at line 142 of file HMC5883.hpp.

Referenced by check_offset(), check_scale(), collect(), HMC5883(), and ioctl().

◆ _sensor_ok

bool HMC5883::_sensor_ok
private

sensor was found and reports ok

Definition at line 157 of file HMC5883.hpp.

Referenced by HMC5883(), and init().

◆ _temperature_counter

uint8_t HMC5883::_temperature_counter
private

Definition at line 165 of file HMC5883.hpp.

Referenced by collect(), and HMC5883().

◆ _temperature_error_count

uint8_t HMC5883::_temperature_error_count
private

Definition at line 166 of file HMC5883.hpp.

Referenced by collect(), and HMC5883().


The documentation for this class was generated from the following files: