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

#include <ADIS16477.hpp>

Inheritance diagram for ADIS16477:
Collaboration diagram for ADIS16477:

Classes

struct  ADISReport
 

Public Member Functions

 ADIS16477 (int bus, uint32_t device, enum Rotation rotation=ROTATION_NONE)
 
virtual ~ADIS16477 ()
 
virtual int init ()
 
void print_info ()
 

Protected Member Functions

virtual int probe ()
 

Private Member Functions

void start ()
 Start automatic measurement. More...
 
void stop ()
 Stop automatic measurement. More...
 
int reset ()
 Reset chip. More...
 
void Run () override
 
int measure ()
 Fetch measurements from the sensor and update the report buffers. More...
 
uint16_t read_reg16 (uint8_t reg)
 
void write_reg (uint8_t reg, uint8_t value)
 
void write_reg16 (uint8_t reg, uint16_t value)
 
bool self_test_memory ()
 
bool self_test_sensor ()
 

Static Private Member Functions

static int data_ready_interrupt (int irq, void *context, void *arg)
 

Private Attributes

PX4Accelerometer _px4_accel
 
PX4Gyroscope _px4_gyro
 
perf_counter_t _sample_perf
 
perf_counter_t _bad_transfers
 

Detailed Description

Definition at line 50 of file ADIS16477.hpp.

Constructor & Destructor Documentation

◆ ADIS16477()

ADIS16477::ADIS16477 ( int  bus,
uint32_t  device,
enum Rotation  rotation = ROTATION_NONE 
)

◆ ~ADIS16477()

ADIS16477::~ADIS16477 ( )
virtual

Definition at line 78 of file ADIS16477.cpp.

References _bad_transfers, _sample_perf, perf_free(), and stop().

Here is the call graph for this function:

Member Function Documentation

◆ data_ready_interrupt()

int ADIS16477::data_ready_interrupt ( int  irq,
void *  context,
void *  arg 
)
staticprivate

Definition at line 302 of file ADIS16477.cpp.

Referenced by start().

Here is the caller graph for this function:

◆ init()

int ADIS16477::init ( )
virtual

Definition at line 89 of file ADIS16477.cpp.

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

Referenced by adis16477::start().

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

◆ measure()

int ADIS16477::measure ( )
private

Fetch measurements from the sensor and update the report buffers.

Definition at line 320 of file ADIS16477.cpp.

References _bad_transfers, _px4_accel, _px4_gyro, _sample_perf, ADIS16477::ADISReport::cmd, DIR_READ, GLOB_CMD, hrt_absolute_time(), hrt_abstime, OK, perf_begin(), perf_count(), perf_end(), PX4Accelerometer::set_temperature(), PX4Gyroscope::set_temperature(), PX4Accelerometer::update(), and PX4Gyroscope::update().

Referenced by Run().

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

◆ print_info()

void ADIS16477::print_info ( )

Definition at line 389 of file ADIS16477.cpp.

References _bad_transfers, _px4_accel, _px4_gyro, _sample_perf, perf_print_counter(), PX4Accelerometer::print_status(), and PX4Gyroscope::print_status().

Referenced by adis16477::status().

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

◆ probe()

int ADIS16477::probe ( )
protectedvirtual

Definition at line 166 of file ADIS16477.cpp.

References PROD_ID, PROD_ID_ADIS16477, read_reg16(), reset(), self_test_memory(), and self_test_sensor().

Here is the call graph for this function:

◆ read_reg16()

uint16_t ADIS16477::read_reg16 ( uint8_t  reg)
private

Definition at line 239 of file ADIS16477.cpp.

References DIR_READ, and T_STALL.

Referenced by probe(), reset(), self_test_memory(), and self_test_sensor().

Here is the caller graph for this function:

◆ reset()

int ADIS16477::reset ( )
private

Reset chip.

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

Definition at line 103 of file ADIS16477.cpp.

References DEC_RATE, FILT_CTRL, GLOB_CMD, MSC_CTRL, OK, read_reg16(), and write_reg16().

Referenced by probe().

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

◆ Run()

void ADIS16477::Run ( )
overrideprivate

Definition at line 313 of file ADIS16477.cpp.

References measure().

Here is the call graph for this function:

◆ self_test_memory()

bool ADIS16477::self_test_memory ( )
private

Definition at line 195 of file ADIS16477.cpp.

References DEVICE_DEBUG, DIAG_STAT, GLOB_CMD, read_reg16(), and write_reg16().

Referenced by probe().

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

◆ self_test_sensor()

bool ADIS16477::self_test_sensor ( )
private

Definition at line 217 of file ADIS16477.cpp.

References DIAG_STAT, GLOB_CMD, read_reg16(), and write_reg16().

Referenced by probe().

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

◆ start()

void ADIS16477::start ( )
private

Start automatic measurement.

Definition at line 276 of file ADIS16477.cpp.

References ADIS16477_DEFAULT_RATE, data_ready_interrupt(), and stop().

Referenced by init().

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

◆ stop()

void ADIS16477::stop ( )
private

Stop automatic measurement.

Definition at line 291 of file ADIS16477.cpp.

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

Here is the caller graph for this function:

◆ write_reg()

void ADIS16477::write_reg ( uint8_t  reg,
uint8_t  value 
)
private

Definition at line 253 of file ADIS16477.cpp.

◆ write_reg16()

void ADIS16477::write_reg16 ( uint8_t  reg,
uint16_t  value 
)
private

Definition at line 262 of file ADIS16477.cpp.

References DIR_WRITE, and T_STALL.

Referenced by reset(), self_test_memory(), and self_test_sensor().

Here is the caller graph for this function:

Member Data Documentation

◆ _bad_transfers

perf_counter_t ADIS16477::_bad_transfers
private

Definition at line 69 of file ADIS16477.hpp.

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

◆ _px4_accel

PX4Accelerometer ADIS16477::_px4_accel
private

Definition at line 65 of file ADIS16477.hpp.

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

◆ _px4_gyro

PX4Gyroscope ADIS16477::_px4_gyro
private

Definition at line 66 of file ADIS16477.hpp.

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

◆ _sample_perf

perf_counter_t ADIS16477::_sample_perf
private

Definition at line 68 of file ADIS16477.hpp.

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


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