PX4 Firmware
PX4 Autopilot Software http://px4.io
L3GD20 Class Reference
Inheritance diagram for L3GD20:
Collaboration diagram for L3GD20:

Public Member Functions

 L3GD20 (int bus, const char *path, uint32_t device, enum Rotation rotation)
 
virtual ~L3GD20 ()
 
virtual int init ()
 
void print_info ()
 Diagnostics - print some basic information about the driver. More...
 
void print_registers ()
 
void test_error ()
 

Protected Member Functions

virtual int probe ()
 

Private Member Functions

void start ()
 Start automatic measurement. More...
 
void stop ()
 Stop automatic measurement. More...
 
void reset ()
 Reset the driver. More...
 
void disable_i2c ()
 disable I2C on the chip More...
 
void Run () override
 
void check_registers (void)
 check key registers for correct values More...
 
void measure ()
 Fetch measurements from the sensor and update the report ring. More...
 
uint8_t read_reg (unsigned reg)
 Read a register from the L3GD20. More...
 
void write_reg (unsigned reg, uint8_t value)
 Write a register in the L3GD20. More...
 
void modify_reg (unsigned reg, uint8_t clearbits, uint8_t setbits)
 Modify a register in the L3GD20. More...
 
void write_checked_reg (unsigned reg, uint8_t value)
 Write a register in the L3GD20, updating _checked_values. More...
 
int set_range (unsigned max_dps)
 Set the L3GD20 measurement range. More...
 
int set_samplerate (unsigned frequency)
 Set the L3GD20 internal sampling frequency. More...
 
 L3GD20 (const L3GD20 &)
 
L3GD20 operator= (const L3GD20 &)
 

Private Attributes

PX4Gyroscope _px4_gyro
 
unsigned _current_rate {0}
 
unsigned _orientation {SENSOR_BOARD_ROTATION_DEFAULT}
 
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}
 
bool _is_l3g4200d {false}
 
enum Rotation _rotation
 
uint8_t _checked_values [L3GD20_NUM_CHECKED_REGISTERS] {}
 
uint8_t _checked_next {0}
 

Static Private Attributes

static constexpr int L3GD20_NUM_CHECKED_REGISTERS {8}
 
static constexpr uint8_t _checked_registers []
 

Detailed Description

Definition at line 168 of file l3gd20.cpp.

Constructor & Destructor Documentation

◆ L3GD20() [1/2]

L3GD20::L3GD20 ( int  bus,
const char *  path,
uint32_t  device,
enum Rotation  rotation 
)

Definition at line 323 of file l3gd20.cpp.

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

Referenced by l3gd20::start().

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

◆ ~L3GD20()

L3GD20::~L3GD20 ( )
virtual

Definition at line 336 of file l3gd20.cpp.

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

Here is the call graph for this function:

◆ L3GD20() [2/2]

L3GD20::L3GD20 ( const L3GD20 )
private

Member Function Documentation

◆ check_registers()

void L3GD20::check_registers ( void  )
private

check key registers for correct values

Definition at line 590 of file l3gd20.cpp.

References _bad_registers, _checked_next, _checked_registers, _checked_values, _register_wait, L3GD20_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:

◆ disable_i2c()

void L3GD20::disable_i2c ( void  )
private

disable I2C on the chip

Definition at line 535 of file l3gd20.cpp.

References ADDR_LOW_ODR, DEVICE_DEBUG, read_reg(), write_checked_reg(), and write_reg().

Referenced by reset().

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

◆ init()

int L3GD20::init ( )
virtual

Definition at line 349 of file l3gd20.cpp.

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

Referenced by l3gd20::start().

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

◆ measure()

void L3GD20::measure ( )
private

Fetch measurements from the sensor and update the report ring.

Definition at line 620 of file l3gd20.cpp.

References _bad_registers, _duplicates, _orientation, _px4_gyro, _read, _sample_perf, ADDR_INCREMENT, ADDR_OUT_TEMP, check_registers(), DIR_READ, hrt_absolute_time(), hrt_abstime, L3GD20_TEMP_OFFSET_CELSIUS, perf_begin(), perf_count(), perf_end(), perf_event_count(), SENSOR_BOARD_ROTATION_000_DEG, SENSOR_BOARD_ROTATION_090_DEG, SENSOR_BOARD_ROTATION_180_DEG, SENSOR_BOARD_ROTATION_270_DEG, PX4Gyroscope::set_error_count(), PX4Gyroscope::set_temperature(), status, STATUS_ZYXDA, 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 L3GD20::modify_reg ( unsigned  reg,
uint8_t  clearbits,
uint8_t  setbits 
)
private

Modify a register in the L3GD20.

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 435 of file l3gd20.cpp.

References read_reg(), and write_checked_reg().

Here is the call graph for this function:

◆ operator=()

L3GD20 L3GD20::operator= ( const L3GD20 )
private

◆ print_info()

void L3GD20::print_info ( )

Diagnostics - print some basic information about the driver.

Definition at line 706 of file l3gd20.cpp.

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

Referenced by l3gd20::info().

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

◆ print_registers()

void L3GD20::print_registers ( )

Definition at line 731 of file l3gd20.cpp.

References read_reg().

Referenced by l3gd20::regdump().

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

◆ probe()

int L3GD20::probe ( )
protectedvirtual

Definition at line 364 of file l3gd20.cpp.

References _checked_values, _is_l3g4200d, _orientation, ADDR_WHO_AM_I, OK, read_reg(), SENSOR_BOARD_ROTATION_180_DEG, SENSOR_BOARD_ROTATION_DEFAULT, WHO_I_AM, WHO_I_AM_H, and WHO_I_AM_L3G4200D.

Here is the call graph for this function:

◆ read_reg()

uint8_t L3GD20::read_reg ( unsigned  reg)
private

Read a register from the L3GD20.

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

Definition at line 398 of file l3gd20.cpp.

References DIR_READ.

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

Here is the caller graph for this function:

◆ reset()

void L3GD20::reset ( )
private

Reset the driver.

Definition at line 558 of file l3gd20.cpp.

References _read, ADDR_CTRL_REG1, ADDR_CTRL_REG2, ADDR_CTRL_REG3, ADDR_CTRL_REG4, ADDR_CTRL_REG5, ADDR_FIFO_CTRL_REG, disable_i2c(), FIFO_CTRL_BYPASS_MODE, L3GD20_DEFAULT_RANGE_DPS, REG1_POWER_NORMAL, REG1_X_ENABLE, REG1_Y_ENABLE, REG1_Z_ENABLE, REG4_BDU, REG5_FIFO_ENABLE, set_range(), set_samplerate(), and write_checked_reg().

Referenced by init().

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

◆ Run()

void L3GD20::Run ( )
overrideprivate

Definition at line 583 of file l3gd20.cpp.

References measure().

Here is the call graph for this function:

◆ set_range()

int L3GD20::set_range ( unsigned  max_dps)
private

Set the L3GD20 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 444 of file l3gd20.cpp.

References _px4_gyro, ADDR_CTRL_REG4, f(), M_PI_F, OK, RANGE_2000DPS, RANGE_250DPS, RANGE_500DPS, REG4_BDU, PX4Gyroscope::set_scale(), and write_checked_reg().

Referenced by reset().

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

◆ set_samplerate()

int L3GD20::set_samplerate ( unsigned  frequency)
private

Set the L3GD20 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 480 of file l3gd20.cpp.

References _current_rate, _is_l3g4200d, ADDR_CTRL_REG1, OK, RATE_190HZ_LP_50HZ, RATE_380HZ_LP_50HZ, RATE_760HZ_LP_50HZ, RATE_95HZ_LP_25HZ, REG1_POWER_NORMAL, REG1_X_ENABLE, REG1_Y_ENABLE, REG1_Z_ENABLE, and write_checked_reg().

Referenced by reset().

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

◆ start()

void L3GD20::start ( )
private

Start automatic measurement.

Definition at line 518 of file l3gd20.cpp.

References L3G4200D_DEFAULT_RATE, L3GD20_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 L3GD20::stop ( )
private

Stop automatic measurement.

Definition at line 529 of file l3gd20.cpp.

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

Here is the caller graph for this function:

◆ test_error()

void L3GD20::test_error ( )

Definition at line 748 of file l3gd20.cpp.

References ADDR_CTRL_REG3, and write_reg().

Referenced by l3gd20::test_error().

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

◆ write_checked_reg()

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

Write a register in the L3GD20, updating _checked_values.

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

Definition at line 422 of file l3gd20.cpp.

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

Referenced by disable_i2c(), modify_reg(), reset(), set_range(), and set_samplerate().

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

◆ write_reg()

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

Write a register in the L3GD20.

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

Definition at line 411 of file l3gd20.cpp.

References DIR_WRITE.

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

Here is the caller graph for this function:

Member Data Documentation

◆ _bad_registers

perf_counter_t L3GD20::_bad_registers
private

Definition at line 201 of file l3gd20.cpp.

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

◆ _checked_next

uint8_t L3GD20::_checked_next {0}
private

Definition at line 227 of file l3gd20.cpp.

Referenced by check_registers(), and print_info().

◆ _checked_registers

constexpr uint8_t L3GD20::_checked_registers
staticprivate

◆ _checked_values

uint8_t L3GD20::_checked_values[L3GD20_NUM_CHECKED_REGISTERS] {}
private

Definition at line 226 of file l3gd20.cpp.

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

◆ _current_rate

unsigned L3GD20::_current_rate {0}
private

Definition at line 194 of file l3gd20.cpp.

Referenced by set_samplerate().

◆ _duplicates

perf_counter_t L3GD20::_duplicates
private

Definition at line 202 of file l3gd20.cpp.

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

◆ _errors

perf_counter_t L3GD20::_errors
private

Definition at line 200 of file l3gd20.cpp.

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

◆ _is_l3g4200d

bool L3GD20::_is_l3g4200d {false}
private

Definition at line 207 of file l3gd20.cpp.

Referenced by probe(), and set_samplerate().

◆ _orientation

unsigned L3GD20::_orientation {SENSOR_BOARD_ROTATION_DEFAULT}
private

Definition at line 195 of file l3gd20.cpp.

Referenced by measure(), and probe().

◆ _px4_gyro

PX4Gyroscope L3GD20::_px4_gyro
private

Definition at line 192 of file l3gd20.cpp.

Referenced by L3GD20(), measure(), print_info(), and set_range().

◆ _read

unsigned L3GD20::_read {0}
private

Definition at line 197 of file l3gd20.cpp.

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

◆ _register_wait

uint8_t L3GD20::_register_wait {0}
private

Definition at line 204 of file l3gd20.cpp.

Referenced by check_registers().

◆ _rotation

enum Rotation L3GD20::_rotation
private

Definition at line 209 of file l3gd20.cpp.

◆ _sample_perf

perf_counter_t L3GD20::_sample_perf
private

Definition at line 199 of file l3gd20.cpp.

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

◆ L3GD20_NUM_CHECKED_REGISTERS

constexpr int L3GD20::L3GD20_NUM_CHECKED_REGISTERS {8}
staticprivate

Definition at line 214 of file l3gd20.cpp.

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


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