| PX4 Firmware
    PX4 Autopilot Software http://px4.io | 
#include <ADIS16448.h>
| 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} | 
Definition at line 101 of file ADIS16448.h.
| 
 | 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.
| ADIS16448::ADIS16448 | ( | int | bus, | 
| uint32_t | device, | ||
| enum Rotation | rotation | ||
| ) | 
Definition at line 40 of file ADIS16448.cpp.
References _px4_accel, _px4_baro, _px4_gyro, _px4_mag, ADIS16448_ACCEL_SENSITIVITY, ADIS16448_GYRO_INITIAL_SENSITIVITY, ADIS16448_MAG_SENSITIVITY, DRV_ACC_DEVTYPE_ADIS16448, DRV_GYR_DEVTYPE_ADIS16448, DRV_MAG_DEVTYPE_ADIS16448, PX4Barometer::set_device_type(), PX4Magnetometer::set_device_type(), PX4Accelerometer::set_device_type(), PX4Gyroscope::set_device_type(), PX4Magnetometer::set_external(), PX4Magnetometer::set_scale(), PX4Accelerometer::set_scale(), and PX4Gyroscope::set_scale().
| 
 | virtual | 
Definition at line 60 of file ADIS16448.cpp.
References _perf_bad_transfer, _perf_crc_bad, _perf_read, _perf_transfer, perf_free(), and stop().
| 
 | virtual | 
Definition at line 73 of file ADIS16448.cpp.
References DEVICE_DEBUG, ToneAlarmInterface::init(), measure(), OK, and start().
Referenced by adis16448::start().
| 
 | 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().
| 
 | private | 
Modify a register in the ADIS16448 Bits are cleared before bits are set.
| reg | The register to modify. | 
| clearbits | Bits in the register to clear. | 
| setbits | Bits 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().
| 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().
| 
 | 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().
| 
 | private | 
Read a register from the ADIS16448.
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().
| 
 | 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().
| 
 | 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.
| arg | Instance pointer for the driver that is polling. | 
Definition at line 533 of file ADIS16448.cpp.
References measure().
| 
 | 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().
| 
 | private | 
Set low pass filter frequency.
Definition at line 268 of file ADIS16448.cpp.
References ADIS16448_SENS_AVG, modify_reg16(), and read_reg16().
| 
 | 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().
| 
 | 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().
| 
 | private | 
Start automatic measurement.
Definition at line 365 of file ADIS16448.cpp.
References _sample_rate, and stop().
Referenced by init().
| 
 | private | 
Stop automatic measurement.
Definition at line 375 of file ADIS16448.cpp.
Referenced by start(), and ~ADIS16448().
| 
 | private | 
Write a register in the ADIS16448.
| reg | The register to write. | 
| value | The 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().
| 
 | private | 
Definition at line 215 of file ADIS16448.h.
Referenced by measure(), print_info(), and ~ADIS16448().
| 
 | private | 
Definition at line 216 of file ADIS16448.h.
Referenced by measure(), print_info(), and ~ADIS16448().
| 
 | private | 
Definition at line 213 of file ADIS16448.h.
Referenced by measure(), print_info(), and ~ADIS16448().
| 
 | private | 
Definition at line 214 of file ADIS16448.h.
Referenced by measure(), print_info(), and ~ADIS16448().
| 
 | private | 
Definition at line 209 of file ADIS16448.h.
Referenced by probe().
| 
 | private | 
Definition at line 204 of file ADIS16448.h.
Referenced by ADIS16448(), measure(), print_info(), and set_sample_rate().
| 
 | private | 
Definition at line 205 of file ADIS16448.h.
Referenced by ADIS16448(), measure(), and print_info().
| 
 | private | 
Definition at line 206 of file ADIS16448.h.
Referenced by ADIS16448(), measure(), print_info(), set_gyro_dyn_range(), and set_sample_rate().
| 
 | private | 
Definition at line 207 of file ADIS16448.h.
Referenced by ADIS16448(), measure(), and print_info().
| 
 | staticprivate | 
Definition at line 211 of file ADIS16448.h.