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

Helper class implementing the magnetometer driver node. More...

#include <ICM20948_mag.h>

Collaboration diagram for ICM20948_mag:

Public Member Functions

 ICM20948_mag (ICM20948 *parent, device::Device *interface, enum Rotation rotation)
 
 ~ICM20948_mag ()
 
void set_passthrough (uint8_t reg, uint8_t size, uint8_t *out=NULL)
 
void passthrough_read (uint8_t reg, uint8_t *buf, uint8_t size)
 
void passthrough_write (uint8_t reg, uint8_t val)
 
void read_block (uint8_t reg, uint8_t *val, uint8_t count)
 
int ak09916_reset ()
 
int ak09916_setup ()
 
int ak09916_setup_master_i2c ()
 
bool ak09916_check_id (uint8_t &id)
 
bool ak09916_read_adjustments ()
 
void print_status ()
 

Protected Member Functions

void measure ()
 
void _measure (hrt_abstime timestamp_sample, ak09916_regs data)
 
uint8_t read_reg (unsigned reg)
 
void write_reg (unsigned reg, uint8_t value)
 
bool is_passthrough ()
 

Protected Attributes

device::Device_interface
 

Private Attributes

PX4Magnetometer _px4_mag
 
ICM20948_parent
 
bool _mag_reading_data {false}
 
perf_counter_t _mag_overruns
 
perf_counter_t _mag_overflows
 
perf_counter_t _mag_errors
 

Friends

class ICM20948
 

Detailed Description

Helper class implementing the magnetometer driver node.

Definition at line 111 of file ICM20948_mag.h.

Constructor & Destructor Documentation

◆ ICM20948_mag()

ICM20948_mag::ICM20948_mag ( ICM20948 parent,
device::Device interface,
enum Rotation  rotation 
)

Definition at line 54 of file ICM20948_mag.cpp.

References _px4_mag, DRV_MAG_DEVTYPE_AK09916, ICM20948_MAG_RANGE_GA, PX4Magnetometer::set_device_type(), and PX4Magnetometer::set_scale().

Here is the call graph for this function:

◆ ~ICM20948_mag()

ICM20948_mag::~ICM20948_mag ( )

Definition at line 67 of file ICM20948_mag.cpp.

References _mag_errors, _mag_overflows, _mag_overruns, and perf_free().

Here is the call graph for this function:

Member Function Documentation

◆ _measure()

void ICM20948_mag::_measure ( hrt_abstime  timestamp_sample,
ak09916_regs  data 
)
protected

Definition at line 118 of file ICM20948_mag.cpp.

References ICM20948::_last_temperature, _parent, _px4_mag, AK09916_ST1_DRDY, ICM20948::is_external(), PX4Magnetometer::set_external(), PX4Magnetometer::set_temperature(), ak09916_regs::st1, PX4Magnetometer::update(), ak09916_regs::x, ak09916_regs::y, and ak09916_regs::z.

Referenced by measure(), and ICM20948::measure().

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

◆ ak09916_check_id()

bool ICM20948_mag::ak09916_check_id ( uint8_t &  id)

Definition at line 195 of file ICM20948_mag.cpp.

References AK09916_DEVICE_ID, AK09916REG_WIA, and read_reg().

Referenced by ak09916_setup().

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

◆ ak09916_read_adjustments()

bool ICM20948_mag::ak09916_read_adjustments ( )

Definition at line 243 of file ICM20948_mag.cpp.

References _interface, _px4_mag, AK09916_16BIT_ADC, AK09916_FUZE_MODE, AK09916_POWERDOWN_MODE, AK09916REG_ASAX, AK09916REG_CNTL1, f(), passthrough_read(), device::Device::read(), PX4Magnetometer::set_sensitivity(), and write_reg().

Here is the call graph for this function:

◆ ak09916_reset()

int ICM20948_mag::ak09916_reset ( )

Definition at line 226 of file ICM20948_mag.cpp.

References AK09916_RESET, ak09916_setup(), AK09916REG_CNTL3, OK, and write_reg().

Referenced by ICM20948::init(), and ICM20948::reset().

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

◆ ak09916_setup()

int ICM20948_mag::ak09916_setup ( void  )

Definition at line 295 of file ICM20948_mag.cpp.

References _interface, _parent, ak09916_check_id(), AK09916_CNTL2_CONTINOUS_MODE_100HZ, AK09916_RESET, ak09916_setup_master_i2c(), AK09916REG_CNTL2, AK09916REG_CNTL3, AK09916REG_ST1, BIT_I2C_MST_EN, BIT_I2C_MST_RST, ICMREG_20948_I2C_MST_CTRL, ICMREG_20948_USER_CTRL, ICM20948::modify_checked_reg(), ICM20948::modify_reg(), OK, set_passthrough(), write_reg(), and ICM20948::write_reg().

Referenced by ak09916_reset().

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

◆ ak09916_setup_master_i2c()

int ICM20948_mag::ak09916_setup_master_i2c ( )

Definition at line 275 of file ICM20948_mag.cpp.

References _interface, _parent, BIT_I2C_MST_EN, BIT_I2C_MST_P_NSR, ICM_BITS_I2C_MST_CLOCK_400HZ, ICMREG_20948_I2C_MST_CTRL, ICMREG_20948_USER_CTRL, ICM20948::modify_checked_reg(), OK, and ICM20948::write_reg().

Referenced by ak09916_setup().

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

◆ is_passthrough()

bool ICM20948_mag::is_passthrough ( )
inlineprotected

Definition at line 141 of file ICM20948_mag.h.

Referenced by ICM20948::init(), ICM20948::measure(), and ICM20948::reset_mpu().

Here is the caller graph for this function:

◆ measure()

void ICM20948_mag::measure ( )
protected

Definition at line 75 of file ICM20948_mag.cpp.

References _interface, _mag_errors, _mag_overflows, _mag_overruns, _measure(), _px4_mag, AK09916_ST1_DRDY, AK09916REG_ST1, data, hrt_absolute_time(), hrt_abstime, OK, perf_count(), perf_event_count(), device::Device::read(), and PX4Magnetometer::set_error_count().

Referenced by ICM20948::measure().

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

◆ passthrough_read()

void ICM20948_mag::passthrough_read ( uint8_t  reg,
uint8_t *  buf,
uint8_t  size 
)

Definition at line 171 of file ICM20948_mag.cpp.

References _parent, ICMREG_20948_EXT_SLV_SENS_DATA_00, ICMREG_20948_I2C_SLV0_CTRL, read_block(), set_passthrough(), and ICM20948::write_reg().

Referenced by ak09916_read_adjustments(), and read_reg().

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

◆ passthrough_write()

void ICM20948_mag::passthrough_write ( uint8_t  reg,
uint8_t  val 
)

Definition at line 206 of file ICM20948_mag.cpp.

References _parent, ICMREG_20948_I2C_SLV0_CTRL, set_passthrough(), and ICM20948::write_reg().

Referenced by write_reg().

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

◆ print_status()

void ICM20948_mag::print_status ( )
inline

Definition at line 128 of file ICM20948_mag.h.

Referenced by ICM20948::print_info().

Here is the caller graph for this function:

◆ read_block()

void ICM20948_mag::read_block ( uint8_t  reg,
uint8_t *  val,
uint8_t  count 
)

Definition at line 165 of file ICM20948_mag.cpp.

References ICM20948::_interface, _parent, and device::Device::read().

Referenced by passthrough_read().

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

◆ read_reg()

uint8_t ICM20948_mag::read_reg ( unsigned  reg)
protected

Definition at line 180 of file ICM20948_mag.cpp.

References _interface, passthrough_read(), and device::Device::read().

Referenced by ak09916_check_id().

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

◆ set_passthrough()

void ICM20948_mag::set_passthrough ( uint8_t  reg,
uint8_t  size,
uint8_t *  out = NULL 
)

Definition at line 145 of file ICM20948_mag.cpp.

References _parent, AK09916_I2C_ADDR, BIT_I2C_READ_FLAG, BIT_I2C_SLV0_EN, ICMREG_20948_I2C_SLV0_ADDR, ICMREG_20948_I2C_SLV0_CTRL, ICMREG_20948_I2C_SLV0_DO, ICMREG_20948_I2C_SLV0_REG, and ICM20948::write_reg().

Referenced by ak09916_setup(), passthrough_read(), and passthrough_write().

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

◆ write_reg()

void ICM20948_mag::write_reg ( unsigned  reg,
uint8_t  value 
)
protected

Definition at line 214 of file ICM20948_mag.cpp.

References _interface, ICM20948_LOW_SPEED_OP, passthrough_write(), and device::Device::write().

Referenced by ak09916_read_adjustments(), ak09916_reset(), and ak09916_setup().

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

Friends And Related Function Documentation

◆ ICM20948

friend class ICM20948
friend

Definition at line 133 of file ICM20948_mag.h.

Member Data Documentation

◆ _interface

device::Device* ICM20948_mag::_interface
protected

◆ _mag_errors

perf_counter_t ICM20948_mag::_mag_errors
private

Definition at line 152 of file ICM20948_mag.h.

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

◆ _mag_overflows

perf_counter_t ICM20948_mag::_mag_overflows
private

Definition at line 151 of file ICM20948_mag.h.

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

◆ _mag_overruns

perf_counter_t ICM20948_mag::_mag_overruns
private

Definition at line 150 of file ICM20948_mag.h.

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

◆ _mag_reading_data

bool ICM20948_mag::_mag_reading_data {false}
private

Definition at line 148 of file ICM20948_mag.h.

◆ _parent

ICM20948* ICM20948_mag::_parent
private

◆ _px4_mag

PX4Magnetometer ICM20948_mag::_px4_mag
private

Definition at line 144 of file ICM20948_mag.h.

Referenced by _measure(), ak09916_read_adjustments(), ICM20948_mag(), and measure().


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