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

#include <FXAS21002C.hpp>

Inheritance diagram for FXAS21002C:
Collaboration diagram for FXAS21002C:

Public Member Functions

 FXAS21002C (int bus, uint32_t device, enum Rotation rotation)
 
virtual ~FXAS21002C ()
 
virtual int init ()
 
void print_info ()
 Diagnostics - print some basic information about the driver. More...
 
void print_registers ()
 dump register values More...
 
void test_error ()
 deliberately trigger an error More...
 

Protected Member Functions

virtual int probe ()
 

Private Member Functions

void start ()
 Start automatic measurement. More...
 
void stop ()
 Stop automatic measurement. More...
 
void reset ()
 Reset chip. More...
 
void set_standby (int rate, bool standby_true)
 Put the chip In stand by. More...
 
void Run () override
 
void check_registers (void)
 check key registers for correct values More...
 
void measure ()
 Fetch accel measurements from the sensor and update the report ring. More...
 
uint8_t read_reg (unsigned reg)
 Read a register from the FXAS21002C. More...
 
void write_reg (unsigned reg, uint8_t value)
 Write a register in the FXAS21002C. More...
 
void modify_reg (unsigned reg, uint8_t clearbits, uint8_t setbits)
 Modify a register in the FXAS21002C. More...
 
void write_checked_reg (unsigned reg, uint8_t value)
 Write a register in the FXAS21002C, updating _checked_values. More...
 
int set_range (unsigned max_dps)
 Set the FXAS21002C measurement range. More...
 
int set_samplerate (unsigned frequency)
 Set the FXAS21002C internal sampling frequency. More...
 
void set_onchip_lowpass_filter (int frequency_hz)
 

Private Attributes

PX4Gyroscope _px4_gyro
 
unsigned _current_rate {800}
 
unsigned _read {0}
 
perf_counter_t _sample_perf
 
perf_counter_t _errors
 
perf_counter_t _bad_registers
 
perf_counter_t _duplicates
 
uint8_t _register_wait {0}
 
uint8_t _checked_values [FXAS21002C_NUM_CHECKED_REGISTERS] {}
 
uint8_t _checked_next {0}
 

Static Private Attributes

static constexpr int FXAS21002C_NUM_CHECKED_REGISTERS {6}
 

Detailed Description

Definition at line 49 of file FXAS21002C.hpp.

Constructor & Destructor Documentation

◆ FXAS21002C()

FXAS21002C::FXAS21002C ( int  bus,
uint32_t  device,
enum Rotation  rotation 
)

Definition at line 189 of file FXAS21002C.cpp.

References _px4_gyro, DRV_GYR_DEVTYPE_FXAS2100C, and PX4Gyroscope::set_device_type().

Here is the call graph for this function:

◆ ~FXAS21002C()

FXAS21002C::~FXAS21002C ( )
virtual

Definition at line 201 of file FXAS21002C.cpp.

References _bad_registers, _duplicates, _errors, _sample_perf, perf_free(), and stop().

Here is the call graph for this function:

Member Function Documentation

◆ check_registers()

void FXAS21002C::check_registers ( void  )
private

check key registers for correct values

Definition at line 497 of file FXAS21002C.cpp.

References _bad_registers, _checked_next, _checked_registers, _checked_values, _register_wait, FXAS21002C_NUM_CHECKED_REGISTERS, perf_count(), read_reg(), and write_reg().

Referenced by measure().

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

◆ init()

int FXAS21002C::init ( )
virtual

Definition at line 214 of file FXAS21002C.cpp.

References ToneAlarmInterface::init(), OK, reset(), and start().

Referenced by fxas21002c::start().

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

◆ measure()

void FXAS21002C::measure ( )
private

Fetch accel measurements from the sensor and update the report ring.

Definition at line 527 of file FXAS21002C.cpp.

References _bad_registers, _current_rate, _duplicates, _px4_gyro, _read, _register_wait, _sample_perf, check_registers(), DIR_READ, DR_STATUS_ZYXDR, FXAS21002C_STATUS, FXAS21002C_TEMP, hrt_absolute_time(), hrt_abstime, perf_begin(), perf_count(), perf_end(), perf_event_count(), read_reg(), PX4Gyroscope::set_error_count(), PX4Gyroscope::set_temperature(), status, swap16, and PX4Gyroscope::update().

Referenced by Run().

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

◆ modify_reg()

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

Modify a register in the FXAS21002C.

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 311 of file FXAS21002C.cpp.

References read_reg(), and write_checked_reg().

Referenced by set_onchip_lowpass_filter(), set_range(), set_samplerate(), and set_standby().

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

◆ print_info()

void FXAS21002C::print_info ( )

Diagnostics - print some basic information about the driver.

Definition at line 594 of file FXAS21002C.cpp.

References _bad_registers, _checked_next, _checked_registers, _checked_values, _duplicates, _errors, _px4_gyro, _read, _sample_perf, FXAS21002C_NUM_CHECKED_REGISTERS, perf_print_counter(), PX4Gyroscope::print_status(), and read_reg().

Referenced by fxas21002c::info().

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

◆ print_registers()

void FXAS21002C::print_registers ( )

dump register values

Definition at line 618 of file FXAS21002C.cpp.

References DEF_REG, FXAS21002C_CTRL_REG0, FXAS21002C_CTRL_REG1, FXAS21002C_CTRL_REG2, FXAS21002C_CTRL_REG3, FXAS21002C_DR_STATUS, FXAS21002C_F_EVENT, FXAS21002C_F_SETUP, FXAS21002C_F_STATUS, FXAS21002C_INT_SRC_FLAG, FXAS21002C_OUT_X_LSB, FXAS21002C_OUT_X_MSB, FXAS21002C_OUT_Y_LSB, FXAS21002C_OUT_Y_MSB, FXAS21002C_OUT_Z_LSB, FXAS21002C_OUT_Z_MSB, FXAS21002C_RT_CFG, FXAS21002C_RT_COUNT, FXAS21002C_RT_SRC, FXAS21002C_RT_THS, FXAS21002C_STATUS, FXAS21002C_TEMP, FXAS21002C_WHO_AM_I, name, and read_reg().

Referenced by fxas21002c::regdump().

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

◆ probe()

int FXAS21002C::probe ( )
protectedvirtual

Definition at line 261 of file FXAS21002C.cpp.

References _checked_values, FXAS21002C_WHO_AM_I, OK, read_reg(), and WHO_AM_I.

Here is the call graph for this function:

◆ read_reg()

uint8_t FXAS21002C::read_reg ( unsigned  reg)
private

Read a register from the FXAS21002C.

Parameters
Theregister to read.
Returns
The value that was read.

Definition at line 275 of file FXAS21002C.cpp.

References DIR_READ.

Referenced by check_registers(), measure(), modify_reg(), print_info(), print_registers(), and probe().

Here is the caller graph for this function:

◆ reset()

void FXAS21002C::reset ( )
private

Reset chip.

Resets the chip and measurements ranges, but not scale and offset.

Definition at line 230 of file FXAS21002C.cpp.

References _read, CTRL_REG0_BW_LOW, CTRL_REG0_FS_2000_DPS, CTRL_REG1_ACTIVE, CTRL_REG1_DR_800HZ, FXAS21002C_CTRL_REG0, FXAS21002C_CTRL_REG1, FXAS21002C_DEFAULT_ONCHIP_FILTER_FREQ, FXAS21002C_DEFAULT_RANGE_DPS, FXAS21002C_DEFAULT_RATE, set_onchip_lowpass_filter(), set_range(), set_samplerate(), write_checked_reg(), and write_reg().

Referenced by init().

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

◆ Run()

void FXAS21002C::Run ( )
overrideprivate

Definition at line 490 of file FXAS21002C.cpp.

References measure().

Here is the call graph for this function:

◆ set_onchip_lowpass_filter()

void FXAS21002C::set_onchip_lowpass_filter ( int  frequency_hz)
private

Definition at line 438 of file FXAS21002C.cpp.

References _current_rate, CTRL_REG0_BW_HIGH, CTRL_REG0_BW_LOW, CTRL_REG0_BW_MASK, CTRL_REG0_BW_MED, FXAS21002C_CTRL_REG1, modify_reg(), and set_standby().

Referenced by reset().

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

◆ set_range()

int FXAS21002C::set_range ( unsigned  max_dps)
private

Set the FXAS21002C measurement range.

Parameters
max_dpsThe measurement range is set to permit reading at least this rate in degrees per second. Zero selects the maximum supported range.
Returns
OK if the value can be supported, -ERANGE otherwise.

Definition at line 320 of file FXAS21002C.cpp.

References _current_rate, _px4_gyro, CTRL_REG0_FS_1000_DPS, CTRL_REG0_FS_2000_DPS, CTRL_REG0_FS_250_DPS, CTRL_REG0_FS_500_DPS, CTRL_REG0_FS_MASK, f(), FXAS21002C_CTRL_REG0, M_PI_F, modify_reg(), OK, PX4Gyroscope::set_scale(), and set_standby().

Referenced by reset().

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

◆ set_samplerate()

int FXAS21002C::set_samplerate ( unsigned  frequency)
private

Set the FXAS21002C internal sampling frequency.

Parameters
frequencyThe internal sampling frequency is set to not less than this value. Zero selects the maximum rate supported.
Returns
OK if the value can be supported.

Definition at line 386 of file FXAS21002C.cpp.

References _current_rate, _px4_gyro, CTRL_REG1_DR_100HZ, CTRL_REG1_DR_12_5, CTRL_REG1_DR_200HZ, CTRL_REG1_DR_25HZ, CTRL_REG1_DR_400HZ, CTRL_REG1_DR_50HZ, CTRL_REG1_DR_800HZ, CTRL_REG1_DR_MASK, FXAS21002C_CTRL_REG1, FXAS21002C_DEFAULT_RATE, modify_reg(), OK, PX4Gyroscope::set_sample_rate(), and set_standby().

Referenced by reset().

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

◆ set_standby()

void FXAS21002C::set_standby ( int  rate,
bool  standby_true 
)
private

Put the chip In stand by.

Definition at line 364 of file FXAS21002C.cpp.

References CTRL_REG1_ACTIVE, CTRL_REG1_READY, FXAS21002C_CTRL_REG1, and modify_reg().

Referenced by set_onchip_lowpass_filter(), set_range(), and set_samplerate().

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

◆ start()

void FXAS21002C::start ( )
private

Start automatic measurement.

Definition at line 474 of file FXAS21002C.cpp.

References FXAS21002C_DEFAULT_RATE, FXAS21002C_TIMER_REDUCTION, and stop().

Referenced by init().

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

◆ stop()

void FXAS21002C::stop ( )
private

Stop automatic measurement.

Definition at line 484 of file FXAS21002C.cpp.

Referenced by start(), and ~FXAS21002C().

Here is the caller graph for this function:

◆ test_error()

void FXAS21002C::test_error ( )

deliberately trigger an error

Definition at line 654 of file FXAS21002C.cpp.

References FXAS21002C_CTRL_REG1, and write_reg().

Referenced by fxas21002c::test_error().

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

◆ write_checked_reg()

void FXAS21002C::write_checked_reg ( unsigned  reg,
uint8_t  value 
)
private

Write a register in the FXAS21002C, updating _checked_values.

Parameters
regThe register to write.
valueThe new value to write.

Definition at line 299 of file FXAS21002C.cpp.

References _checked_registers, _checked_values, FXAS21002C_NUM_CHECKED_REGISTERS, and write_reg().

Referenced by modify_reg(), and reset().

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

◆ write_reg()

void FXAS21002C::write_reg ( unsigned  reg,
uint8_t  value 
)
private

Write a register in the FXAS21002C.

Parameters
regThe register to write.
valueThe new value to write.

Definition at line 288 of file FXAS21002C.cpp.

References DIR_WRITE.

Referenced by check_registers(), reset(), test_error(), and write_checked_reg().

Here is the caller graph for this function:

Member Data Documentation

◆ _bad_registers

perf_counter_t FXAS21002C::_bad_registers
private

Definition at line 85 of file FXAS21002C.hpp.

Referenced by check_registers(), measure(), print_info(), and ~FXAS21002C().

◆ _checked_next

uint8_t FXAS21002C::_checked_next {0}
private

Definition at line 97 of file FXAS21002C.hpp.

Referenced by check_registers(), and print_info().

◆ _checked_values

uint8_t FXAS21002C::_checked_values[FXAS21002C_NUM_CHECKED_REGISTERS] {}
private

Definition at line 96 of file FXAS21002C.hpp.

Referenced by check_registers(), print_info(), probe(), and write_checked_reg().

◆ _current_rate

unsigned FXAS21002C::_current_rate {800}
private

Definition at line 79 of file FXAS21002C.hpp.

Referenced by measure(), set_onchip_lowpass_filter(), set_range(), and set_samplerate().

◆ _duplicates

perf_counter_t FXAS21002C::_duplicates
private

Definition at line 86 of file FXAS21002C.hpp.

Referenced by measure(), print_info(), and ~FXAS21002C().

◆ _errors

perf_counter_t FXAS21002C::_errors
private

Definition at line 84 of file FXAS21002C.hpp.

Referenced by print_info(), and ~FXAS21002C().

◆ _px4_gyro

PX4Gyroscope FXAS21002C::_px4_gyro
private

Definition at line 77 of file FXAS21002C.hpp.

Referenced by FXAS21002C(), measure(), print_info(), set_range(), and set_samplerate().

◆ _read

unsigned FXAS21002C::_read {0}
private

Definition at line 81 of file FXAS21002C.hpp.

Referenced by measure(), print_info(), and reset().

◆ _register_wait

uint8_t FXAS21002C::_register_wait {0}
private

Definition at line 88 of file FXAS21002C.hpp.

Referenced by check_registers(), and measure().

◆ _sample_perf

perf_counter_t FXAS21002C::_sample_perf
private

Definition at line 83 of file FXAS21002C.hpp.

Referenced by measure(), print_info(), and ~FXAS21002C().

◆ FXAS21002C_NUM_CHECKED_REGISTERS

constexpr int FXAS21002C::FXAS21002C_NUM_CHECKED_REGISTERS {6}
staticprivate

Definition at line 94 of file FXAS21002C.hpp.

Referenced by check_registers(), print_info(), and write_checked_reg().


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