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

#include <rm3100.h>

Inheritance diagram for RM3100:
Collaboration diagram for RM3100:

Classes

struct  _last_report
 used for info() More...
 

Public Member Functions

 RM3100 (device::Device *interface, const char *path, enum Rotation rotation)
 
virtual ~RM3100 ()
 
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
 
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 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 collect ()
 Collect the result of the most recent measurement. More...
 
int self_test ()
 Run sensor self-test. More...
 
int check_measurement ()
 Check whether new data is available or not. More...
 
void convert_signed (int32_t *n)
 Converts int24_t stored in 32-bit container to int32_t. 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...
 
 RM3100 (const RM3100 &)
 
RM3100 operator= (const RM3100 &)
 

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_scale
 
uint8_t _check_state_cnt
 

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 118 of file rm3100.h.

Constructor & Destructor Documentation

◆ RM3100() [1/2]

◆ ~RM3100()

RM3100::~RM3100 ( )
virtual

Definition at line 81 of file rm3100.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:

◆ RM3100() [2/2]

RM3100::RM3100 ( const RM3100 )
private

Member Function Documentation

◆ check_measurement()

int RM3100::check_measurement ( )
private

Check whether new data is available or not.

Returns
0 if new data is available, 1 else

Definition at line 154 of file rm3100.cpp.

References _interface, ADDR_STATUS, status, and STATUS_DRDY.

Referenced by collect(), and self_test().

Here is the caller graph for this function:

◆ collect()

int RM3100::collect ( )
private

Collect the result of the most recent measurement.

RAW outputs As we only have 16 bits to store raw data, the following values are not correct

Definition at line 169 of file rm3100.cpp.

References _comms_errors, _interface, _mag_topic, _orb_class_instance, device::CDev::_pub_blocked, _range_scale, _reports, _rotation, _sample_perf, _scale, ADDR_MX, check_measurement(), convert_signed(), 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(), Run(), and self_test().

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

◆ convert_signed()

void RM3100::convert_signed ( int32_t *  n)
private

Converts int24_t stored in 32-bit container to int32_t.

Definition at line 281 of file rm3100.cpp.

Referenced by collect().

Here is the caller graph for this function:

◆ init()

int RM3100::init ( )
virtual

Reimplemented from device::CDev.

Definition at line 317 of file rm3100.cpp.

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

Here is the call graph for this function:

◆ ioctl()

int RM3100::ioctl ( struct file file_pointer,
int  cmd,
unsigned long  arg 
)
virtual

Definition at line 350 of file rm3100.cpp.

References _interface, _measure_interval, _scale, DEVICE_DEBUG, MAGIOCCALIBRATE, MAGIOCGEXTERNAL, MAGIOCGSCALE, MAGIOCSRANGE, MAGIOCSSCALE, OK, reset(), RM3100_CONVERSION_INTERVAL, SENSOR_POLLRATE_DEFAULT, SENSORIOCRESET, SENSORIOCSPOLLRATE, and start().

Here is the call graph for this function:

◆ measure()

int RM3100::measure ( )
private

Issue a measurement command.

Returns
OK if the measurement command was successful.

Definition at line 439 of file rm3100.cpp.

References _comms_errors, _continuous_mode_set, _interface, _mode, ADDR_CMM, ADDR_POLL, CMM_DEFAULT, CONTINUOUS, CONTINUOUS_MODE, OK, perf_count(), POLL_XYZ, POLLING_MODE, and SINGLE.

Referenced by read(), and Run().

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

◆ operator=()

RM3100 RM3100::operator= ( const RM3100 )
private

◆ print_info()

void RM3100::print_info ( )

Diagnostics - print some basic information about the driver.

Definition at line 477 of file rm3100.cpp.

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

Referenced by rm3100::info().

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

◆ read()

int RM3100::read ( struct file file_pointer,
char *  buffer,
size_t  buffer_len 
)
virtual

Definition at line 501 of file rm3100.cpp.

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

Here is the call graph for this function:

◆ reset()

int RM3100::reset ( )
private

Resets the device.

Definition at line 487 of file rm3100.cpp.

References OK, and set_default_register_values().

Referenced by init(), and ioctl().

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

◆ Run()

void RM3100::Run ( )
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 290 of file rm3100.cpp.

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

Here is the call graph for this function:

◆ self_test()

int RM3100::self_test ( )
private

Run sensor self-test.

Returns
0 if self-test is ok, 1 else

Definition at line 102 of file rm3100.cpp.

References _interface, ADDR_BIST, ADDR_POLL, BIST_SELFTEST, BIST_XYZ_OK, check_measurement(), collect(), POLL_XYZ, RM3100_CONVERSION_INTERVAL, start(), and stop().

Referenced by init().

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

◆ set_default_register_values()

int RM3100::set_default_register_values ( )

Configures the device with default register values.

Definition at line 559 of file rm3100.cpp.

References _interface, ADDR_BIST, ADDR_CCX, ADDR_CCY, ADDR_CCZ, ADDR_CMM, ADDR_TMRC, BIST_DEFAULT, CCX_DEFAULT_LSB, CCX_DEFAULT_MSB, CCY_DEFAULT_LSB, CCY_DEFAULT_MSB, CCZ_DEFAULT_LSB, CCZ_DEFAULT_MSB, CMM_DEFAULT, and TMRC_DEFAULT.

Referenced by reset(), and start().

Here is the caller graph for this function:

◆ start()

void RM3100::start ( )
private

Initialises 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 588 of file rm3100.cpp.

References _measure_interval, _reports, RM3100_CONVERSION_INTERVAL, and set_default_register_values().

Referenced by ioctl(), Run(), and self_test().

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

◆ stop()

void RM3100::stop ( )

Stop the automatic measurement state machine.

Definition at line 601 of file rm3100.cpp.

References _measure_interval.

Referenced by self_test(), and ~RM3100().

Here is the caller graph for this function:

Member Data Documentation

◆ _calibrated

bool RM3100::_calibrated
private

the calibration is valid

Definition at line 165 of file rm3100.h.

Referenced by RM3100().

◆ _check_state_cnt

uint8_t RM3100::_check_state_cnt
private

Definition at line 178 of file rm3100.h.

Referenced by RM3100().

◆ _class_instance

int RM3100::_class_instance
private

Definition at line 173 of file rm3100.h.

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

◆ _comms_errors

perf_counter_t RM3100::_comms_errors
private

Definition at line 159 of file rm3100.h.

Referenced by collect(), measure(), print_info(), RM3100(), and ~RM3100().

◆ _conf_errors

perf_counter_t RM3100::_conf_errors
private

Definition at line 160 of file rm3100.h.

Referenced by RM3100(), and ~RM3100().

◆ _continuous_mode_set

bool RM3100::_continuous_mode_set
private

Definition at line 166 of file rm3100.h.

Referenced by measure(), and RM3100().

◆ _interface

Device* RM3100::_interface
protected

◆ _mag_topic

orb_advert_t RM3100::_mag_topic
private

Definition at line 157 of file rm3100.h.

Referenced by collect(), and RM3100().

◆ _measure_interval

unsigned int RM3100::_measure_interval
private

Definition at line 171 of file rm3100.h.

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

◆ _mode

enum OPERATING_MODE RM3100::_mode
private

Definition at line 168 of file rm3100.h.

Referenced by measure(), and RM3100().

◆ _orb_class_instance

int RM3100::_orb_class_instance
private

Definition at line 174 of file rm3100.h.

Referenced by collect(), and RM3100().

◆ _range_errors

perf_counter_t RM3100::_range_errors
private

Definition at line 161 of file rm3100.h.

Referenced by RM3100(), and ~RM3100().

◆ _range_scale

float RM3100::_range_scale
private

Definition at line 176 of file rm3100.h.

Referenced by collect(), and RM3100().

◆ _reports

ringbuffer::RingBuffer* RM3100::_reports
private

Definition at line 151 of file rm3100.h.

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

◆ _rotation

enum Rotation RM3100::_rotation
private

Definition at line 169 of file rm3100.h.

Referenced by collect(), and RM3100().

◆ _sample_perf

perf_counter_t RM3100::_sample_perf
private

Definition at line 162 of file rm3100.h.

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

◆ _scale

struct mag_calibration_s RM3100::_scale
private

Definition at line 153 of file rm3100.h.

Referenced by collect(), ioctl(), and RM3100().


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