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

#include <ADIS16497.hpp>

Inheritance diagram for ADIS16497:
Collaboration diagram for ADIS16497:

Classes

struct  ADISReport
 

Public Member Functions

 ADIS16497 (int bus, uint32_t device, enum Rotation rotation=ROTATION_NONE)
 
virtual ~ADIS16497 ()
 
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 ()
 
uint32_t crc32 (const uint16_t *data, size_t len) const
 

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 86 of file ADIS16497.hpp.

Constructor & Destructor Documentation

◆ ADIS16497()

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

◆ ~ADIS16497()

ADIS16497::~ADIS16497 ( )
virtual

Definition at line 91 of file ADIS16497.cpp.

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

Here is the call graph for this function:

Member Function Documentation

◆ crc32()

uint32_t ADIS16497::crc32 ( const uint16_t *  data,
size_t  len 
) const
inlineprivate

Definition at line 167 of file ADIS16497.hpp.

References crc32_tab, and data.

Referenced by measure().

Here is the caller graph for this function:

◆ data_ready_interrupt()

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

Definition at line 365 of file ADIS16497.cpp.

Referenced by start().

Here is the caller graph for this function:

◆ init()

int ADIS16497::init ( )
virtual

Definition at line 102 of file ADIS16497.cpp.

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

Referenced by adis16497::start().

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

◆ measure()

int ADIS16497::measure ( )
private

Fetch measurements from the sensor and update the report buffers.

Definition at line 383 of file ADIS16497.cpp.

References _bad_transfers, _px4_accel, _px4_gyro, _sample_perf, BURST_CMD, ADIS16497::ADISReport::cmd, crc32(), DIR_READ, f(), hrt_absolute_time(), hrt_abstime, OK, perf_begin(), perf_count(), perf_end(), perf_event_count(), PX4Accelerometer::set_error_count(), PX4Gyroscope::set_error_count(), 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 ADIS16497::print_info ( )

Definition at line 466 of file ADIS16497.cpp.

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

Referenced by adis16497::status().

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

◆ probe()

int ADIS16497::probe ( )
protectedvirtual

Definition at line 234 of file ADIS16497.cpp.

References PAGE_ID, PROD_ID, PROD_ID_ADIS16497, read_reg16(), reset(), self_test(), and write_reg16().

Here is the call graph for this function:

◆ read_reg16()

uint16_t ADIS16497::read_reg16 ( uint8_t  reg)
private

Definition at line 302 of file ADIS16497.cpp.

References DIR_READ, and T_STALL.

Referenced by probe(), reset(), and self_test().

Here is the caller graph for this function:

◆ reset()

int ADIS16497::reset ( )
private

Reset chip.

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

Definition at line 116 of file ADIS16497.cpp.

References CONFIG, DEC_RATE, FILTR_BNK_0, FILTR_BNK_1, FNCTIO_CTRL, GLOB_CMD, NULL_CNFG, OK, PAGE_ID, 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 ADIS16497::Run ( )
overrideprivate

Definition at line 376 of file ADIS16497.cpp.

References measure().

Here is the call graph for this function:

◆ self_test()

bool ADIS16497::self_test ( )
private

Definition at line 267 of file ADIS16497.cpp.

References DIAG_STS, GLOB_CMD, PAGE_ID, read_reg16(), SYS_E_FLAG, and write_reg16().

Referenced by probe().

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

◆ start()

void ADIS16497::start ( )
private

Start automatic measurement.

Definition at line 339 of file ADIS16497.cpp.

References ADIS16497_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 ADIS16497::stop ( )
private

Stop automatic measurement.

Definition at line 354 of file ADIS16497.cpp.

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

Here is the caller graph for this function:

◆ write_reg()

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

Definition at line 316 of file ADIS16497.cpp.

◆ write_reg16()

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

Definition at line 325 of file ADIS16497.cpp.

References DIR_WRITE, and T_STALL.

Referenced by probe(), reset(), and self_test().

Here is the caller graph for this function:

Member Data Documentation

◆ _bad_transfers

perf_counter_t ADIS16497::_bad_transfers
private

Definition at line 105 of file ADIS16497.hpp.

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

◆ _px4_accel

PX4Accelerometer ADIS16497::_px4_accel
private

Definition at line 101 of file ADIS16497.hpp.

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

◆ _px4_gyro

PX4Gyroscope ADIS16497::_px4_gyro
private

Definition at line 102 of file ADIS16497.hpp.

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

◆ _sample_perf

perf_counter_t ADIS16497::_sample_perf
private

Definition at line 104 of file ADIS16497.hpp.

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


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