drivers/imu/analog_devices/adis16470: Analog Devices ADIS16470 IMU driver for CUAV x7pro

This commit is contained in:
Daniel Agar 2021-03-16 18:00:06 -04:00 committed by GitHub
parent 4092f87390
commit dd479f9cca
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
11 changed files with 899 additions and 19 deletions

View File

@ -31,6 +31,7 @@ px4_add_board(
heater
#imu # all available imu drivers
imu/analog_devices/adis16448
imu/analog_devices/adis16470
imu/bosch/bmi088
imu/invensense/icm20649
imu/invensense/icm20689
@ -117,6 +118,7 @@ px4_add_board(
work_queue
EXAMPLES
fake_gps
fake_gyro
fake_magnetometer
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
#hello

View File

@ -5,8 +5,10 @@
board_adc start
# SPI1
#adis16470 -s start
icm20689 -s -b 1 -R 2 start
if ! icm20689 -s -b 1 -R 2 start
then
adis16470 -s -b 1 -R 2 start
fi
# SPI2
rm3100 -s -b 2 start

View File

@ -250,25 +250,27 @@
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */
/* SPI */
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_3 /* PG11 */
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz))
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_6 /* PI1 */
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */
#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_3) /* PG11 */
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_2 /* PE2 */
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */
#define GPIO_SPI5_SCK GPIO_SPI5_SCK_1 /* PF7 */
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_2) /* PE2 */
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */
#define GPIO_SPI6_SCK GPIO_SPI6_SCK_1 /* PG13 */
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_2 /* PA7 */
#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_1) /* PG13 */
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_2 /* PA7 */
/* I2C */
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */

View File

@ -37,7 +37,7 @@
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::PortF, GPIO::Pin10}, SPI::DRDY{GPIO::PortE, GPIO::Pin7}), // ADIS16470
initSPIDevice(DRV_IMU_DEVTYPE_ADIS16470, SPI::CS{GPIO::PortF, GPIO::Pin10}, SPI::DRDY{GPIO::PortE, GPIO::Pin7}),
initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::PortG, GPIO::Pin6}, SPI::DRDY{GPIO::PortJ, GPIO::Pin0}),
}, {GPIO::PortE, GPIO::Pin3}),
initSPIBus(SPI::Bus::SPI2, {

View File

@ -112,10 +112,13 @@
#define DRV_ACC_DEVTYPE_FXOS8701C 0x52
#define DRV_GYR_DEVTYPE_FXAS2100C 0x54
#define DRV_IMU_DEVTYPE_ADIS16448 0x57
#define DRV_BARO_DEVTYPE_LPS22HB 0x58
#define DRV_IMU_DEVTYPE_ADIS16470 0x58
#define DRV_IMU_DEVTYPE_ADIS16477 0x59
#define DRV_BARO_DEVTYPE_LPS22HB 0x60
#define DRV_ACC_DEVTYPE_LSM303AGR 0x61
#define DRV_MAG_DEVTYPE_LSM303AGR 0x62
#define DRV_IMU_DEVTYPE_ADIS16497 0x63

View File

@ -32,3 +32,4 @@
############################################################################
add_subdirectory(adis16448)
add_subdirectory(adis16470)

View File

@ -0,0 +1,462 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "ADIS16470.hpp"
using namespace time_literals;
static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
{
return (msb << 8u) | lsb;
}
ADIS16470::ADIS16470(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_drdy_gpio_t drdy_gpio) :
SPI(DRV_IMU_DEVTYPE_ADIS16470, MODULE_NAME, bus, device, SPIDEV_MODE3, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_drdy_gpio(drdy_gpio),
_px4_accel(get_device_id(), rotation),
_px4_gyro(get_device_id(), rotation)
{
_debug_enabled = true;
}
ADIS16470::~ADIS16470()
{
perf_free(_bad_register_perf);
perf_free(_bad_transfer_perf);
}
int ADIS16470::init()
{
int ret = SPI::init();
if (ret != PX4_OK) {
DEVICE_DEBUG("SPI::init failed (%i)", ret);
return ret;
}
return Reset() ? 0 : -1;
}
bool ADIS16470::Reset()
{
_state = STATE::RESET;
DataReadyInterruptDisable();
ScheduleClear();
ScheduleNow();
return true;
}
void ADIS16470::exit_and_cleanup()
{
DataReadyInterruptDisable();
I2CSPIDriverBase::exit_and_cleanup();
}
void ADIS16470::print_status()
{
I2CSPIDriverBase::print_status();
perf_print_counter(_reset_perf);
perf_print_counter(_perf_crc_bad);
perf_print_counter(_bad_register_perf);
perf_print_counter(_bad_transfer_perf);
}
int ADIS16470::probe()
{
// Power-On Start-Up Time 205 ms
if (hrt_absolute_time() < 205_ms) {
PX4_WARN("Power-On Start-Up Time is 205 ms");
}
const uint16_t PROD_ID = RegisterRead(Register::PROD_ID);
if (PROD_ID != Product_identification) {
DEVICE_DEBUG("unexpected PROD_ID 0x%02x", PROD_ID);
return PX4_ERROR;
}
const uint16_t SERIAL_NUM = RegisterRead(Register::SERIAL_NUM);
const uint16_t FIRM_REV = RegisterRead(Register::FIRM_REV);
const uint16_t FIRM_DM = RegisterRead(Register::FIRM_DM);
const uint16_t FIRM_Y = RegisterRead(Register::FIRM_Y);
PX4_INFO("Serial Number: 0x%X, Firmware revision: 0x%X Date: Y %X DM %X", SERIAL_NUM, FIRM_REV, FIRM_Y, FIRM_DM);
return PX4_OK;
}
void ADIS16470::RunImpl()
{
const hrt_abstime now = hrt_absolute_time();
switch (_state) {
case STATE::RESET:
perf_count(_reset_perf);
// GLOB_CMD: software reset
RegisterWrite(Register::GLOB_CMD, GLOB_CMD_BIT::Software_reset);
_reset_timestamp = now;
_failure_count = 0;
_state = STATE::WAIT_FOR_RESET;
ScheduleDelayed(193_ms); // 193 ms Software Reset Recovery Time
break;
case STATE::WAIT_FOR_RESET:
if (_self_test_passed) {
if ((RegisterRead(Register::PROD_ID) == Product_identification)) {
// if reset succeeded then configure
_state = STATE::CONFIGURE;
ScheduleNow();
} else {
// RESET not complete
if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) {
PX4_DEBUG("Reset failed, retrying");
_state = STATE::RESET;
ScheduleDelayed(100_ms);
} else {
PX4_DEBUG("Reset not complete, check again in 100 ms");
ScheduleDelayed(100_ms);
}
}
} else {
RegisterWrite(Register::GLOB_CMD, GLOB_CMD_BIT::Sensor_self_test);
_state = STATE::SELF_TEST_CHECK;
ScheduleDelayed(14_ms); // Self Test Time
}
break;
case STATE::SELF_TEST_CHECK: {
// read DIAG_STAT to check result
const uint16_t DIAG_STAT = RegisterRead(Register::DIAG_STAT);
if (DIAG_STAT != 0) {
PX4_ERR("DIAG_STAT: %#X", DIAG_STAT);
} else {
PX4_DEBUG("self test passed");
_self_test_passed = true;
_state = STATE::RESET;
ScheduleNow();
}
}
break;
case STATE::CONFIGURE:
if (Configure()) {
// if configure succeeded then start reading
_state = STATE::READ;
if (DataReadyInterruptConfigure()) {
_data_ready_interrupt_enabled = true;
// backup schedule as a watchdog timeout
ScheduleDelayed(100_ms);
} else {
_data_ready_interrupt_enabled = false;
ScheduleOnInterval(SAMPLE_INTERVAL_US, SAMPLE_INTERVAL_US);
}
} else {
// CONFIGURE not complete
if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) {
PX4_DEBUG("Configure failed, resetting");
_state = STATE::RESET;
} else {
PX4_DEBUG("Configure failed, retrying");
}
ScheduleDelayed(100_ms);
}
break;
case STATE::READ: {
if (_data_ready_interrupt_enabled) {
// push backup schedule back
ScheduleDelayed(SAMPLE_INTERVAL_US * 2);
}
bool success = false;
struct BurstRead {
uint8_t cmd[2];
uint8_t DIAG_STAT[2];
uint8_t X_GYRO_OUT[2];
uint8_t Y_GYRO_OUT[2];
uint8_t Z_GYRO_OUT[2];
uint8_t X_ACCL_OUT[2];
uint8_t Y_ACCL_OUT[2];
uint8_t Z_ACCL_OUT[2];
uint8_t TEMP_OUT[2];
uint8_t DATA_CNTR[2];
uint8_t _padding; // 16 bit SPI mode
uint8_t checksum;
} buffer{};
// ADIS16470 burst report should be 176 bits
static_assert(sizeof(BurstRead) == (176 / 8), "ADIS16470 report not 176 bits");
buffer.cmd[0] = static_cast<uint16_t>(Register::GLOB_CMD);// << 8;
set_frequency(SPI_SPEED_BURST);
//if (transferhword((uint16_t *)&buffer, (uint16_t *)&buffer, sizeof(buffer) / sizeof(uint16_t)) == PX4_OK) {
if (transfer((uint8_t *)&buffer, (uint8_t *)&buffer, sizeof(buffer)) == PX4_OK) {
// Calculate checksum and compare
// Checksum = DIAG_STAT, Bits[15:8] + DIAG_STAT, Bits[7:0] +
// X_GYRO_OUT, Bits[15:8] + X_GYRO_OUT, Bits[7:0] +
// Y_GYRO_OUT, Bits[15:8] + Y_GYRO_OUT, Bits[7:0] +
// Z_GYRO_OUT, Bits[15:8] + Z_GYRO_OUT, Bits[7:0] +
// X_ACCL_OUT, Bits[15:8] + X_ACCL_OUT, Bits[7:0] +
// Y_ACCL_OUT, Bits[15:8] + Y_ACCL_OUT, Bits[7:0] +
// Z_ACCL_OUT, Bits[15:8] + Z_ACCL_OUT, Bits[7:0] +
// TEMP_OUT, Bits[15:8] + TEMP_OUT, Bits[7:0] +
// DATA_CNTR, Bits[15:8] + DATA_CNTR, Bits[7:0]
uint8_t *checksum_helper = (uint8_t *)&buffer.DIAG_STAT;
uint8_t checksum = 0;
for (int i = 0; i < 18; i++) {
checksum += checksum_helper[i];
}
if (buffer.checksum != checksum) {
//PX4_DEBUG("adis_report.checksum: %X vs calculated: %X", buffer.checksum, checksum);
perf_count(_bad_transfer_perf);
}
uint16_t DIAG_STAT = combine(buffer.DIAG_STAT[0], buffer.DIAG_STAT[1]);
if (DIAG_STAT != DIAG_STAT_BIT::Data_path_overrun) {
// Data path overrun. A 1 indicates that one of the
// data paths have experienced an overrun condition.
// If this occurs, initiate a reset,
//Reset();
//return;
}
// Check all Status/Error Flag Indicators (DIAG_STAT)
if (DIAG_STAT != 0) {
perf_count(_bad_transfer_perf);
}
// temperature 1 LSB = 0.1°C
const float temperature = combine(buffer.TEMP_OUT[0], buffer.TEMP_OUT[1]) * 0.1f;
_px4_accel.set_temperature(temperature);
_px4_gyro.set_temperature(temperature);
int16_t accel_x = combine(buffer.X_ACCL_OUT[0], buffer.X_ACCL_OUT[1]);
int16_t accel_y = combine(buffer.Y_ACCL_OUT[0], buffer.Y_ACCL_OUT[1]);
int16_t accel_z = combine(buffer.Z_ACCL_OUT[0], buffer.Z_ACCL_OUT[1]);
// sensor's frame is +x forward, +y left, +z up
// flip y & z to publish right handed with z down (x forward, y right, z down)
accel_y = (accel_y == INT16_MIN) ? INT16_MAX : -accel_y;
accel_z = (accel_z == INT16_MIN) ? INT16_MAX : -accel_z;
_px4_accel.update(now, accel_x, accel_y, accel_z);
int16_t gyro_x = combine(buffer.X_GYRO_OUT[0], buffer.X_GYRO_OUT[1]);
int16_t gyro_y = combine(buffer.Y_GYRO_OUT[0], buffer.Y_GYRO_OUT[1]);
int16_t gyro_z = combine(buffer.Z_GYRO_OUT[0], buffer.Z_GYRO_OUT[1]);
// sensor's frame is +x forward, +y left, +z up
// flip y & z to publish right handed with z down (x forward, y right, z down)
gyro_y = (gyro_y == INT16_MIN) ? INT16_MAX : -gyro_y;
gyro_z = (gyro_z == INT16_MIN) ? INT16_MAX : -gyro_z;
_px4_gyro.update(now, gyro_x, gyro_y, gyro_z);
success = true;
if (_failure_count > 0) {
_failure_count--;
}
} else {
perf_count(_bad_transfer_perf);
}
if (!success) {
_failure_count++;
// full reset if things are failing consistently
if (_failure_count > 10) {
Reset();
return;
}
}
if (!success || hrt_elapsed_time(&_last_config_check_timestamp) > 100_ms) {
// check configuration registers periodically or immediately following any failure
if (RegisterCheck(_register_cfg[_checked_register])) {
_last_config_check_timestamp = now;
_checked_register = (_checked_register + 1) % size_register_cfg;
} else {
// register check failed, force reset
perf_count(_bad_register_perf);
Reset();
}
}
}
break;
}
}
bool ADIS16470::Configure()
{
// first set and clear all configured register bits
for (const auto &reg_cfg : _register_cfg) {
RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits);
}
// now check that all are configured
bool success = true;
for (const auto &reg_cfg : _register_cfg) {
if (!RegisterCheck(reg_cfg)) {
success = false;
}
}
_px4_accel.set_scale(CONSTANTS_ONE_G / 2048.f);
_px4_accel.set_range(40.f * CONSTANTS_ONE_G);
_px4_gyro.set_scale(math::radians(2000.f / 32768.f));
_px4_gyro.set_range(math::radians(2000.f));
_px4_accel.set_scale(1.25f * CONSTANTS_ONE_G / 1000.0f); // accel 1.25 mg/LSB
_px4_gyro.set_scale(math::radians(0.025f)); // gyro 0.025 °/sec/LSB
return success;
}
int ADIS16470::DataReadyInterruptCallback(int irq, void *context, void *arg)
{
static_cast<ADIS16470 *>(arg)->DataReady();
return 0;
}
void ADIS16470::DataReady()
{
ScheduleNow();
}
bool ADIS16470::DataReadyInterruptConfigure()
{
if (_drdy_gpio == 0) {
return false;
}
// Setup data ready on falling edge
return px4_arch_gpiosetevent(_drdy_gpio, false, true, false, &DataReadyInterruptCallback, this) == 0;
}
bool ADIS16470::DataReadyInterruptDisable()
{
if (_drdy_gpio == 0) {
return false;
}
return px4_arch_gpiosetevent(_drdy_gpio, false, false, false, nullptr, nullptr) == 0;
}
bool ADIS16470::RegisterCheck(const register_config_t &reg_cfg)
{
bool success = true;
const uint16_t reg_value = RegisterRead(reg_cfg.reg);
if (reg_cfg.set_bits && ((reg_value & reg_cfg.set_bits) != reg_cfg.set_bits)) {
PX4_DEBUG("0x%02hhX: 0x%02hhX (0x%02hhX not set)", (uint8_t)reg_cfg.reg, reg_value, reg_cfg.set_bits);
success = false;
}
if (reg_cfg.clear_bits && ((reg_value & reg_cfg.clear_bits) != 0)) {
PX4_DEBUG("0x%02hhX: 0x%02hhX (0x%02hhX not cleared)", (uint8_t)reg_cfg.reg, reg_value, reg_cfg.clear_bits);
success = false;
}
return success;
}
uint16_t ADIS16470::RegisterRead(Register reg)
{
set_frequency(SPI_SPEED);
uint16_t cmd[1];
cmd[0] = (static_cast<uint16_t>(reg) << 8);
transferhword(cmd, nullptr, 1);
px4_udelay(SPI_STALL_PERIOD);
transferhword(nullptr, cmd, 1);
return cmd[0];
}
void ADIS16470::RegisterWrite(Register reg, uint16_t value)
{
set_frequency(SPI_SPEED);
uint16_t cmd[2];
cmd[0] = (((static_cast<uint16_t>(reg)) | DIR_WRITE) << 8) | ((0x00FF & value));
cmd[1] = (((static_cast<uint16_t>(reg) + 1) | DIR_WRITE) << 8) | ((0xFF00 & value) >> 8);
transferhword(cmd, nullptr, 1);
px4_udelay(SPI_STALL_PERIOD);
transferhword(cmd + 1, nullptr, 1);
}
void ADIS16470::RegisterSetAndClearBits(Register reg, uint16_t setbits, uint16_t clearbits)
{
const uint16_t orig_val = RegisterRead(reg);
uint16_t val = (orig_val & ~clearbits) | setbits;
if (orig_val != val) {
RegisterWrite(reg, val);
}
}

View File

@ -0,0 +1,129 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file ADIS16470.hpp
*
* Driver for the Analog Devices ADIS16470 connected via SPI.
*
*/
#pragma once
#include "Analog_Devices_ADIS16470_registers.hpp"
#include <drivers/drv_hrt.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>
using namespace Analog_Devices_ADIS16470;
class ADIS16470 : public device::SPI, public I2CSPIDriver<ADIS16470>
{
public:
ADIS16470(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_drdy_gpio_t drdy_gpio);
~ADIS16470() override;
static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
int runtime_instance);
static void print_usage();
void RunImpl();
int init() override;
void print_status() override;
private:
void exit_and_cleanup() override;
struct register_config_t {
Register reg;
uint16_t set_bits{0};
uint16_t clear_bits{0};
};
int probe() override;
bool Reset();
bool Configure();
static int DataReadyInterruptCallback(int irq, void *context, void *arg);
void DataReady();
bool DataReadyInterruptConfigure();
bool DataReadyInterruptDisable();
bool RegisterCheck(const register_config_t &reg_cfg);
uint16_t RegisterRead(Register reg);
void RegisterWrite(Register reg, uint16_t value);
void RegisterSetAndClearBits(Register reg, uint16_t setbits, uint16_t clearbits);
const spi_drdy_gpio_t _drdy_gpio;
PX4Accelerometer _px4_accel;
PX4Gyroscope _px4_gyro;
perf_counter_t _reset_perf{perf_alloc(PC_COUNT, MODULE_NAME": reset")};
perf_counter_t _perf_crc_bad{perf_counter_t(perf_alloc(PC_COUNT, MODULE_NAME": CRC16 bad"))};
perf_counter_t _bad_register_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad register")};
perf_counter_t _bad_transfer_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad transfer")};
hrt_abstime _reset_timestamp{0};
hrt_abstime _last_config_check_timestamp{0};
int _failure_count{0};
bool _data_ready_interrupt_enabled{false};
bool _self_test_passed{false};
enum class STATE : uint8_t {
RESET,
WAIT_FOR_RESET,
SELF_TEST_CHECK,
CONFIGURE,
READ,
} _state{STATE::RESET};
uint8_t _checked_register{0};
static constexpr uint8_t size_register_cfg{1};
register_config_t _register_cfg[size_register_cfg] {
// Register | Set bits, Clear bits
{ Register::MSC_CTRL, 0, MSC_CTRL_BIT::DR_polarity },
};
};

View File

@ -0,0 +1,126 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file Analog_Devices_ADIS16470_registers.hpp
*
* Analog Devices ADIS16470 registers.
*
*/
#pragma once
#include <cstdint>
// TODO: move to a central header
static constexpr uint16_t Bit0 = (1 << 0);
static constexpr uint16_t Bit1 = (1 << 1);
static constexpr uint16_t Bit2 = (1 << 2);
static constexpr uint16_t Bit3 = (1 << 3);
static constexpr uint16_t Bit4 = (1 << 4);
static constexpr uint16_t Bit5 = (1 << 5);
static constexpr uint16_t Bit6 = (1 << 6);
static constexpr uint16_t Bit7 = (1 << 7);
static constexpr uint16_t Bit8 = (1 << 8);
static constexpr uint16_t Bit9 = (1 << 9);
static constexpr uint16_t Bit10 = (1 << 10);
static constexpr uint16_t Bit11 = (1 << 11);
static constexpr uint16_t Bit12 = (1 << 12);
static constexpr uint16_t Bit13 = (1 << 13);
static constexpr uint16_t Bit14 = (1 << 14);
static constexpr uint16_t Bit15 = (1 << 15);
namespace Analog_Devices_ADIS16470
{
static constexpr uint32_t SPI_SPEED = 2 * 1000 * 1000; // 2 MHz SPI serial interface
static constexpr uint32_t SPI_SPEED_BURST = 1 * 1000 * 1000; // 1 MHz SPI serial interface for burst read
static constexpr uint32_t SPI_STALL_PERIOD = 16; // 16 us Stall period between data
static constexpr uint16_t DIR_WRITE = 0x80;
static constexpr uint16_t Product_identification = 0x4056;
static constexpr uint32_t SAMPLE_INTERVAL_US = 500; // 2000 Hz
enum class Register : uint16_t {
DIAG_STAT = 0x02,
FILT_CTRL = 0x5C,
MSC_CTRL = 0x60,
GLOB_CMD = 0x68,
FIRM_REV = 0x6C, // Identification, firmware revision
FIRM_DM = 0x6E, // Identification, date code, day and month
FIRM_Y = 0x70, // Identification, date code, year
PROD_ID = 0x72, // Identification, part number
SERIAL_NUM = 0x74, // Identification, serial number
FLSHCNT_LOW = 0x7C, // Output, flash memory write cycle counter, lower word
FLSHCNT_HIGH = 0x7E, // Output, flash memory write cycle counter, upper word
};
// DIAG_STAT
enum DIAG_STAT_BIT : uint16_t {
Clock_error = Bit7, // A 1 indicates that the internal data sampling clock
Memory_failure = Bit6, // A 1 indicates a failure in the flash memory test
Sensor_failure = Bit5, // A 1 indicates failure of at least one sensor, at the conclusion of the self test
Standby_mode = Bit4, // A 1 indicates that the voltage across VDD and GND is <2.8 V, which causes data processing to stop
SPI_communication_error = Bit3, // A 1 indicates that the total number of SCLK cycles is not equal to an integer multiple of 16
Flash_memory_update_failure = Bit2, // A 1 indicates that the most recent flash memory update failed
Data_path_overrun = Bit1, // A 1 indicates that one of the data paths have experienced an overrun condition
};
// FILT_CTRL
enum FILT_CTRL_BIT : uint16_t {
};
// MSC_CTRL
enum MSC_CTRL_BIT : uint16_t {
DR_polarity = Bit0, // 1 = active high when data is valid
};
// GLOB_CMD
enum GLOB_CMD_BIT : uint16_t {
Software_reset = Bit7,
Flash_memory_test = Bit4,
Sensor_self_test = Bit2,
};
} // namespace Analog_Devices_ADIS16470

View File

@ -0,0 +1,47 @@
############################################################################
#
# Copyright (c) 2021 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__imu__analog_devices__adis16470
MAIN adis16470
COMPILE_FLAGS
SRCS
ADIS16470.cpp
ADIS16470.hpp
adis16470_main.cpp
Analog_Devices_ADIS16470_registers.hpp
DEPENDS
drivers_accelerometer
drivers_gyroscope
px4_work_queue
)

View File

@ -0,0 +1,106 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "ADIS16470.hpp"
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/module.h>
void ADIS16470::print_usage()
{
PRINT_MODULE_USAGE_NAME("adis16470", "driver");
PRINT_MODULE_USAGE_SUBCATEGORY("imu");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true);
PRINT_MODULE_USAGE_PARAM_INT('R', 0, 0, 35, "Rotation", true);
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
}
I2CSPIDriverBase *ADIS16470::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
int runtime_instance)
{
ADIS16470 *instance = new ADIS16470(iterator.configuredBusOption(), iterator.bus(), iterator.devid(), cli.rotation,
cli.bus_frequency, iterator.DRDYGPIO());
if (!instance) {
PX4_ERR("alloc failed");
return nullptr;
}
if (OK != instance->init()) {
delete instance;
return nullptr;
}
return instance;
}
extern "C" int adis16470_main(int argc, char *argv[])
{
int ch;
using ThisDriver = ADIS16470;
BusCLIArguments cli{false, true};
cli.default_spi_frequency = SPI_SPEED;
while ((ch = cli.getopt(argc, argv, "R:")) != EOF) {
switch (ch) {
case 'R':
cli.rotation = (enum Rotation)atoi(cli.optarg());
break;
}
}
const char *verb = cli.optarg();
if (!verb) {
ThisDriver::print_usage();
return -1;
}
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_IMU_DEVTYPE_ADIS16470);
if (!strcmp(verb, "start")) {
return ThisDriver::module_start(cli, iterator);
}
if (!strcmp(verb, "stop")) {
return ThisDriver::module_stop(iterator);
}
if (!strcmp(verb, "status")) {
return ThisDriver::module_status(iterator);
}
ThisDriver::print_usage();
return -1;
}