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

#include <ADIS16448.h>

Inheritance diagram for ADIS16448:
Collaboration diagram for ADIS16448:

Public Member Functions

 ADIS16448 (int bus, uint32_t device, enum Rotation rotation)
 
virtual ~ADIS16448 ()
 
virtual int init ()
 
void print_info ()
 Diagnostics - print some basic information about the driver and sensor. More...
 

Protected Member Functions

virtual int probe ()
 

Private Types

enum  Register : uint8_t {
  Register::GPIO_CTRL = 0x32, Register::MSC_CTRL = 0x34, Register::SMPL_PRD = 0x36, Register::SENS_AVG = 0x38,
  Register::DIAG_STAT = 0x3C, Register::GLOB_CMD = 0x3E, Register::PRODUCT_ID = 0x56, Register::SERIAL_NUMBER = 0x58
}
 

Private Member Functions

int measure ()
 Fetch measurements from the sensor and update the report buffers. More...
 
void Run ()
 Static trampoline from the hrt_call context; because we don't have a generic hrt wrapper yet. More...
 
void modify_reg16 (unsigned reg, uint16_t clearbits, uint16_t setbits)
 Modify a register in the ADIS16448 Bits are cleared before bits are set. More...
 
bool reset ()
 Resets the chip and measurements ranges. More...
 
bool self_test ()
 
uint16_t read_reg16 (unsigned reg)
 Read a register from the ADIS16448. More...
 
void write_reg16 (unsigned reg, uint16_t value)
 Write a register in the ADIS16448. More...
 
bool set_dlpf_filter (uint16_t frequency_hz)
 Set low pass filter frequency. More...
 
bool set_gyro_dyn_range (uint16_t desired_gyro_dyn_range)
 Set the gyroscope dynamic range. More...
 
bool set_sample_rate (uint16_t desired_sample_rate_hz)
 Set sample rate (approximate) - 1kHz to 5Hz. More...
 
void start ()
 Start automatic measurement. More...
 
void stop ()
 Stop automatic measurement. More...
 

Private Attributes

PX4Accelerometer _px4_accel
 
PX4Barometer _px4_baro
 
PX4Gyroscope _px4_gyro
 
PX4Magnetometer _px4_mag
 
uint16_t _product_ID {0}
 
perf_counter_t _perf_read {perf_counter_t(perf_alloc(PC_ELAPSED, "ADIS16448: read"))}
 
perf_counter_t _perf_transfer {perf_counter_t(perf_alloc(PC_ELAPSED, "ADIS16448: transfer"))}
 
perf_counter_t _perf_bad_transfer {perf_counter_t(perf_alloc(PC_COUNT, "ADIS16448: bad transfers"))}
 
perf_counter_t _perf_crc_bad {perf_counter_t(perf_alloc(PC_COUNT, "ADIS16448: CRC16 bad"))}
 

Static Private Attributes

static constexpr float _sample_rate {ADIS16448_ACCEL_GYRO_UPDATE_RATE}
 

Detailed Description

Definition at line 101 of file ADIS16448.h.

Member Enumeration Documentation

◆ Register

enum ADIS16448::Register : uint8_t
strongprivate
Enumerator
GPIO_CTRL 
MSC_CTRL 
SMPL_PRD 
SENS_AVG 
DIAG_STAT 
GLOB_CMD 
PRODUCT_ID 
SERIAL_NUMBER 

Definition at line 119 of file ADIS16448.h.

Constructor & Destructor Documentation

◆ ADIS16448()

◆ ~ADIS16448()

ADIS16448::~ADIS16448 ( )
virtual

Definition at line 60 of file ADIS16448.cpp.

References _perf_bad_transfer, _perf_crc_bad, _perf_read, _perf_transfer, perf_free(), and stop().

Here is the call graph for this function:

Member Function Documentation

◆ init()

int ADIS16448::init ( )
virtual

Definition at line 73 of file ADIS16448.cpp.

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

Referenced by adis16448::start().

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

◆ measure()

int ADIS16448::measure ( )
private

Fetch measurements from the sensor and update the report buffers.

Definition at line 443 of file ADIS16448.cpp.

References _perf_bad_transfer, _perf_crc_bad, _perf_read, _perf_transfer, _px4_accel, _px4_baro, _px4_gyro, _px4_mag, ADIS16448_BARO_SENSITIVITY, ADIS16448_GLOB_CMD, ComputeCRC16(), convert12BitToINT16(), DIR_READ, f(), hrt_absolute_time(), hrt_abstime, OK, perf_begin(), perf_count(), perf_end(), perf_event_count(), PX4Barometer::set_error_count(), PX4Magnetometer::set_error_count(), PX4Accelerometer::set_error_count(), PX4Gyroscope::set_error_count(), PX4Barometer::set_temperature(), PX4Magnetometer::set_temperature(), PX4Accelerometer::set_temperature(), PX4Gyroscope::set_temperature(), PX4Barometer::update(), PX4Magnetometer::update(), PX4Accelerometer::update(), and PX4Gyroscope::update().

Referenced by init(), and Run().

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

◆ modify_reg16()

void ADIS16448::modify_reg16 ( unsigned  reg,
uint16_t  clearbits,
uint16_t  setbits 
)
private

Modify a register in the ADIS16448 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 327 of file ADIS16448.cpp.

References read_reg16(), and write_reg16().

Referenced by probe(), set_dlpf_filter(), set_gyro_dyn_range(), and set_sample_rate().

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

◆ print_info()

void ADIS16448::print_info ( )

Diagnostics - print some basic information about the driver and sensor.

Definition at line 313 of file ADIS16448.cpp.

References _perf_bad_transfer, _perf_crc_bad, _perf_read, _perf_transfer, _px4_accel, _px4_baro, _px4_gyro, _px4_mag, perf_print_counter(), PX4Barometer::print_status(), PX4Magnetometer::print_status(), PX4Accelerometer::print_status(), and PX4Gyroscope::print_status().

Referenced by adis16448::status().

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

◆ probe()

int ADIS16448::probe ( )
protectedvirtual

Definition at line 195 of file ADIS16448.cpp.

References _product_ID, ADIS16334_SERIAL_NUMBER, ADIS16448_GPIO_CTRL, ADIS16448_Product, ADIS16448_PRODUCT_ID, DEVICE_DEBUG, modify_reg16(), OK, read_reg16(), and reset().

Here is the call graph for this function:

◆ read_reg16()

uint16_t ADIS16448::read_reg16 ( unsigned  reg)
private

Read a register from the ADIS16448.

  • reg The register to read.
    Returns
    Returns the register value.

Definition at line 336 of file ADIS16448.cpp.

References DIR_READ, and T_STALL.

Referenced by modify_reg16(), probe(), self_test(), set_dlpf_filter(), set_gyro_dyn_range(), and set_sample_rate().

Here is the caller graph for this function:

◆ reset()

bool ADIS16448::reset ( )
private

Resets the chip and measurements ranges.

Definition at line 97 of file ADIS16448.cpp.

References _sample_rate, ADIS16448_GLOB_CMD, ADIS16448_MSC_CTRL, self_test(), set_sample_rate(), and write_reg16().

Referenced by probe().

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

◆ Run()

void ADIS16448::Run ( )
private

Static trampoline from the hrt_call context; because we don't have a generic hrt wrapper yet.

Called by the HRT in interrupt context at the specified rate if automatic polling is enabled.

Parameters
argInstance pointer for the driver that is polling.

Definition at line 533 of file ADIS16448.cpp.

References measure().

Here is the call graph for this function:

◆ self_test()

bool ADIS16448::self_test ( )
private

Definition at line 136 of file ADIS16448.cpp.

References ADIS16448_DIAG_STAT, ADIS16448_MSC_CTRL, read_reg16(), status, and write_reg16().

Referenced by reset().

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

◆ set_dlpf_filter()

bool ADIS16448::set_dlpf_filter ( uint16_t  frequency_hz)
private

Set low pass filter frequency.

Definition at line 268 of file ADIS16448.cpp.

References ADIS16448_SENS_AVG, modify_reg16(), and read_reg16().

Here is the call graph for this function:

◆ set_gyro_dyn_range()

bool ADIS16448::set_gyro_dyn_range ( uint16_t  desired_gyro_dyn_range)
private

Set the gyroscope dynamic range.

Definition at line 284 of file ADIS16448.cpp.

References _px4_gyro, ADIS16448_SENS_AVG, BITS_GYRO_DYN_RANGE_1000_CFG, BITS_GYRO_DYN_RANGE_250_CFG, BITS_GYRO_DYN_RANGE_500_CFG, f(), M_PI_F, modify_reg16(), read_reg16(), and PX4Gyroscope::set_scale().

Here is the call graph for this function:

◆ set_sample_rate()

bool ADIS16448::set_sample_rate ( uint16_t  desired_sample_rate_hz)
private

Set sample rate (approximate) - 1kHz to 5Hz.

Definition at line 233 of file ADIS16448.cpp.

References _px4_accel, _px4_gyro, ADIS16448_SMPL_PRD, BITS_SMPL_PRD_16_TAP_CFG, BITS_SMPL_PRD_2_TAP_CFG, BITS_SMPL_PRD_4_TAP_CFG, BITS_SMPL_PRD_8_TAP_CFG, BITS_SMPL_PRD_NO_TAP_CFG, modify_reg16(), read_reg16(), PX4Accelerometer::set_sample_rate(), and PX4Gyroscope::set_sample_rate().

Referenced by reset().

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

◆ start()

void ADIS16448::start ( )
private

Start automatic measurement.

Definition at line 365 of file ADIS16448.cpp.

References _sample_rate, and stop().

Referenced by init().

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

◆ stop()

void ADIS16448::stop ( )
private

Stop automatic measurement.

Definition at line 375 of file ADIS16448.cpp.

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

Here is the caller graph for this function:

◆ write_reg16()

void ADIS16448::write_reg16 ( unsigned  reg,
uint16_t  value 
)
private

Write a register in the ADIS16448.

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

Definition at line 351 of file ADIS16448.cpp.

References DIR_WRITE, and T_STALL.

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

Here is the caller graph for this function:

Member Data Documentation

◆ _perf_bad_transfer

perf_counter_t ADIS16448::_perf_bad_transfer {perf_counter_t(perf_alloc(PC_COUNT, "ADIS16448: bad transfers"))}
private

Definition at line 215 of file ADIS16448.h.

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

◆ _perf_crc_bad

perf_counter_t ADIS16448::_perf_crc_bad {perf_counter_t(perf_alloc(PC_COUNT, "ADIS16448: CRC16 bad"))}
private

Definition at line 216 of file ADIS16448.h.

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

◆ _perf_read

perf_counter_t ADIS16448::_perf_read {perf_counter_t(perf_alloc(PC_ELAPSED, "ADIS16448: read"))}
private

Definition at line 213 of file ADIS16448.h.

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

◆ _perf_transfer

perf_counter_t ADIS16448::_perf_transfer {perf_counter_t(perf_alloc(PC_ELAPSED, "ADIS16448: transfer"))}
private

Definition at line 214 of file ADIS16448.h.

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

◆ _product_ID

uint16_t ADIS16448::_product_ID {0}
private

Definition at line 209 of file ADIS16448.h.

Referenced by probe().

◆ _px4_accel

PX4Accelerometer ADIS16448::_px4_accel
private

Definition at line 204 of file ADIS16448.h.

Referenced by ADIS16448(), measure(), print_info(), and set_sample_rate().

◆ _px4_baro

PX4Barometer ADIS16448::_px4_baro
private

Definition at line 205 of file ADIS16448.h.

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

◆ _px4_gyro

PX4Gyroscope ADIS16448::_px4_gyro
private

Definition at line 206 of file ADIS16448.h.

Referenced by ADIS16448(), measure(), print_info(), set_gyro_dyn_range(), and set_sample_rate().

◆ _px4_mag

PX4Magnetometer ADIS16448::_px4_mag
private

Definition at line 207 of file ADIS16448.h.

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

◆ _sample_rate

constexpr float ADIS16448::_sample_rate {ADIS16448_ACCEL_GYRO_UPDATE_RATE}
staticprivate

Definition at line 211 of file ADIS16448.h.

Referenced by reset(), and start().


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