diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index 135cbc3e60..762c024f0f 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -24,6 +24,7 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y CONFIG_DRIVERS_IRLOCK=y CONFIG_COMMON_LIGHT=y CONFIG_COMMON_MAGNETOMETER=y diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index 0edd9a169b..fbe8419f38 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -79,6 +79,7 @@ #define DRV_IMU_DEVTYPE_ICM20948 0x28 #define DRV_IMU_DEVTYPE_ICM42605 0x29 #define DRV_IMU_DEVTYPE_ICM42670P 0x2A +#define DRV_IMU_DEVTYPE_IIM42652 0x2B #define DRV_RNG_DEVTYPE_MB12XX 0x31 #define DRV_RNG_DEVTYPE_LL40LS 0x32 diff --git a/src/drivers/imu/invensense/iim42652/CMakeLists.txt b/src/drivers/imu/invensense/iim42652/CMakeLists.txt new file mode 100644 index 0000000000..1ce153c6f6 --- /dev/null +++ b/src/drivers/imu/invensense/iim42652/CMakeLists.txt @@ -0,0 +1,47 @@ +############################################################################ +# +# Copyright (c) 2022 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__invensense__iim42652 + MAIN iim42652 + COMPILE_FLAGS + ${MAX_CUSTOM_OPT_LEVEL} + SRCS + iim42652_main.cpp + IIM42652.cpp + IIM42652.hpp + InvenSense_IIM42652_registers.hpp + DEPENDS + px4_work_queue + drivers_accelerometer + drivers_gyroscope + ) diff --git a/src/drivers/imu/invensense/iim42652/IIM42652.cpp b/src/drivers/imu/invensense/iim42652/IIM42652.cpp new file mode 100644 index 0000000000..dabd688715 --- /dev/null +++ b/src/drivers/imu/invensense/iim42652/IIM42652.cpp @@ -0,0 +1,800 @@ +/**************************************************************************** + * + * Copyright (c) 2022 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 "IIM42652.hpp" + +using namespace time_literals; + +static constexpr int16_t combine(uint8_t msb, uint8_t lsb) +{ + return (msb << 8u) | lsb; +} + +IIM42652::IIM42652(const I2CSPIDriverConfig &config) : + SPI(config), + I2CSPIDriver(config), + _drdy_gpio(config.drdy_gpio), + _px4_accel(get_device_id(), config.rotation), + _px4_gyro(get_device_id(), config.rotation) +{ + if (config.drdy_gpio != 0) { + _drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed"); + } + + ConfigureSampleRate(_px4_gyro.get_max_rate_hz()); +} + +IIM42652::~IIM42652() +{ + perf_free(_bad_register_perf); + perf_free(_bad_transfer_perf); + perf_free(_fifo_empty_perf); + perf_free(_fifo_overflow_perf); + perf_free(_fifo_reset_perf); + perf_free(_drdy_missed_perf); +} + +int IIM42652::init() +{ + int ret = SPI::init(); + + if (ret != PX4_OK) { + DEVICE_DEBUG("SPI::init failed (%i)", ret); + return ret; + } + + return Reset() ? 0 : -1; +} + +bool IIM42652::Reset() +{ + _state = STATE::RESET; + DataReadyInterruptDisable(); + ScheduleClear(); + ScheduleNow(); + return true; +} + +void IIM42652::exit_and_cleanup() +{ + DataReadyInterruptDisable(); + I2CSPIDriverBase::exit_and_cleanup(); +} + +void IIM42652::print_status() +{ + I2CSPIDriverBase::print_status(); + + PX4_INFO("FIFO empty interval: %d us (%.1f Hz)", _fifo_empty_interval_us, 1e6 / _fifo_empty_interval_us); + + perf_print_counter(_bad_register_perf); + perf_print_counter(_bad_transfer_perf); + perf_print_counter(_fifo_empty_perf); + perf_print_counter(_fifo_overflow_perf); + perf_print_counter(_fifo_reset_perf); + perf_print_counter(_drdy_missed_perf); +} + +int IIM42652::probe() +{ + for (int i = 0; i < 3; i++) { + uint8_t whoami = RegisterRead(Register::BANK_0::WHO_AM_I); + + if (whoami == WHOAMI) { + return PX4_OK; + + } else { + DEVICE_DEBUG("unexpected WHO_AM_I 0x%02x", whoami); + + uint8_t reg_bank_sel = RegisterRead(Register::BANK_0::REG_BANK_SEL); + int bank = reg_bank_sel >> 4; + + if (bank >= 1 && bank <= 3) { + DEVICE_DEBUG("incorrect register bank for WHO_AM_I REG_BANK_SEL:0x%02x, bank:%d", reg_bank_sel, bank); + // force bank selection and retry + SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_0, true); + } + } + } + + return PX4_ERROR; +} + +void IIM42652::RunImpl() +{ + const hrt_abstime now = hrt_absolute_time(); + + switch (_state) { + case STATE::RESET: + // DEVICE_CONFIG: Software reset configuration + RegisterWrite(Register::BANK_0::DEVICE_CONFIG, DEVICE_CONFIG_BIT::SOFT_RESET_CONFIG); + _reset_timestamp = now; + _failure_count = 0; + _state = STATE::WAIT_FOR_RESET; + ScheduleDelayed(1_ms); // wait 1 ms for soft reset to be effective + break; + + case STATE::WAIT_FOR_RESET: + if ((RegisterRead(Register::BANK_0::WHO_AM_I) == WHOAMI) + && (RegisterRead(Register::BANK_0::DEVICE_CONFIG) == 0x00) + && (RegisterRead(Register::BANK_0::INT_STATUS) & INT_STATUS_BIT::RESET_DONE_INT)) { + + // Wakeup accel and gyro and schedule remaining configuration + RegisterWrite(Register::BANK_0::PWR_MGMT0, PWR_MGMT0_BIT::GYRO_MODE_LOW_NOISE | PWR_MGMT0_BIT::ACCEL_MODE_LOW_NOISE); + _state = STATE::CONFIGURE; + ScheduleDelayed(30_ms); // 30 ms gyro startup time, 10 ms accel from sleep to valid data + + } 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 10 ms"); + ScheduleDelayed(10_ms); + } + } + + break; + + case STATE::CONFIGURE: + if (Configure()) { + // if configure succeeded then start reading from FIFO + _state = STATE::FIFO_READ; + + if (DataReadyInterruptConfigure()) { + _data_ready_interrupt_enabled = true; + + // backup schedule as a watchdog timeout + ScheduleDelayed(100_ms); + + } else { + _data_ready_interrupt_enabled = false; + ScheduleOnInterval(_fifo_empty_interval_us, _fifo_empty_interval_us); + } + + FIFOReset(); + + } 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::FIFO_READ: { + hrt_abstime timestamp_sample = now; + uint8_t samples = 0; + + if (_data_ready_interrupt_enabled) { + // scheduled from interrupt if _drdy_timestamp_sample was set as expected + const hrt_abstime drdy_timestamp_sample = _drdy_timestamp_sample.fetch_and(0); + + if ((now - drdy_timestamp_sample) < _fifo_empty_interval_us) { + timestamp_sample = drdy_timestamp_sample; + samples = _fifo_gyro_samples; + + } else { + perf_count(_drdy_missed_perf); + } + + // push backup schedule back + ScheduleDelayed(_fifo_empty_interval_us * 2); + } + + if (samples == 0) { + // check current FIFO count + const uint16_t fifo_count = FIFOReadCount(); + + if (fifo_count >= FIFO::SIZE) { + FIFOReset(); + perf_count(_fifo_overflow_perf); + + } else if (fifo_count == 0) { + perf_count(_fifo_empty_perf); + + } else { + // FIFO count (size in bytes) + samples = (fifo_count / sizeof(FIFO::DATA)); + + // tolerate minor jitter, leave sample to next iteration if behind by only 1 + if (samples == _fifo_gyro_samples + 1) { + timestamp_sample -= static_cast(FIFO_SAMPLE_DT); + samples--; + } + + if (samples > FIFO_MAX_SAMPLES) { + // not technically an overflow, but more samples than we expected or can publish + FIFOReset(); + perf_count(_fifo_overflow_perf); + samples = 0; + } + } + } + + bool success = false; + + if (samples >= 1) { + if (FIFORead(timestamp_sample, samples)) { + success = true; + + if (_failure_count > 0) { + _failure_count--; + } + } + } + + 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_bank0_cfg[_checked_register_bank0]) + && RegisterCheck(_register_bank1_cfg[_checked_register_bank1]) + && RegisterCheck(_register_bank2_cfg[_checked_register_bank2]) + ) { + _last_config_check_timestamp = now; + _checked_register_bank0 = (_checked_register_bank0 + 1) % size_register_bank0_cfg; + _checked_register_bank1 = (_checked_register_bank1 + 1) % size_register_bank1_cfg; + _checked_register_bank2 = (_checked_register_bank2 + 1) % size_register_bank2_cfg; + + } else { + // register check failed, force reset + perf_count(_bad_register_perf); + Reset(); + } + } + } + + break; + } +} + +void IIM42652::ConfigureSampleRate(int sample_rate) +{ + // round down to nearest FIFO sample dt + const float min_interval = FIFO_SAMPLE_DT; + _fifo_empty_interval_us = math::max(roundf((1e6f / (float)sample_rate) / min_interval) * min_interval, min_interval); + + _fifo_gyro_samples = roundf(math::min((float)_fifo_empty_interval_us / (1e6f / GYRO_RATE), (float)FIFO_MAX_SAMPLES)); + + // recompute FIFO empty interval (us) with actual gyro sample limit + _fifo_empty_interval_us = _fifo_gyro_samples * (1e6f / GYRO_RATE); + + ConfigureFIFOWatermark(_fifo_gyro_samples); +} + +void IIM42652::ConfigureFIFOWatermark(uint8_t samples) +{ + // FIFO watermark threshold in number of bytes + const uint16_t fifo_watermark_threshold = samples * sizeof(FIFO::DATA); + + for (auto &r : _register_bank0_cfg) { + if (r.reg == Register::BANK_0::FIFO_CONFIG2) { + // FIFO_WM[7:0] FIFO_CONFIG2 + r.set_bits = fifo_watermark_threshold & 0xFF; + + } else if (r.reg == Register::BANK_0::FIFO_CONFIG3) { + // FIFO_WM[11:8] FIFO_CONFIG3 + r.set_bits = (fifo_watermark_threshold >> 8) & 0x0F; + } + } +} + +void IIM42652::SelectRegisterBank(enum REG_BANK_SEL_BIT bank, bool force) +{ + if (bank != _last_register_bank || force) { + // select BANK_0 + uint8_t cmd_bank_sel[2] {}; + cmd_bank_sel[0] = static_cast(Register::BANK_0::REG_BANK_SEL); + cmd_bank_sel[1] = bank; + transfer(cmd_bank_sel, cmd_bank_sel, sizeof(cmd_bank_sel)); + + _last_register_bank = bank; + } +} + +bool IIM42652::Configure() +{ + // first set and clear all configured register bits + for (const auto ®_cfg : _register_bank0_cfg) { + RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits); + } + + for (const auto ®_cfg : _register_bank1_cfg) { + RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits); + } + + for (const auto ®_cfg : _register_bank2_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 ®_cfg : _register_bank0_cfg) { + if (!RegisterCheck(reg_cfg)) { + success = false; + } + } + + for (const auto ®_cfg : _register_bank1_cfg) { + if (!RegisterCheck(reg_cfg)) { + success = false; + } + } + + for (const auto ®_cfg : _register_bank2_cfg) { + if (!RegisterCheck(reg_cfg)) { + success = false; + } + } + + // 20-bits data format used + // the only FSR settings that are operational are ±2000dps for gyroscope and ±16g for accelerometer + _px4_accel.set_range(16.f * CONSTANTS_ONE_G); + _px4_gyro.set_range(math::radians(2000.f)); + + return success; +} + +int IIM42652::DataReadyInterruptCallback(int irq, void *context, void *arg) +{ + static_cast(arg)->DataReady(); + return 0; +} + +void IIM42652::DataReady() +{ + _drdy_timestamp_sample.store(hrt_absolute_time()); + ScheduleNow(); +} + +bool IIM42652::DataReadyInterruptConfigure() +{ + if (_drdy_gpio == 0) { + return false; + } + + // Setup data ready on falling edge + return px4_arch_gpiosetevent(_drdy_gpio, false, true, true, &DataReadyInterruptCallback, this) == 0; +} + +bool IIM42652::DataReadyInterruptDisable() +{ + if (_drdy_gpio == 0) { + return false; + } + + return px4_arch_gpiosetevent(_drdy_gpio, false, false, false, nullptr, nullptr) == 0; +} + +template +bool IIM42652::RegisterCheck(const T ®_cfg) +{ + bool success = true; + + const uint8_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; +} + +template +uint8_t IIM42652::RegisterRead(T reg) +{ + uint8_t cmd[2] {}; + cmd[0] = static_cast(reg) | DIR_READ; + SelectRegisterBank(reg); + transfer(cmd, cmd, sizeof(cmd)); + return cmd[1]; +} + +template +void IIM42652::RegisterWrite(T reg, uint8_t value) +{ + uint8_t cmd[2] { (uint8_t)reg, value }; + SelectRegisterBank(reg); + transfer(cmd, cmd, sizeof(cmd)); +} + +template +void IIM42652::RegisterSetAndClearBits(T reg, uint8_t setbits, uint8_t clearbits) +{ + const uint8_t orig_val = RegisterRead(reg); + + uint8_t val = (orig_val & ~clearbits) | setbits; + + if (orig_val != val) { + RegisterWrite(reg, val); + } +} + +uint16_t IIM42652::FIFOReadCount() +{ + // read FIFO count + uint8_t fifo_count_buf[3] {}; + fifo_count_buf[0] = static_cast(Register::BANK_0::FIFO_COUNTH) | DIR_READ; + SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_0); + + if (transfer(fifo_count_buf, fifo_count_buf, sizeof(fifo_count_buf)) != PX4_OK) { + perf_count(_bad_transfer_perf); + return 0; + } + + return combine(fifo_count_buf[1], fifo_count_buf[2]); +} + +bool IIM42652::FIFORead(const hrt_abstime ×tamp_sample, uint8_t samples) +{ + FIFOTransferBuffer buffer{}; + const size_t transfer_size = math::min(samples * sizeof(FIFO::DATA) + 4, FIFO::SIZE); + SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_0); + + if (transfer((uint8_t *)&buffer, (uint8_t *)&buffer, transfer_size) != PX4_OK) { + perf_count(_bad_transfer_perf); + return false; + } + + if (buffer.INT_STATUS & INT_STATUS_BIT::FIFO_FULL_INT) { + perf_count(_fifo_overflow_perf); + FIFOReset(); + return false; + } + + const uint16_t fifo_count_bytes = combine(buffer.FIFO_COUNTH, buffer.FIFO_COUNTL); + + if (fifo_count_bytes >= FIFO::SIZE) { + perf_count(_fifo_overflow_perf); + FIFOReset(); + return false; + } + + const uint8_t fifo_count_samples = fifo_count_bytes / sizeof(FIFO::DATA); + + if (fifo_count_samples == 0) { + perf_count(_fifo_empty_perf); + return false; + } + + // check FIFO header in every sample + uint8_t valid_samples = 0; + + for (int i = 0; i < math::min(samples, fifo_count_samples); i++) { + bool valid = true; + + // With FIFO_ACCEL_EN and FIFO_GYRO_EN header should be 8’b_0110_10xx + const uint8_t FIFO_HEADER = buffer.f[i].FIFO_Header; + + if (FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_MSG) { + // FIFO sample empty if HEADER_MSG set + valid = false; + + } else if (!(FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_ACCEL)) { + // accel bit not set + valid = false; + + } else if (!(FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_GYRO)) { + // gyro bit not set + valid = false; + + } else if (!(FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_20)) { + // Packet does not contain a new and valid extended 20-bit data + valid = false; + + } else if (FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_ODR_ACCEL) { + // accel ODR changed + valid = false; + + } else if (FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_ODR_GYRO) { + // gyro ODR changed + valid = false; + } + + if (valid) { + valid_samples++; + + } else { + perf_count(_bad_transfer_perf); + break; + } + } + + if (valid_samples > 0) { + if (ProcessTemperature(buffer.f, valid_samples)) { + ProcessGyro(timestamp_sample, buffer.f, valid_samples); + ProcessAccel(timestamp_sample, buffer.f, valid_samples); + return true; + } + } + + return false; +} + +void IIM42652::FIFOReset() +{ + perf_count(_fifo_reset_perf); + + // SIGNAL_PATH_RESET: FIFO flush + RegisterSetBits(Register::BANK_0::SIGNAL_PATH_RESET, SIGNAL_PATH_RESET_BIT::FIFO_FLUSH); + + // reset while FIFO is disabled + _drdy_timestamp_sample.store(0); +} + +static constexpr int32_t reassemble_20bit(const uint32_t a, const uint32_t b, const uint32_t c) +{ + // 0xXXXAABBC + uint32_t high = ((a << 12) & 0x000FF000); + uint32_t low = ((b << 4) & 0x00000FF0); + uint32_t lowest = (c & 0x0000000F); + + uint32_t x = high | low | lowest; + + if (a & Bit7) { + // sign extend + x |= 0xFFF00000u; + } + + return static_cast(x); +} + +void IIM42652::ProcessAccel(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples) +{ + sensor_accel_fifo_s accel{}; + accel.timestamp_sample = timestamp_sample; + accel.samples = 0; + accel.dt = FIFO_SAMPLE_DT; + + // 18-bits of accelerometer data + bool scale_20bit = false; + + // first pass + for (int i = 0; i < samples; i++) { + // 20 bit hires mode + // Sign extension + Accel [19:12] + Accel [11:4] + Accel [3:2] (20 bit extension byte) + // Accel data is 18 bit () + int32_t accel_x = reassemble_20bit(fifo[i].ACCEL_DATA_X1, fifo[i].ACCEL_DATA_X0, + fifo[i].Ext_Accel_X_Gyro_X & 0xF0 >> 4); + int32_t accel_y = reassemble_20bit(fifo[i].ACCEL_DATA_Y1, fifo[i].ACCEL_DATA_Y0, + fifo[i].Ext_Accel_Y_Gyro_Y & 0xF0 >> 4); + int32_t accel_z = reassemble_20bit(fifo[i].ACCEL_DATA_Z1, fifo[i].ACCEL_DATA_Z0, + fifo[i].Ext_Accel_Z_Gyro_Z & 0xF0 >> 4); + + // sample invalid if -524288 + if (accel_x != -524288 && accel_y != -524288 && accel_z != -524288) { + // check if any values are going to exceed int16 limits + static constexpr int16_t max_accel = INT16_MAX; + static constexpr int16_t min_accel = INT16_MIN; + + if (accel_x >= max_accel || accel_x <= min_accel) { + scale_20bit = true; + } + + if (accel_y >= max_accel || accel_y <= min_accel) { + scale_20bit = true; + } + + if (accel_z >= max_accel || accel_z <= min_accel) { + scale_20bit = true; + } + + // shift by 2 (2 least significant bits are always 0) + accel.x[accel.samples] = accel_x / 4; + accel.y[accel.samples] = accel_y / 4; + accel.z[accel.samples] = accel_z / 4; + accel.samples++; + } + } + + if (!scale_20bit) { + // if highres enabled accel data is always 8192 LSB/g + _px4_accel.set_scale(CONSTANTS_ONE_G / 8192.f); + + } else { + // 20 bit data scaled to 16 bit (2^4) + for (int i = 0; i < samples; i++) { + // 20 bit hires mode + // Sign extension + Accel [19:12] + Accel [11:4] + Accel [3:2] (20 bit extension byte) + // Accel data is 18 bit () + int16_t accel_x = combine(fifo[i].ACCEL_DATA_X1, fifo[i].ACCEL_DATA_X0); + int16_t accel_y = combine(fifo[i].ACCEL_DATA_Y1, fifo[i].ACCEL_DATA_Y0); + int16_t accel_z = combine(fifo[i].ACCEL_DATA_Z1, fifo[i].ACCEL_DATA_Z0); + + accel.x[i] = accel_x; + accel.y[i] = accel_y; + accel.z[i] = accel_z; + } + + _px4_accel.set_scale(CONSTANTS_ONE_G / 2048.f); + } + + // correct frame for publication + for (int i = 0; i < accel.samples; i++) { + // 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.x[i] = accel.x[i]; + accel.y[i] = (accel.y[i] == INT16_MIN) ? INT16_MAX : -accel.y[i]; + accel.z[i] = (accel.z[i] == INT16_MIN) ? INT16_MAX : -accel.z[i]; + } + + _px4_accel.set_error_count(perf_event_count(_bad_register_perf) + perf_event_count(_bad_transfer_perf) + + perf_event_count(_fifo_empty_perf) + perf_event_count(_fifo_overflow_perf)); + + if (accel.samples > 0) { + _px4_accel.updateFIFO(accel); + } +} + +void IIM42652::ProcessGyro(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples) +{ + sensor_gyro_fifo_s gyro{}; + gyro.timestamp_sample = timestamp_sample; + gyro.samples = 0; + gyro.dt = FIFO_SAMPLE_DT; + + // 20-bits of gyroscope data + bool scale_20bit = false; + + // first pass + for (int i = 0; i < samples; i++) { + // 20 bit hires mode + // Gyro [19:12] + Gyro [11:4] + Gyro [3:0] (bottom 4 bits of 20 bit extension byte) + int32_t gyro_x = reassemble_20bit(fifo[i].GYRO_DATA_X1, fifo[i].GYRO_DATA_X0, fifo[i].Ext_Accel_X_Gyro_X & 0x0F); + int32_t gyro_y = reassemble_20bit(fifo[i].GYRO_DATA_Y1, fifo[i].GYRO_DATA_Y0, fifo[i].Ext_Accel_Y_Gyro_Y & 0x0F); + int32_t gyro_z = reassemble_20bit(fifo[i].GYRO_DATA_Z1, fifo[i].GYRO_DATA_Z0, fifo[i].Ext_Accel_Z_Gyro_Z & 0x0F); + + // check if any values are going to exceed int16 limits + static constexpr int16_t max_gyro = INT16_MAX; + static constexpr int16_t min_gyro = INT16_MIN; + + if (gyro_x >= max_gyro || gyro_x <= min_gyro) { + scale_20bit = true; + } + + if (gyro_y >= max_gyro || gyro_y <= min_gyro) { + scale_20bit = true; + } + + if (gyro_z >= max_gyro || gyro_z <= min_gyro) { + scale_20bit = true; + } + + gyro.x[gyro.samples] = gyro_x / 2; + gyro.y[gyro.samples] = gyro_y / 2; + gyro.z[gyro.samples] = gyro_z / 2; + gyro.samples++; + } + + if (!scale_20bit) { + // if highres enabled gyro data is always 131 LSB/dps + _px4_gyro.set_scale(math::radians(1.f / 131.f)); + + } else { + // 20 bit data scaled to 16 bit (2^4) + for (int i = 0; i < samples; i++) { + gyro.x[i] = combine(fifo[i].GYRO_DATA_X1, fifo[i].GYRO_DATA_X0); + gyro.y[i] = combine(fifo[i].GYRO_DATA_Y1, fifo[i].GYRO_DATA_Y0); + gyro.z[i] = combine(fifo[i].GYRO_DATA_Z1, fifo[i].GYRO_DATA_Z0); + } + + _px4_gyro.set_scale(math::radians(2000.f / 32768.f)); + } + + // correct frame for publication + for (int i = 0; i < gyro.samples; i++) { + // 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.x[i] = gyro.x[i]; + gyro.y[i] = (gyro.y[i] == INT16_MIN) ? INT16_MAX : -gyro.y[i]; + gyro.z[i] = (gyro.z[i] == INT16_MIN) ? INT16_MAX : -gyro.z[i]; + } + + _px4_gyro.set_error_count(perf_event_count(_bad_register_perf) + perf_event_count(_bad_transfer_perf) + + perf_event_count(_fifo_empty_perf) + perf_event_count(_fifo_overflow_perf)); + + if (gyro.samples > 0) { + _px4_gyro.updateFIFO(gyro); + } +} + +bool IIM42652::ProcessTemperature(const FIFO::DATA fifo[], const uint8_t samples) +{ + int16_t temperature[FIFO_MAX_SAMPLES]; + float temperature_sum{0}; + + int valid_samples = 0; + + for (int i = 0; i < samples; i++) { + const int16_t t = combine(fifo[i].TEMP_DATA1, fifo[i].TEMP_DATA0); + + // sample invalid if -32768 + if (t != -32768) { + temperature_sum += t; + temperature[valid_samples] = t; + valid_samples++; + } + } + + if (valid_samples > 0) { + const float temperature_avg = temperature_sum / valid_samples; + + for (int i = 0; i < valid_samples; i++) { + // temperature changing wildly is an indication of a transfer error + if (fabsf(temperature[i] - temperature_avg) > 1000) { + perf_count(_bad_transfer_perf); + return false; + } + } + + // use average temperature reading + const float TEMP_degC = (temperature_avg / TEMPERATURE_SENSITIVITY) + TEMPERATURE_OFFSET; + + if (PX4_ISFINITE(TEMP_degC)) { + _px4_accel.set_temperature(TEMP_degC); + _px4_gyro.set_temperature(TEMP_degC); + return true; + + } else { + perf_count(_bad_transfer_perf); + } + } + + return false; +} diff --git a/src/drivers/imu/invensense/iim42652/IIM42652.hpp b/src/drivers/imu/invensense/iim42652/IIM42652.hpp new file mode 100644 index 0000000000..9ba671d093 --- /dev/null +++ b/src/drivers/imu/invensense/iim42652/IIM42652.hpp @@ -0,0 +1,206 @@ +/**************************************************************************** + * + * Copyright (c) 2022 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 IIM42652.hpp + * + * Driver for the Invensense IIM42652 connected via SPI. + * + */ + +#pragma once + +#include "InvenSense_IIM42652_registers.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace InvenSense_IIM42652; + +class IIM42652 : public device::SPI, public I2CSPIDriver +{ +public: + IIM42652(const I2CSPIDriverConfig &config); + ~IIM42652() override; + + static void print_usage(); + + void RunImpl(); + + int init() override; + void print_status() override; + +private: + void exit_and_cleanup() override; + + // Sensor Configuration + static constexpr float FIFO_SAMPLE_DT{1e6f / 8000.f}; // 8000 Hz accel & gyro ODR configured + static constexpr float GYRO_RATE{1e6f / FIFO_SAMPLE_DT}; + static constexpr float ACCEL_RATE{1e6f / FIFO_SAMPLE_DT}; + + // maximum FIFO samples per transfer is limited to the size of sensor_accel_fifo/sensor_gyro_fifo + static constexpr int32_t FIFO_MAX_SAMPLES{math::min(FIFO::SIZE / sizeof(FIFO::DATA), sizeof(sensor_gyro_fifo_s::x) / sizeof(sensor_gyro_fifo_s::x[0]), sizeof(sensor_accel_fifo_s::x) / sizeof(sensor_accel_fifo_s::x[0]) * (int)(GYRO_RATE / ACCEL_RATE))}; + + // Transfer data + struct FIFOTransferBuffer { + uint8_t cmd{static_cast(Register::BANK_0::INT_STATUS) | DIR_READ}; + uint8_t INT_STATUS{0}; + uint8_t FIFO_COUNTH{0}; + uint8_t FIFO_COUNTL{0}; + FIFO::DATA f[FIFO_MAX_SAMPLES] {}; + }; + // ensure no struct padding + static_assert(sizeof(FIFOTransferBuffer) == (4 + FIFO_MAX_SAMPLES *sizeof(FIFO::DATA))); + + struct register_bank0_config_t { + Register::BANK_0 reg; + uint8_t set_bits{0}; + uint8_t clear_bits{0}; + }; + + struct register_bank1_config_t { + Register::BANK_1 reg; + uint8_t set_bits{0}; + uint8_t clear_bits{0}; + }; + + struct register_bank2_config_t { + Register::BANK_2 reg; + uint8_t set_bits{0}; + uint8_t clear_bits{0}; + }; + + int probe() override; + + bool Reset(); + + bool Configure(); + void ConfigureSampleRate(int sample_rate); + void ConfigureFIFOWatermark(uint8_t samples); + + void SelectRegisterBank(enum REG_BANK_SEL_BIT bank, bool force = false); + void SelectRegisterBank(Register::BANK_0 reg) { SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_0); } + void SelectRegisterBank(Register::BANK_1 reg) { SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_1); } + void SelectRegisterBank(Register::BANK_2 reg) { SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_2); } + + static int DataReadyInterruptCallback(int irq, void *context, void *arg); + void DataReady(); + bool DataReadyInterruptConfigure(); + bool DataReadyInterruptDisable(); + + template bool RegisterCheck(const T ®_cfg); + template uint8_t RegisterRead(T reg); + template void RegisterWrite(T reg, uint8_t value); + template void RegisterSetAndClearBits(T reg, uint8_t setbits, uint8_t clearbits); + template void RegisterSetBits(T reg, uint8_t setbits) { RegisterSetAndClearBits(reg, setbits, 0); } + template void RegisterClearBits(T reg, uint8_t clearbits) { RegisterSetAndClearBits(reg, 0, clearbits); } + + uint16_t FIFOReadCount(); + bool FIFORead(const hrt_abstime ×tamp_sample, uint8_t samples); + void FIFOReset(); + + void ProcessAccel(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples); + void ProcessGyro(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples); + bool ProcessTemperature(const FIFO::DATA fifo[], const uint8_t samples); + + const spi_drdy_gpio_t _drdy_gpio; + + PX4Accelerometer _px4_accel; + PX4Gyroscope _px4_gyro; + + 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")}; + perf_counter_t _fifo_empty_perf{perf_alloc(PC_COUNT, MODULE_NAME": FIFO empty")}; + perf_counter_t _fifo_overflow_perf{perf_alloc(PC_COUNT, MODULE_NAME": FIFO overflow")}; + perf_counter_t _fifo_reset_perf{perf_alloc(PC_COUNT, MODULE_NAME": FIFO reset")}; + perf_counter_t _drdy_missed_perf{nullptr}; + + hrt_abstime _reset_timestamp{0}; + hrt_abstime _last_config_check_timestamp{0}; + hrt_abstime _temperature_update_timestamp{0}; + int _failure_count{0}; + + enum REG_BANK_SEL_BIT _last_register_bank {REG_BANK_SEL_BIT::USER_BANK_0}; + + px4::atomic _drdy_timestamp_sample{0}; + bool _data_ready_interrupt_enabled{false}; + + enum class STATE : uint8_t { + RESET, + WAIT_FOR_RESET, + CONFIGURE, + FIFO_READ, + } _state{STATE::RESET}; + + uint16_t _fifo_empty_interval_us{1250}; // default 1250 us / 800 Hz transfer interval + int32_t _fifo_gyro_samples{static_cast(_fifo_empty_interval_us / (1000000 / GYRO_RATE))}; + + uint8_t _checked_register_bank0{0}; + static constexpr uint8_t size_register_bank0_cfg{13}; + register_bank0_config_t _register_bank0_cfg[size_register_bank0_cfg] { + // Register | Set bits, Clear bits + { Register::BANK_0::INT_CONFIG, INT_CONFIG_BIT::INT1_MODE | INT_CONFIG_BIT::INT1_DRIVE_CIRCUIT, INT_CONFIG_BIT::INT1_POLARITY }, + { Register::BANK_0::FIFO_CONFIG, FIFO_CONFIG_BIT::FIFO_MODE_STOP_ON_FULL, 0 }, + { Register::BANK_0::PWR_MGMT0, PWR_MGMT0_BIT::GYRO_MODE_LOW_NOISE | PWR_MGMT0_BIT::ACCEL_MODE_LOW_NOISE, 0 }, + { Register::BANK_0::GYRO_CONFIG0, GYRO_CONFIG0_BIT::GYRO_FS_SEL_2000_DPS | GYRO_CONFIG0_BIT::GYRO_ODR_8KHZ_SET, GYRO_CONFIG0_BIT::GYRO_ODR_8KHZ_CLEAR }, + { Register::BANK_0::ACCEL_CONFIG0, ACCEL_CONFIG0_BIT::ACCEL_FS_SEL_16G | ACCEL_CONFIG0_BIT::ACCEL_ODR_8KHZ_SET, ACCEL_CONFIG0_BIT::ACCEL_ODR_8KHZ_CLEAR }, + { Register::BANK_0::GYRO_CONFIG1, 0, GYRO_CONFIG1_BIT::GYRO_UI_FILT_ORD }, + { Register::BANK_0::GYRO_ACCEL_CONFIG0, 0, GYRO_ACCEL_CONFIG0_BIT::ACCEL_UI_FILT_BW | GYRO_ACCEL_CONFIG0_BIT::GYRO_UI_FILT_BW }, + { Register::BANK_0::ACCEL_CONFIG1, 0, ACCEL_CONFIG1_BIT::ACCEL_UI_FILT_ORD }, + { Register::BANK_0::FIFO_CONFIG1, FIFO_CONFIG1_BIT::FIFO_WM_GT_TH | FIFO_CONFIG1_BIT::FIFO_HIRES_EN | FIFO_CONFIG1_BIT::FIFO_TEMP_EN | FIFO_CONFIG1_BIT::FIFO_GYRO_EN | FIFO_CONFIG1_BIT::FIFO_ACCEL_EN, 0 }, + { Register::BANK_0::FIFO_CONFIG2, 0, 0 }, // FIFO_WM[7:0] set at runtime + { Register::BANK_0::FIFO_CONFIG3, 0, 0 }, // FIFO_WM[11:8] set at runtime + { Register::BANK_0::INT_CONFIG0, INT_CONFIG0_BIT::CLEAR_ON_FIFO_READ, 0 }, + { Register::BANK_0::INT_SOURCE0, INT_SOURCE0_BIT::FIFO_THS_INT1_EN, 0 }, + }; + + uint8_t _checked_register_bank1{0}; + static constexpr uint8_t size_register_bank1_cfg{1}; + register_bank1_config_t _register_bank1_cfg[size_register_bank1_cfg] { + // Register | Set bits, Clear bits + { Register::BANK_1::GYRO_CONFIG_STATIC2, GYRO_CONFIG_STATIC2_BIT::GYRO_AAF_DIS | GYRO_CONFIG_STATIC2_BIT::GYRO_NF_DIS, 0 }, + }; + + uint8_t _checked_register_bank2{0}; + static constexpr uint8_t size_register_bank2_cfg{1}; + register_bank2_config_t _register_bank2_cfg[size_register_bank2_cfg] { + // Register | Set bits, Clear bits + { Register::BANK_2::ACCEL_CONFIG_STATIC2, ACCEL_CONFIG_STATIC2_BIT::ACCEL_AAF_DIS, 0 }, + }; +}; diff --git a/src/drivers/imu/invensense/iim42652/InvenSense_IIM42652_registers.hpp b/src/drivers/imu/invensense/iim42652/InvenSense_IIM42652_registers.hpp new file mode 100644 index 0000000000..7f59099e2f --- /dev/null +++ b/src/drivers/imu/invensense/iim42652/InvenSense_IIM42652_registers.hpp @@ -0,0 +1,322 @@ +/**************************************************************************** + * + * Copyright (c) 2022 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 InvenSense_IIM42652_registers.hpp + * + * Invensense IIM-42652 registers. + * + */ + +#pragma once + +#include +#include + +namespace InvenSense_IIM42652 +{ +// TODO: move to a central header +static constexpr uint8_t Bit0 = (1 << 0); +static constexpr uint8_t Bit1 = (1 << 1); +static constexpr uint8_t Bit2 = (1 << 2); +static constexpr uint8_t Bit3 = (1 << 3); +static constexpr uint8_t Bit4 = (1 << 4); +static constexpr uint8_t Bit5 = (1 << 5); +static constexpr uint8_t Bit6 = (1 << 6); +static constexpr uint8_t Bit7 = (1 << 7); + +static constexpr uint32_t SPI_SPEED = 24 * 1000 * 1000; // 24 MHz SPI +static constexpr uint8_t DIR_READ = 0x80; + +static constexpr uint8_t WHOAMI = 0x6F; + +static constexpr float TEMPERATURE_SENSITIVITY = 132.48f; // LSB/C +static constexpr float TEMPERATURE_OFFSET = 25.f; // C + +namespace Register +{ + +enum class BANK_0 : uint8_t { + DEVICE_CONFIG = 0x11, + + INT_CONFIG = 0x14, + + FIFO_CONFIG = 0x16, + + TEMP_DATA1 = 0x1D, + TEMP_DATA0 = 0x1E, + + INT_STATUS = 0x2D, + FIFO_COUNTH = 0x2E, + FIFO_COUNTL = 0x2F, + FIFO_DATA = 0x30, + + SIGNAL_PATH_RESET = 0x4B, + INTF_CONFIG0 = 0x4C, + INTF_CONFIG1 = 0x4D, + PWR_MGMT0 = 0x4E, + GYRO_CONFIG0 = 0x4F, + ACCEL_CONFIG0 = 0x50, + GYRO_CONFIG1 = 0x51, + GYRO_ACCEL_CONFIG0 = 0x52, + ACCEL_CONFIG1 = 0x53, + + FIFO_CONFIG1 = 0x5F, + FIFO_CONFIG2 = 0x60, + FIFO_CONFIG3 = 0x61, + + INT_CONFIG0 = 0x63, + + INT_SOURCE0 = 0x65, + + SELF_TEST_CONFIG = 0x70, + + WHO_AM_I = 0x75, + REG_BANK_SEL = 0x76, +}; + +enum class BANK_1 : uint8_t { + GYRO_CONFIG_STATIC2 = 0x0B, + + INTF_CONFIG5 = 0x7B, +}; + +enum class BANK_2 : uint8_t { + ACCEL_CONFIG_STATIC2 = 0x03, +}; + +}; + +//---------------- BANK0 Register bits + +// DEVICE_CONFIG +enum DEVICE_CONFIG_BIT : uint8_t { + SOFT_RESET_CONFIG = Bit0, // +}; + +// INT_CONFIG +enum INT_CONFIG_BIT : uint8_t { + INT1_MODE = Bit2, + INT1_DRIVE_CIRCUIT = Bit1, + INT1_POLARITY = Bit0, +}; + +// FIFO_CONFIG +enum FIFO_CONFIG_BIT : uint8_t { + // 7:6 FIFO_MODE + FIFO_MODE_STOP_ON_FULL = Bit7 | Bit6, // 11: STOP-on-FULL Mode +}; + +// INT_STATUS +enum INT_STATUS_BIT : uint8_t { + RESET_DONE_INT = Bit4, + DATA_RDY_INT = Bit3, + FIFO_THS_INT = Bit2, + FIFO_FULL_INT = Bit1, +}; + +// SIGNAL_PATH_RESET +enum SIGNAL_PATH_RESET_BIT : uint8_t { + ABORT_AND_RESET = Bit3, + FIFO_FLUSH = Bit1, +}; + +// PWR_MGMT0 +enum PWR_MGMT0_BIT : uint8_t { + GYRO_MODE_LOW_NOISE = Bit3 | Bit2, // 11: Places gyroscope in Low Noise (LN) Mode + ACCEL_MODE_LOW_NOISE = Bit1 | Bit0, // 11: Places accelerometer in Low Noise (LN) Mode +}; + +// GYRO_CONFIG0 +enum GYRO_CONFIG0_BIT : uint8_t { + // 7:5 GYRO_FS_SEL + GYRO_FS_SEL_2000_DPS = 0, // 0b000 = ±2000dps (default) + GYRO_FS_SEL_1000_DPS = Bit5, + GYRO_FS_SEL_500_DPS = Bit6, + GYRO_FS_SEL_250_DPS = Bit6 | Bit5, + GYRO_FS_SEL_125_DPS = Bit7, + + + // 3:0 GYRO_ODR + // 0001: 32kHz + GYRO_ODR_32KHZ_SET = Bit0, + GYRO_ODR_32KHZ_CLEAR = Bit3 | Bit2 | Bit0, + // 0010: 16kHz + GYRO_ODR_16KHZ_SET = Bit1, + GYRO_ODR_16KHZ_CLEAR = Bit3 | Bit2 | Bit0, + // 0011: 8kHz + GYRO_ODR_8KHZ_SET = Bit1 | Bit0, + GYRO_ODR_8KHZ_CLEAR = Bit3 | Bit2, + // 0110: 1kHz (default) + GYRO_ODR_1KHZ_SET = Bit2 | Bit1, + GYRO_ODR_1KHZ_CLEAR = Bit3 | Bit0, +}; + +// ACCEL_CONFIG0 +enum ACCEL_CONFIG0_BIT : uint8_t { + // 7:5 ACCEL_FS_SEL + ACCEL_FS_SEL_16G = 0, // 000: ±16g (default) + ACCEL_FS_SEL_8G = Bit5, + ACCEL_FS_SEL_4G = Bit6, + ACCEL_FS_SEL_2G = Bit6 | Bit5, + + + // 3:0 ACCEL_ODR + // 0001: 32kHz + ACCEL_ODR_32KHZ_SET = Bit0, + ACCEL_ODR_32KHZ_CLEAR = Bit3 | Bit2 | Bit0, + // 0010: 16kHz + ACCEL_ODR_16KHZ_SET = Bit1, + ACCEL_ODR_16KHZ_CLEAR = Bit3 | Bit2 | Bit0, + // 0011: 8kHz + ACCEL_ODR_8KHZ_SET = Bit1 | Bit0, + ACCEL_ODR_8KHZ_CLEAR = Bit3 | Bit2, + // 0110: 1kHz (default) + ACCEL_ODR_1KHZ_SET = Bit2 | Bit1, + ACCEL_ODR_1KHZ_CLEAR = Bit3 | Bit0, +}; + +// GYRO_CONFIG1 +enum GYRO_CONFIG1_BIT : uint8_t { + GYRO_UI_FILT_ORD = Bit3 | Bit2, // 00: 1st Order +}; + +// GYRO_ACCEL_CONFIG0 +enum GYRO_ACCEL_CONFIG0_BIT : uint8_t { + // 7:4 ACCEL_UI_FILT_BW + ACCEL_UI_FILT_BW = Bit7 | Bit6 | Bit5 | Bit4, // 0: BW=ODR/2 + + // 3:0 GYRO_UI_FILT_BW + GYRO_UI_FILT_BW = Bit3 | Bit2 | Bit1 | Bit0, // 0: BW=ODR/2 +}; + +// ACCEL_CONFIG1 +enum ACCEL_CONFIG1_BIT : uint8_t { + ACCEL_UI_FILT_ORD = Bit4 | Bit3, // 00: 1st Order +}; + +// FIFO_CONFIG1 +enum FIFO_CONFIG1_BIT : uint8_t { + FIFO_RESUME_PARTIAL_RD = Bit6, + FIFO_WM_GT_TH = Bit5, + FIFO_HIRES_EN = Bit4, + FIFO_TEMP_EN = Bit2, + FIFO_GYRO_EN = Bit1, + FIFO_ACCEL_EN = Bit0, +}; + +// INT_CONFIG0 +enum INT_CONFIG0_BIT : uint8_t { + // 3:2 FIFO_THS_INT_CLEAR + CLEAR_ON_FIFO_READ = Bit3, +}; + +// INT_SOURCE0 +enum INT_SOURCE0_BIT : uint8_t { + UI_FSYNC_INT1_EN = Bit6, + PLL_RDY_INT1_EN = Bit5, + RESET_DONE_INT1_EN = Bit4, + UI_DRDY_INT1_EN = Bit3, + FIFO_THS_INT1_EN = Bit2, // FIFO threshold interrupt routed to INT1 + FIFO_FULL_INT1_EN = Bit1, + UI_AGC_RDY_INT1_EN = Bit0, +}; + +// REG_BANK_SEL +enum REG_BANK_SEL_BIT : uint8_t { + USER_BANK_0 = 0, // 0: Select USER BANK 0. + USER_BANK_1 = Bit4, // 1: Select USER BANK 1. + USER_BANK_2 = Bit5, // 2: Select USER BANK 2. + USER_BANK_3 = Bit5 | Bit4, // 3: Select USER BANK 3. +}; + + +//---------------- BANK1 Register bits + +// GYRO_CONFIG_STATIC2 +enum GYRO_CONFIG_STATIC2_BIT : uint8_t { + GYRO_AAF_DIS = Bit1, + GYRO_NF_DIS = Bit0, +}; + + +//---------------- BANK2 Register bits + +// ACCEL_CONFIG_STATIC2 +enum ACCEL_CONFIG_STATIC2_BIT : uint8_t { + ACCEL_AAF_DIS = Bit0, +}; + +namespace FIFO +{ +static constexpr size_t SIZE = 2048; + +// FIFO_DATA layout when FIFO_CONFIG1 has FIFO_GYRO_EN and FIFO_ACCEL_EN set + +// Packet 4 +struct DATA { + uint8_t FIFO_Header; + uint8_t ACCEL_DATA_X1; // Accel X [19:12] + uint8_t ACCEL_DATA_X0; // Accel X [11:4] + uint8_t ACCEL_DATA_Y1; // Accel Y [19:12] + uint8_t ACCEL_DATA_Y0; // Accel Y [11:4] + uint8_t ACCEL_DATA_Z1; // Accel Z [19:12] + uint8_t ACCEL_DATA_Z0; // Accel Z [11:4] + uint8_t GYRO_DATA_X1; // Gyro X [19:12] + uint8_t GYRO_DATA_X0; // Gyro X [11:4] + uint8_t GYRO_DATA_Y1; // Gyro Y [19:12] + uint8_t GYRO_DATA_Y0; // Gyro Y [11:4] + uint8_t GYRO_DATA_Z1; // Gyro Z [19:12] + uint8_t GYRO_DATA_Z0; // Gyro Z [11:4] + uint8_t TEMP_DATA1; // Temperature[15:8] + uint8_t TEMP_DATA0; // Temperature[7:0] + uint8_t TimeStamp_h; // TimeStamp[15:8] + uint8_t TimeStamp_l; // TimeStamp[7:0] + uint8_t Ext_Accel_X_Gyro_X; // Accel X [3:0] Gyro X [3:0] + uint8_t Ext_Accel_Y_Gyro_Y; // Accel Y [3:0] Gyro Y [3:0] + uint8_t Ext_Accel_Z_Gyro_Z; // Accel Z [3:0] Gyro Z [3:0] +}; + +// With FIFO_ACCEL_EN and FIFO_GYRO_EN header should be 8’b_0110_10xx +enum FIFO_HEADER_BIT : uint8_t { + HEADER_MSG = Bit7, // 1: FIFO is empty + HEADER_ACCEL = Bit6, // 1: Packet is sized so that accel data have location in the packet, FIFO_ACCEL_EN must be 1 + HEADER_GYRO = Bit5, // 1: Packet is sized so that gyro data have location in the packet, FIFO_GYRO_EN must be1 + HEADER_20 = Bit4, // 1: Packet has a new and valid sample of extended 20-bit data for gyro and/or accel + HEADER_TIMESTAMP_FSYNC = Bit3 | Bit2, + HEADER_ODR_ACCEL = Bit1, // 1: The ODR for accel is different for this accel data packet compared to the previous accel packet + HEADER_ODR_GYRO = Bit0, // 1: The ODR for gyro is different for this gyro data packet compared to the previous gyro packet +}; + +} +} // namespace InvenSense_IIM42652 diff --git a/src/drivers/imu/invensense/iim42652/Kconfig b/src/drivers/imu/invensense/iim42652/Kconfig new file mode 100644 index 0000000000..88031b3b6a --- /dev/null +++ b/src/drivers/imu/invensense/iim42652/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_INVENSENSE_IIM42652 + bool "iim42652" + default n + ---help--- + Enable support for iim42652 diff --git a/src/drivers/imu/invensense/iim42652/iim42652_main.cpp b/src/drivers/imu/invensense/iim42652/iim42652_main.cpp new file mode 100644 index 0000000000..ae88e7e709 --- /dev/null +++ b/src/drivers/imu/invensense/iim42652/iim42652_main.cpp @@ -0,0 +1,87 @@ +/**************************************************************************** + * + * Copyright (c) 2022 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 "IIM42652.hpp" + +#include +#include + +void IIM42652::print_usage() +{ + PRINT_MODULE_USAGE_NAME("iim42652", "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(); +} + +extern "C" int iim42652_main(int argc, char *argv[]) +{ + int ch; + using ThisDriver = IIM42652; + 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_IIM42652); + + 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; +}