Open Model Railroad Network (OpenMRN)
Loading...
Searching...
No Matches
TMAG5273 Class Reference

Implementation of TMAG5273 sensor driver. More...

#include <TMAG5273.hxx>

Inheritance diagram for TMAG5273:
Atomic

Public Types

enum  I2CAddress : uint8_t { ADDR_A = 0x35 , ADDR_B = 0x22 , ADDR_C = 0x78 , ADDR_D = 0x44 }
 Supported I2C addresses. More...
 
enum class  DeviceID : uint8_t { UNKNOWN = 0x00 , MT_40_AND_80 = 0x01 , MT_133_AND_266 = 0x02 , ERROR = 0xFF }
 Device Identifier. More...
 
enum class  ChannelEnable : uint8_t {
  ALL_OFF = 0x00 , X_ENABLE = 0x10 , Y_ENABLE = 0x20 , XY_ENABLE = 0x30 ,
  Z_ENABLE = 0x40 , XZ_ENABLE = 0x50 , YZ_ENABLE = 0x60 , XYZ_ENABLE = 0x70 ,
  XYX_ENABLE = 0x80 , YXY_ENABLE = 0x90 , YZY_ENABLE = 0xA0 , XZX_ENABLE = 0xB0
}
 Channels to enabled. More...
 
enum class  SleepTime : uint8_t {
  SLEEP_1_MSEC = 0x00 , SLEEP_5_MSEC = 0x01 , SLEEP_10_MSEC = 0x02 , SLEEP_15_MSEC = 0x03 ,
  SLEEP_20_MSEC = 0x04 , SLEEP_30_MSEC = 0x05 , SLEEP_50_MSEC = 0x06 , SLEEP_100_MSEC = 0x07 ,
  SLEEP_500_MSEC = 0x08 , SLEEP_1000_MSEC = 0x09 , SLEEP_2000_MSEC = 0x0A , SLEEP_5000_MSEC = 0x0B ,
  SLEEP_20000_MSEC = 0x0C
}
 Sleep time between conversions when operating mode is wake-up and sleep. More...
 
enum class  DeviceStatus : uint8_t {
  INT_N_PIN_RESET_LEVEL_MASK = 0x10 , OSC_ERROR_MASK = 0x08 , INT_N_PIN_ERROR_MASK = 0x04 , OTP_CRC_ERROR_MASK = 0x02 ,
  VCC_UV_ERROR_MASK = 0x01
}
 Device status bit masks. More...
 
enum class  InterruptConfig : uint8_t {
  CONVERSION_COMPLETE_ENABLE = 0x80 , THRESHOLD_ENABLE = 0x40 , STATE_MASK = 0x20 , MODE_NONE = (0 << 2) ,
  MODE_INT_N = (1 << 2) , MODE_INT_N_EXCEPT_I2C_BUSY = (2 << 2) , MODE_SCL = (3 << 2) , MODE_SCL_EXCEPT_I2C_BUSY = (4 << 2) ,
  MASK_INT_N_MASK = 0x01
}
 Interrupt configuration. More...
 
enum class  ConversionStatus : uint8_t {
  SET_COUNT_MASK = 0xE0 , SET_COUNT_SHIFT = 5 , POR_MASK = 0x10 , DIAG_STATUS_MASK = 0x02 ,
  RESULT_STATUS_MASK = 0x01
}
 conversion status. More...
 
enum class  ConversionAverage : uint8_t {
  AVG_1 = (0 << 2) , AVG_2 = (1 << 2) , AVG_4 = (2 << 2) , AVG_8 = (3 << 2) ,
  AVG_16 = (4 << 2) , AVG_32 = (5 << 2)
}
 Conversion oversampling average configuration. More...
 
enum class  AngleEnable : uint8_t { OFF = (0 << 2) , XY_ENABLE = (1 << 2) , YZ_ENABLE = (2 << 2) , XZ_ENABLE = (3 << 2) }
 Angle calculation to enable. More...
 
enum class  OperatingMode : uint8_t { STANDBY = 0x00 , SLEEP = 0x01 , CONTINUOUS = 0x02 , WAKE_UP_AND_SLEEP = 0x03 }
 Operating modes of the device. More...
 

Public Member Functions

 TMAG5273 (uint8_t address=ADDR_A)
 Constructor.
 
 TMAG5273 (const char *i2c_path, uint8_t address=ADDR_A)
 Constructor.
 
 ~TMAG5273 ()
 Destructor.
 
void init (const char *i2c_path)
 
void init (int i2c_fd)
 Initializes the device.
 
DeviceID is_present ()
 Checks whether the magnetic sensor is present.
 
DeviceStatus get_device_status ()
 Get the device status.
 
void clr_device_status (DeviceStatus status)
 Get the device status.
 
void enable_channels (ChannelEnable enable)
 Enable/disable channels.
 
void set_sleep_time (SleepTime t)
 Set the sleep time between channels in wake and sleep mode.
 
void set_interrupt_config (InterruptConfig config)
 Set the interrupt config.
 
void set_operating_mode (OperatingMode mode)
 Set the operating mode.
 
uint8_t get_conversion_status ()
 Get the conversion status.
 
void clr_por_conversion_status ()
 Clear the power on reset bit of the conversion status.
 
void set_oversampling (ConversionAverage avg)
 Sets the oversampling+averaging mode.
 
void set_angle_en (AngleEnable angle)
 Sets whether angle measurement should be enabled.
 
void set_angle_gain (uint8_t gain, bool second)
 Sets angle gain parameters.
 
void set_offset_1 (int8_t offset)
 Sets offset correction for the first axis.
 
void set_offset_2 (int8_t offset)
 Sets offset correction for the second axis.
 
DeviceID get_device_id ()
 
void read_conversion_results (int16_t xyz[3])
 Read the conversion results.
 
int16_t read_angle_result ()
 Read the angle result.
 

Private Types

enum  BitMasks {
  DCONF1_AVG_MASK = 0b11100 , DCONF2_OPERATING_MODE_MASK = 0b11 , SCONF1_MAG_CH_MASK = 0b11110000 , SCONF1_SLEEP_TIME_MASK = 0b00001111 ,
  SCONF2_MAG_GAIN_CH_MASK = 1 << 4 , SCONF2_MAG_GAIN_CH_ADJ1 = 0 , SCONF2_MAG_GAIN_CH_ADJ2 = SCONF2_MAG_GAIN_CH_MASK , SCONF2_ANGLE_EN_MASK = 0b1100 ,
  DEVICE_ID_RESERVED_MASK = 0b11111100 , DEVICE_ID_VERSION_MASK = 0b00000011
}
 Useful bit masks. More...
 
enum  Registers {
  DEVICE_CONFIG_1 = 0x0 , DEVICE_CONFIG_2 = 0x1 , SENSOR_CONFIG_1 = 0x2 , SENSOR_CONFIG_2 = 0x3 ,
  X_THR_CONFIG = 0x4 , Y_THR_CONFIG = 0x5 , Z_THR_CONFIG = 0x6 , T_CONFIG = 0x7 ,
  INT_CONFIG_1 = 0x8 , MAG_GAIN_CONFIG = 0x9 , MAG_OFFSET_CONFIG_1 = 0xA , MAG_OFFSET_CONFIG_2 = 0xB ,
  I2C_ADDRESS = 0xC , DEVICE_ID = 0xD , MANUFACTURER_ID_LSB = 0xE , MANUFACTURER_ID_MSB = 0xF ,
  T_MSB_RESULT = 0x10 , T_LSB_RESULT = 0x11 , X_MSB_RESULT = 0x12 , X_LSB_RESULT = 0x13 ,
  Y_MSB_RESULT = 0x14 , Y_LSB_RESULT = 0x15 , Z_MSB_RESULT = 0x16 , Z_LSB_RESULT = 0x17 ,
  CONV_STATUS = 0x18 , ANGLE_RESULT_MSB = 0x19 , ANGLE_RESULT_LSB = 0x1A , MAGNITUDE_RESULT = 0x1B ,
  DEVICE_STATUS = 0x1C
}
 Device register address offsets. More...
 

Private Member Functions

int register_read (uint8_t reg, uint8_t *data, uint16_t len)
 Reads one or more (sequential) registers.
 
void register_write (uint8_t reg, const uint8_t *data, uint16_t len)
 Writes one or more (sequential) register.
 
void register_write (uint8_t reg, uint8_t value)
 Writes one register.
 
uint8_t register_read (uint8_t reg)
 Reads a single register.
 
void register_modify (uint8_t reg, uint8_t mask, uint8_t value)
 Modifies a register value in place.
 
- Private Member Functions inherited from Atomic
void lock ()
 
void unlock ()
 

Private Attributes

int fd_ = -1
 I2C device.
 
const uint8_t i2cAddress_
 7-bit address, right aligned.
 

Friends

class MagSensorTest
 
class Input
 

Detailed Description

Implementation of TMAG5273 sensor driver.

Definition at line 49 of file TMAG5273.hxx.

Member Enumeration Documentation

◆ AngleEnable

enum class TMAG5273::AngleEnable : uint8_t
strong

Angle calculation to enable.

Enumerator
OFF 

angle not enabled

XY_ENABLE 

X + Y derived angle.

YZ_ENABLE 

Y + Z derived angle.

XZ_ENABLE 

X + Z derived angle.

Definition at line 170 of file TMAG5273.hxx.

◆ BitMasks

enum TMAG5273::BitMasks
private

Useful bit masks.

Enumerator
DCONF1_AVG_MASK 

Mask for averaging field in DEVICE_CONFIG_1 register.

DCONF2_OPERATING_MODE_MASK 

Mask for the operating mode in DEVICE_CONFIG_2 register.

SCONF1_MAG_CH_MASK 

Channel enable mask.

SCONF1_SLEEP_TIME_MASK 

sleep time mask.

SCONF2_MAG_GAIN_CH_MASK 

Mask for MAG_GAIN_CH bits in the SENSOR_CONFIG_2 register.

SCONF2_ANGLE_EN_MASK 

Mask for ANGLE_EN bits in the SENSOR_CONFIG_2 register.

DEVICE_ID_RESERVED_MASK 

reserved bits.

DEVICE_ID_VERSION_MASK 

version bits.

Definition at line 398 of file TMAG5273.hxx.

◆ ChannelEnable

enum class TMAG5273::ChannelEnable : uint8_t
strong

Channels to enabled.

Enumerator
ALL_OFF 

all channels off, default

X_ENABLE 

X channel enabled.

Y_ENABLE 

Y channel enabled.

XY_ENABLE 

X and Y channels enabled.

Z_ENABLE 

Z channel enabled.

XZ_ENABLE 

X and Z channels enabled.

YZ_ENABLE 

Y and Z channels enabled.

XYZ_ENABLE 

X, Y, and Z channels enabled.

XYX_ENABLE 

pseudo-simultaneous X plus Y channels enabled

YXY_ENABLE 

pseudo-simultaneous Y plus X channels enabled

YZY_ENABLE 

pseudo-simultaneous Y plus Z channels enabled

XZX_ENABLE 

pseudo-simultaneous X plus Z channels enabled

Definition at line 71 of file TMAG5273.hxx.

◆ ConversionAverage

enum class TMAG5273::ConversionAverage : uint8_t
strong

Conversion oversampling average configuration.

Enumerator
AVG_1 

average 1 saple

AVG_2 

average 2 saples

AVG_4 

average 4 saples

AVG_8 

average 8 saples

AVG_16 

average 16 saples

AVG_32 

average 32 saples

Definition at line 159 of file TMAG5273.hxx.

◆ ConversionStatus

enum class TMAG5273::ConversionStatus : uint8_t
strong

conversion status.

Enumerator
SET_COUNT_MASK 

rolling count of conversion data sets mask

SET_COUNT_SHIFT 

rolling count of conversion data sets shift

POR_MASK 

Device powered up, 0 = no power on reset, 1 = power on reset.

DIAG_STATUS_MASK 

Diagnositic status, 0 = no diag fail, 1 diag fail detected.

RESULT_STATUS_MASK 

Conversion, 0 = conversion not complete, 1 = conversion complete.

Definition at line 144 of file TMAG5273.hxx.

◆ DeviceID

enum class TMAG5273::DeviceID : uint8_t
strong

Device Identifier.

Enumerator
UNKNOWN 

ID unknown or device not detected.

MT_40_AND_80 

40-mT and 80-mT range supported

MT_133_AND_266 

133-mT and 266-mT range supported

ERROR 

some kind of error occured

Definition at line 62 of file TMAG5273.hxx.

◆ DeviceStatus

enum class TMAG5273::DeviceStatus : uint8_t
strong

Device status bit masks.

Enumerator
INT_N_PIN_RESET_LEVEL_MASK 

value of the INT_N pin read at reset, 0 = low, 1 = high

OSC_ERROR_MASK 

Oscillator error, 0 = no error, 1 = error, write 1 to clear.

INT_N_PIN_ERROR_MASK 

INT_N pin error, 0 = no error, 1 = error, write 1 to clear.

OTP_CRC_ERROR_MASK 

OTP CRC error, 0 = no error, 1 = error, write 1 to clear.

VCC_UV_ERROR_MASK 

VCC < 2.3V, 0 = no VCC UV, 1 = VCC UV, write 1 to clear.

Definition at line 106 of file TMAG5273.hxx.

◆ I2CAddress

enum TMAG5273::I2CAddress : uint8_t

Supported I2C addresses.

Enumerator
ADDR_A 

A1 and A2 device address.

ADDR_B 

B1 and B2 device address.

ADDR_C 

C1 and C2 device address.

ADDR_D 

D1 and D2 device address.

Definition at line 53 of file TMAG5273.hxx.

◆ InterruptConfig

enum class TMAG5273::InterruptConfig : uint8_t
strong

Interrupt configuration.

Enumerator
CONVERSION_COMPLETE_ENABLE 

interrupt on conversion complete, 0 = disable, 1 = enable

THRESHOLD_ENABLE 

interrupt on threshold, 0 = disabled, 1 = enabled

STATE_MASK 

interrupt state, 0 = lached until clear, 1 = pulse for 10 usec

MODE_NONE 

no interrupt

MODE_INT_N 

interrupt mode through INT_N

MODE_INT_N_EXCEPT_I2C_BUSY 

interrupt mode through INT_N, except when I2C is busy

MODE_SCL 

interrupt mode through SCL

MODE_SCL_EXCEPT_I2C_BUSY 

interrupt mode through SCL, except when I2C is busy

MASK_INT_N_MASK 

mask interrupt pin when INT_N is connected to ground

Definition at line 121 of file TMAG5273.hxx.

◆ OperatingMode

enum class TMAG5273::OperatingMode : uint8_t
strong

Operating modes of the device.

Enumerator
STANDBY 

starts new conversion at trigger event

SLEEP 

sleep

CONTINUOUS 

continuous measurement mode

WAKE_UP_AND_SLEEP 

wake-up and sleep mode

Definition at line 179 of file TMAG5273.hxx.

◆ Registers

enum TMAG5273::Registers
private

Device register address offsets.

Definition at line 422 of file TMAG5273.hxx.

◆ SleepTime

enum class TMAG5273::SleepTime : uint8_t
strong

Sleep time between conversions when operating mode is wake-up and sleep.

Enumerator
SLEEP_1_MSEC 

1 millisecond, default

SLEEP_5_MSEC 

5 milliseconds

SLEEP_10_MSEC 

10 milliseconds

SLEEP_15_MSEC 

15 milliseconds

SLEEP_20_MSEC 

20 milliseconds

SLEEP_30_MSEC 

30 milliseconds

SLEEP_50_MSEC 

50 milliseconds

SLEEP_100_MSEC 

100 milliseconds

SLEEP_500_MSEC 

500 milliseconds

SLEEP_1000_MSEC 

1000 milliseconds

SLEEP_2000_MSEC 

2000 milliseconds

SLEEP_5000_MSEC 

5000 milliseconds

SLEEP_20000_MSEC 

20000 milliseconds

Definition at line 88 of file TMAG5273.hxx.

Constructor & Destructor Documentation

◆ TMAG5273() [1/2]

TMAG5273::TMAG5273 ( uint8_t  address = ADDR_A)
inline

Constructor.

Parameters
addressis the 7-bit address (right aligned), typically 0x35, 0x22, 0x78 or 0x44. Default is the A1/A2 device.

Definition at line 190 of file TMAG5273.hxx.

◆ TMAG5273() [2/2]

TMAG5273::TMAG5273 ( const char *  i2c_path,
uint8_t  address = ADDR_A 
)
inline

Constructor.

Can only be called from thread context.

Parameters
i2c_pathpath to the i2c bus to use.
addressis the 7-bit address (right aligned), typically 0x35, 0x22, 0x78 or 0x44. Default is the A1/A2 device.

Definition at line 198 of file TMAG5273.hxx.

◆ ~TMAG5273()

TMAG5273::~TMAG5273 ( )
inline

Destructor.

Definition at line 205 of file TMAG5273.hxx.

Member Function Documentation

◆ clr_device_status()

void TMAG5273::clr_device_status ( DeviceStatus  status)
inline

Get the device status.

Parameters
bitmask of DeviceStatus bits to clear

Definition at line 267 of file TMAG5273.hxx.

◆ clr_por_conversion_status()

void TMAG5273::clr_por_conversion_status ( )
inline

Clear the power on reset bit of the conversion status.

Definition at line 313 of file TMAG5273.hxx.

◆ enable_channels()

void TMAG5273::enable_channels ( ChannelEnable  enable)
inline

Enable/disable channels.

Parameters
enableThe channel set to enable. Default is all channels off.

Definition at line 274 of file TMAG5273.hxx.

◆ get_conversion_status()

uint8_t TMAG5273::get_conversion_status ( )
inline

Get the conversion status.

Returns
mask of ConversionStatus bits

Definition at line 305 of file TMAG5273.hxx.

◆ get_device_id()

DeviceID TMAG5273::get_device_id ( )
inline
Returns
Device ID (die version / sensitivity range). Mask off the reserved bits of the Device ID register. Deprecated, recommend is_present() API instead.

Definition at line 371 of file TMAG5273.hxx.

◆ get_device_status()

DeviceStatus TMAG5273::get_device_status ( )
inline

Get the device status.

Returns
bit mask of DeviceStatus

Definition at line 258 of file TMAG5273.hxx.

◆ init() [1/2]

void TMAG5273::init ( const char *  i2c_path)
inline

Definition at line 213 of file TMAG5273.hxx.

◆ init() [2/2]

void TMAG5273::init ( int  i2c_fd)
inline

Initializes the device.

Parameters
i2c_fdis the file descriptor of the i2c port to use.

Definition at line 222 of file TMAG5273.hxx.

◆ is_present()

DeviceID TMAG5273::is_present ( )
inline

Checks whether the magnetic sensor is present.

Returns
device identifier, else ID_UNKNOWN if not detected or unknown device

Definition at line 233 of file TMAG5273.hxx.

◆ read_angle_result()

int16_t TMAG5273::read_angle_result ( )
inline

Read the angle result.

Returns
angle in degrees (0 - 360) * 16

Definition at line 389 of file TMAG5273.hxx.

◆ read_conversion_results()

void TMAG5273::read_conversion_results ( int16_t  xyz[3])
inline

Read the conversion results.

Parameters
xyzresults as a three item array in order of X, Y, and Z

Definition at line 379 of file TMAG5273.hxx.

◆ register_modify()

void TMAG5273::register_modify ( uint8_t  reg,
uint8_t  mask,
uint8_t  value 
)
inlineprivate

Modifies a register value in place.

Parameters
regregister address to modify.
maskbitmask of which bits to modify
valuenew value of these bits (shifted to the right position). Any bits set outside the mask will be ignored.

Definition at line 528 of file TMAG5273.hxx.

◆ register_read() [1/2]

uint8_t TMAG5273::register_read ( uint8_t  reg)
inlineprivate

Reads a single register.

Parameters
regregister number.
Returns
the register's current value.

Definition at line 514 of file TMAG5273.hxx.

◆ register_read() [2/2]

int TMAG5273::register_read ( uint8_t  reg,
uint8_t *  data,
uint16_t  len 
)
inlineprivate

Reads one or more (sequential) registers.

Parameters
regstarting register offset.
datawhere to write payload
lennumber of registers to read (1 byte each). Returns when the read is complete.
Returns
-1 on error (see errno), 0 on success

Definition at line 461 of file TMAG5273.hxx.

◆ register_write() [1/2]

void TMAG5273::register_write ( uint8_t  reg,
const uint8_t *  data,
uint16_t  len 
)
inlineprivate

Writes one or more (sequential) register.

Parameters
regstarting register offset.
datapayload to write
lennumber of bytes to write. Returns when the write is complete.

Definition at line 478 of file TMAG5273.hxx.

◆ register_write() [2/2]

void TMAG5273::register_write ( uint8_t  reg,
uint8_t  value 
)
inlineprivate

Writes one register.

Parameters
regstarting register offset.
valuepayload to write Returns when the write is complete.

Definition at line 503 of file TMAG5273.hxx.

◆ set_angle_en()

void TMAG5273::set_angle_en ( AngleEnable  angle)
inline

Sets whether angle measurement should be enabled.

Parameters
angleangle measurement to enabld (or disable)

Definition at line 329 of file TMAG5273.hxx.

◆ set_angle_gain()

void TMAG5273::set_angle_gain ( uint8_t  gain,
bool  second 
)
inline

Sets angle gain parameters.

Parameters
gain8-bit gain value (interpreted as 0..1)
secondtrue if the second channel is larger than the first channel

Definition at line 340 of file TMAG5273.hxx.

◆ set_interrupt_config()

void TMAG5273::set_interrupt_config ( InterruptConfig  config)
inline

Set the interrupt config.

Parameters
configInterruptConfig options or'd together.

Definition at line 290 of file TMAG5273.hxx.

◆ set_offset_1()

void TMAG5273::set_offset_1 ( int8_t  offset)
inline

Sets offset correction for the first axis.

The maximum correction is -2048 .. +2032.

Parameters
offset8-bit signed value to write to offset correction. The counts offset are offset * 16.

Definition at line 353 of file TMAG5273.hxx.

◆ set_offset_2()

void TMAG5273::set_offset_2 ( int8_t  offset)
inline

Sets offset correction for the second axis.

The maximum correction is -2048 .. +2032.

Parameters
offset8-bit signed value to write to offset correction.

Definition at line 363 of file TMAG5273.hxx.

◆ set_operating_mode()

void TMAG5273::set_operating_mode ( OperatingMode  mode)
inline

Set the operating mode.

Parameters
modeoperating mode to set

Definition at line 297 of file TMAG5273.hxx.

◆ set_oversampling()

void TMAG5273::set_oversampling ( ConversionAverage  avg)
inline

Sets the oversampling+averaging mode.

Parameters
avgaverage oversample setting

Definition at line 321 of file TMAG5273.hxx.

◆ set_sleep_time()

void TMAG5273::set_sleep_time ( SleepTime  t)
inline

Set the sleep time between channels in wake and sleep mode.

Parameters
tThe sleep time between conversions.

Definition at line 282 of file TMAG5273.hxx.

Friends And Related Symbol Documentation

◆ Input

friend class Input
friend

Definition at line 228 of file TMAG5273.hxx.

◆ MagSensorTest

friend class MagSensorTest
friend

Definition at line 227 of file TMAG5273.hxx.

Member Data Documentation

◆ fd_

int TMAG5273::fd_ = -1
private

I2C device.

Definition at line 537 of file TMAG5273.hxx.

◆ i2cAddress_

const uint8_t TMAG5273::i2cAddress_
private

7-bit address, right aligned.

Definition at line 539 of file TMAG5273.hxx.


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