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

#include <bmm150.hpp>

Inheritance diagram for BMM150:
Collaboration diagram for BMM150:

Public Member Functions

 BMM150 (int bus, const char *path, enum Rotation rotation)
 
virtual ~BMM150 ()
 
virtual int init ()
 
virtual ssize_t read (struct file *filp, char *buffer, size_t buflen)
 
virtual int ioctl (struct file *filp, int cmd, unsigned long arg)
 
void stop ()
 Stop automatic measurement. More...
 
void print_info ()
 Diagnostics - print some basic information about the driver. More...
 
void print_registers ()
 

Protected Member Functions

virtual int probe ()
 

Private Member Functions

int init_trim_registers (void)
 
void start ()
 Start automatic measurement. More...
 
int measure ()
 
int collect ()
 
void Run () override
 
int get_data (uint8_t reg, uint8_t *data, unsigned len)
 Read the specified number of bytes from BMM150. More...
 
int reset ()
 Resets the chip. More...
 
int self_test ()
 Measurement self test. More...
 
uint8_t read_reg (uint8_t reg)
 Read a register from the BMM150. More...
 
int write_reg (uint8_t reg, uint8_t value)
 Write a register in the BMM150. More...
 
void modify_reg (unsigned reg, uint8_t clearbits, uint8_t setbits)
 Modify a register in the BMM150. More...
 
int set_power_mode (uint8_t power)
 
int set_data_rate (uint8_t data_rate)
 
int set_rep_xy (uint8_t rep_xy)
 
int set_rep_z (uint8_t rep_z)
 
int set_presetmode (uint8_t presetmode)
 
 BMM150 (const BMM150 &)
 
BMM150 operator= (const BMM150 &)
 

Private Attributes

bool _running
 
unsigned _call_interval
 
mag_report _report {}
 
ringbuffer::RingBuffer * _reports
 
bool _collect_phase
 
struct mag_calibration_s _scale
 
float _range_scale
 
orb_advert_t _topic
 
int _orb_class_instance
 
int _class_instance
 
uint8_t _power
 
uint8_t _output_data_rate
 
bool _calibrated
 the calibration is valid More...
 
int8_t dig_x1
 trim x1 data More...
 
int8_t dig_y1
 trim y1 data More...
 
int8_t dig_x2
 trim x2 data More...
 
int8_t dig_y2
 trim y2 data More...
 
uint16_t dig_z1
 trim z1 data More...
 
int16_t dig_z2
 trim z2 data More...
 
int16_t dig_z3
 trim z3 data More...
 
int16_t dig_z4
 trim z4 data More...
 
uint8_t dig_xy1
 trim xy1 data More...
 
int8_t dig_xy2
 trim xy2 data More...
 
uint16_t dig_xyz1
 trim xyz1 data More...
 
perf_counter_t _sample_perf
 
perf_counter_t _bad_transfers
 
perf_counter_t _good_transfers
 
perf_counter_t _measure_perf
 
perf_counter_t _comms_errors
 
perf_counter_t _duplicates
 
enum Rotation _rotation
 
bool _got_duplicate
 
mag_report _last_report {}
 used for info() More...
 

Detailed Description

Definition at line 194 of file bmm150.hpp.

Constructor & Destructor Documentation

◆ BMM150() [1/2]

◆ ~BMM150()

BMM150::~BMM150 ( )
virtual

Definition at line 298 of file bmm150.cpp.

References _bad_transfers, _class_instance, _comms_errors, _duplicates, _good_transfers, _measure_perf, _reports, _sample_perf, _topic, MAG_BASE_DEVICE_PATH, orb_unadvertise(), perf_free(), and stop().

Here is the call graph for this function:

◆ BMM150() [2/2]

BMM150::BMM150 ( const BMM150 )
private

Member Function Documentation

◆ collect()

int BMM150::collect ( )
private

Definition at line 536 of file bmm150.cpp.

References _bad_transfers, _collect_phase, _comms_errors, _duplicates, _good_transfers, _got_duplicate, _last_report, _range_scale, _reports, _rotation, _sample_perf, _scale, _topic, BMM150_DATA_X_LSB_REG, BMM150_FLIP_OVERFLOW_ADCVAL, BMM150_HALL_OVERFLOW_ADCVAL, BMM150_OVERFLOW_OUTPUT_FLOAT, BMM150_R_LSB, dig_x1, dig_x2, dig_xy1, dig_xy2, dig_xyz1, dig_y1, dig_y2, dig_z1, dig_z2, dig_z3, dig_z4, get_data(), hrt_absolute_time(), mag_report, OK, ORB_ID, orb_publish(), perf_begin(), perf_count(), perf_end(), perf_event_count(), read_reg(), rotate_3f(), status, 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 init(), read(), Run(), and self_test().

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

◆ get_data()

int BMM150::get_data ( uint8_t  reg,
uint8_t *  data,
unsigned  len 
)
private

Read the specified number of bytes from BMM150.

Parameters
regThe register to read.
dataPointer to buffer for bytes read.
lenNumber of bytes to read
Returns
OK if the transfer was successful, -errno otherwise.

Definition at line 823 of file bmm150.cpp.

Referenced by collect(), and init_trim_registers().

Here is the caller graph for this function:

◆ init()

int BMM150::init ( )
virtual

Definition at line 327 of file bmm150.cpp.

References _class_instance, _orb_class_instance, _reports, _topic, BMM150_CHIP_ID, BMM150_CHIP_ID_REG, BMM150_POWER_CTRL_REG, collect(), DEVICE_DEBUG, ToneAlarmInterface::init(), init_trim_registers(), MAG_BASE_DEVICE_PATH, mag_report, measure(), modify_reg(), OK, orb_advertise_multi(), ORB_ID, ORB_PRIO_HIGH, ORB_PRIO_MAX, read_reg(), and reset().

Here is the call graph for this function:

◆ init_trim_registers()

int BMM150::init_trim_registers ( void  )
private

Definition at line 923 of file bmm150.cpp.

References BMM150_DIG_X1, BMM150_DIG_X2, BMM150_DIG_XY1, BMM150_DIG_XY2, BMM150_DIG_XYZ1_LSB, BMM150_DIG_Y1, BMM150_DIG_Y2, BMM150_DIG_Z1_LSB, BMM150_DIG_Z2_LSB, BMM150_DIG_Z3_LSB, BMM150_DIG_Z4_LSB, data, dig_x1, dig_x2, dig_xy1, dig_xy2, dig_xyz1, dig_y1, dig_y2, dig_z1, dig_z2, dig_z3, dig_z4, get_data(), OK, and read_reg().

Referenced by init().

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

◆ ioctl()

int BMM150::ioctl ( struct file filp,
int  cmd,
unsigned long  arg 
)
virtual

Definition at line 707 of file bmm150.cpp.

References _call_interval, BMM150_CONVERSION_INTERVAL, BMM150_MAX_DATA_RATE, MAGIOCCALIBRATE, MAGIOCEXSTRAP, MAGIOCGSCALE, MAGIOCSSCALE, OK, reset(), SENSOR_POLLRATE_DEFAULT, SENSORIOCRESET, SENSORIOCSPOLLRATE, and start().

Here is the call graph for this function:

◆ measure()

int BMM150::measure ( )
private

Definition at line 513 of file bmm150.cpp.

References _collect_phase, _comms_errors, _measure_perf, BMM150_FORCED_MODE, OK, perf_begin(), perf_cancel(), perf_count(), perf_end(), and set_power_mode().

Referenced by init(), read(), and Run().

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

◆ modify_reg()

void BMM150::modify_reg ( unsigned  reg,
uint8_t  clearbits,
uint8_t  setbits 
)
private

Modify a register in the BMM150.

Bits are cleared before bits are set.

Parameters
regThe register to modify.
clearbitsBits in the register to clear.
setbitsBits in the register to set.

Definition at line 832 of file bmm150.cpp.

References read_reg(), and write_reg().

Referenced by init(), reset(), set_data_rate(), and set_power_mode().

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

◆ operator=()

BMM150 BMM150::operator= ( const BMM150 )
private

◆ print_info()

void BMM150::print_info ( )

Diagnostics - print some basic information about the driver.

Definition at line 1026 of file bmm150.cpp.

References _bad_transfers, _good_transfers, _last_report, _range_scale, _reports, _sample_perf, _scale, perf_print_counter(), 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.

Here is the call graph for this function:

◆ print_registers()

void BMM150::print_registers ( )

Definition at line 1043 of file bmm150.cpp.

References BMM150_AXES_EN_CTRL_REG, BMM150_CHIP_ID_REG, BMM150_INT_SETT_CTRL_REG, and read_reg().

Here is the call graph for this function:

◆ probe()

int BMM150::probe ( )
protectedvirtual

Definition at line 393 of file bmm150.cpp.

References OK.

◆ read()

ssize_t BMM150::read ( struct file filp,
char *  buffer,
size_t  buflen 
)
virtual

Definition at line 426 of file bmm150.cpp.

References _call_interval, _reports, BMM150_CONVERSION_INTERVAL, collect(), mag_report, measure(), and OK.

Here is the call graph for this function:

◆ read_reg()

uint8_t BMM150::read_reg ( uint8_t  reg)
private

Read a register from the BMM150.

Parameters
regThe register to read.
Returns
The value that was read.

Definition at line 804 of file bmm150.cpp.

Referenced by collect(), init(), init_trim_registers(), modify_reg(), and print_registers().

Here is the caller graph for this function:

◆ reset()

int BMM150::reset ( )
private

Resets the chip.

Definition at line 770 of file bmm150.cpp.

References BMM150_DEFAULT_ODR, BMM150_DEFAULT_POWER_MODE, BMM150_POWER_CTRL_REG, BMM150_PRESETMODE_REGULAR, BMM150_SOFT_RESET_MASK, BMM150_SOFT_RESET_VALUE, modify_reg(), OK, set_data_rate(), set_power_mode(), and set_presetmode().

Referenced by init(), and ioctl().

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

◆ Run()

void BMM150::Run ( )
overrideprivate

Definition at line 487 of file bmm150.cpp.

References _call_interval, _collect_phase, _running, BMM150_CONVERSION_INTERVAL, collect(), and measure().

Here is the call graph for this function:

◆ self_test()

int BMM150::self_test ( )
private

Measurement self test.

Returns
0 on success, 1 on failure

Definition at line 793 of file bmm150.cpp.

References _sample_perf, collect(), and perf_event_count().

Here is the call graph for this function:

◆ set_data_rate()

int BMM150::set_data_rate ( uint8_t  data_rate)
private

Definition at line 873 of file bmm150.cpp.

References _output_data_rate, BMM150_CTRL_REG, BMM150_DATA_RATE_02HZ, BMM150_DATA_RATE_06HZ, BMM150_DATA_RATE_08HZ, BMM150_DATA_RATE_10HZ, BMM150_DATA_RATE_15HZ, BMM150_DATA_RATE_20HZ, BMM150_DATA_RATE_25HZ, BMM150_DATA_RATE_30HZ, BMM150_OUTPUT_DATA_RATE_MASK, modify_reg(), and OK.

Referenced by reset(), and set_presetmode().

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

◆ set_power_mode()

int BMM150::set_power_mode ( uint8_t  power)
private

Definition at line 844 of file bmm150.cpp.

References _power, BMM150_CTRL_REG, BMM150_FORCED_MODE, BMM150_NORMAL_MODE, BMM150_POWER_MASK, BMM150_SLEEP_MODE, modify_reg(), and OK.

Referenced by measure(), and reset().

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

◆ set_presetmode()

int BMM150::set_presetmode ( uint8_t  presetmode)
private

Definition at line 987 of file bmm150.cpp.

References BMM150_ENHANCED_DR, BMM150_ENHANCED_REPXY, BMM150_ENHANCED_REPZ, BMM150_HIGHACCURACY_DR, BMM150_HIGHACCURACY_REPXY, BMM150_HIGHACCURACY_REPZ, BMM150_LOWPOWER_DR, BMM150_LOWPOWER_REPXY, BMM150_LOWPOWER_REPZ, BMM150_REGULAR_DR, BMM150_REGULAR_REPXY, BMM150_REGULAR_REPZ, OK, set_data_rate(), set_rep_xy(), and set_rep_z().

Referenced by reset().

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

◆ set_rep_xy()

int BMM150::set_rep_xy ( uint8_t  rep_xy)
private

Definition at line 970 of file bmm150.cpp.

References BMM150_XY_REP_CTRL_REG.

Referenced by set_presetmode().

Here is the caller graph for this function:

◆ set_rep_z()

int BMM150::set_rep_z ( uint8_t  rep_z)
private

Definition at line 978 of file bmm150.cpp.

References BMM150_Z_REP_CTRL_REG.

Referenced by set_presetmode().

Here is the caller graph for this function:

◆ start()

void BMM150::start ( )
private

Start automatic measurement.

Definition at line 407 of file bmm150.cpp.

References _collect_phase, _reports, and _running.

Referenced by ioctl().

Here is the caller graph for this function:

◆ stop()

void BMM150::stop ( )

Stop automatic measurement.

Definition at line 419 of file bmm150.cpp.

References _running.

Referenced by ~BMM150().

Here is the caller graph for this function:

◆ write_reg()

int BMM150::write_reg ( uint8_t  reg,
uint8_t  value 
)
private

Write a register in the BMM150.

Parameters
regThe register to write.
valueThe new value to write.
Returns
OK if the transfer was successful, -errno otherwise.

Definition at line 815 of file bmm150.cpp.

Referenced by modify_reg().

Here is the caller graph for this function:

Member Data Documentation

◆ _bad_transfers

perf_counter_t BMM150::_bad_transfers
private

Definition at line 259 of file bmm150.hpp.

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

◆ _calibrated

bool BMM150::_calibrated
private

the calibration is valid

Definition at line 240 of file bmm150.hpp.

Referenced by BMM150().

◆ _call_interval

unsigned BMM150::_call_interval
private

Definition at line 224 of file bmm150.hpp.

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

◆ _class_instance

int BMM150::_class_instance
private

Definition at line 237 of file bmm150.hpp.

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

◆ _collect_phase

bool BMM150::_collect_phase
private

Definition at line 230 of file bmm150.hpp.

Referenced by collect(), measure(), Run(), and start().

◆ _comms_errors

perf_counter_t BMM150::_comms_errors
private

Definition at line 262 of file bmm150.hpp.

Referenced by BMM150(), collect(), measure(), and ~BMM150().

◆ _duplicates

perf_counter_t BMM150::_duplicates
private

Definition at line 263 of file bmm150.hpp.

Referenced by BMM150(), collect(), and ~BMM150().

◆ _good_transfers

perf_counter_t BMM150::_good_transfers
private

Definition at line 260 of file bmm150.hpp.

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

◆ _got_duplicate

bool BMM150::_got_duplicate
private

Definition at line 266 of file bmm150.hpp.

Referenced by BMM150(), and collect().

◆ _last_report

mag_report BMM150::_last_report {}
private

used for info()

Definition at line 268 of file bmm150.hpp.

Referenced by collect(), and print_info().

◆ _measure_perf

perf_counter_t BMM150::_measure_perf
private

Definition at line 261 of file bmm150.hpp.

Referenced by BMM150(), measure(), and ~BMM150().

◆ _orb_class_instance

int BMM150::_orb_class_instance
private

Definition at line 236 of file bmm150.hpp.

Referenced by BMM150(), and init().

◆ _output_data_rate

uint8_t BMM150::_output_data_rate
private

Definition at line 239 of file bmm150.hpp.

Referenced by BMM150(), and set_data_rate().

◆ _power

uint8_t BMM150::_power
private

Definition at line 238 of file bmm150.hpp.

Referenced by BMM150(), and set_power_mode().

◆ _range_scale

float BMM150::_range_scale
private

Definition at line 233 of file bmm150.hpp.

Referenced by BMM150(), collect(), and print_info().

◆ _report

mag_report BMM150::_report {}
private

Definition at line 227 of file bmm150.hpp.

◆ _reports

ringbuffer::RingBuffer* BMM150::_reports
private

Definition at line 228 of file bmm150.hpp.

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

◆ _rotation

enum Rotation BMM150::_rotation
private

Definition at line 265 of file bmm150.hpp.

Referenced by BMM150(), and collect().

◆ _running

bool BMM150::_running
private

Definition at line 221 of file bmm150.hpp.

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

◆ _sample_perf

perf_counter_t BMM150::_sample_perf
private

Definition at line 258 of file bmm150.hpp.

Referenced by BMM150(), collect(), print_info(), self_test(), and ~BMM150().

◆ _scale

struct mag_calibration_s BMM150::_scale
private

Definition at line 232 of file bmm150.hpp.

Referenced by BMM150(), collect(), and print_info().

◆ _topic

orb_advert_t BMM150::_topic
private

Definition at line 235 of file bmm150.hpp.

Referenced by BMM150(), collect(), init(), and ~BMM150().

◆ dig_x1

int8_t BMM150::dig_x1
private

trim x1 data

Definition at line 242 of file bmm150.hpp.

Referenced by BMM150(), collect(), and init_trim_registers().

◆ dig_x2

int8_t BMM150::dig_x2
private

trim x2 data

Definition at line 245 of file bmm150.hpp.

Referenced by BMM150(), collect(), and init_trim_registers().

◆ dig_xy1

uint8_t BMM150::dig_xy1
private

trim xy1 data

Definition at line 253 of file bmm150.hpp.

Referenced by BMM150(), collect(), and init_trim_registers().

◆ dig_xy2

int8_t BMM150::dig_xy2
private

trim xy2 data

Definition at line 254 of file bmm150.hpp.

Referenced by BMM150(), collect(), and init_trim_registers().

◆ dig_xyz1

uint16_t BMM150::dig_xyz1
private

trim xyz1 data

Definition at line 256 of file bmm150.hpp.

Referenced by BMM150(), collect(), and init_trim_registers().

◆ dig_y1

int8_t BMM150::dig_y1
private

trim y1 data

Definition at line 243 of file bmm150.hpp.

Referenced by BMM150(), collect(), and init_trim_registers().

◆ dig_y2

int8_t BMM150::dig_y2
private

trim y2 data

Definition at line 246 of file bmm150.hpp.

Referenced by BMM150(), collect(), and init_trim_registers().

◆ dig_z1

uint16_t BMM150::dig_z1
private

trim z1 data

Definition at line 248 of file bmm150.hpp.

Referenced by BMM150(), collect(), and init_trim_registers().

◆ dig_z2

int16_t BMM150::dig_z2
private

trim z2 data

Definition at line 249 of file bmm150.hpp.

Referenced by BMM150(), collect(), and init_trim_registers().

◆ dig_z3

int16_t BMM150::dig_z3
private

trim z3 data

Definition at line 250 of file bmm150.hpp.

Referenced by BMM150(), collect(), and init_trim_registers().

◆ dig_z4

int16_t BMM150::dig_z4
private

trim z4 data

Definition at line 251 of file bmm150.hpp.

Referenced by BMM150(), collect(), and init_trim_registers().


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