7 changed files with 1359 additions and 0 deletions
@ -0,0 +1,46 @@ |
|||||||
|
############################################################################ |
||||||
|
# |
||||||
|
# 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__invensense__icm42670p |
||||||
|
MAIN icm42670p |
||||||
|
COMPILE_FLAGS |
||||||
|
SRCS |
||||||
|
icm42670p_main.cpp |
||||||
|
ICM42670P.cpp |
||||||
|
ICM42670P.hpp |
||||||
|
InvenSense_ICM42670P_registers.hpp |
||||||
|
DEPENDS |
||||||
|
px4_work_queue |
||||||
|
drivers_accelerometer |
||||||
|
drivers_gyroscope |
||||||
|
) |
@ -0,0 +1,745 @@ |
|||||||
|
/****************************************************************************
|
||||||
|
* |
||||||
|
* 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 "ICM42670P.hpp" |
||||||
|
|
||||||
|
using namespace time_literals; |
||||||
|
|
||||||
|
static constexpr int16_t combine(uint8_t msb, uint8_t lsb) |
||||||
|
{ |
||||||
|
return (msb << 8u) | lsb; |
||||||
|
} |
||||||
|
|
||||||
|
ICM42670P::ICM42670P(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 (_drdy_gpio != 0) { |
||||||
|
_drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed"); |
||||||
|
} |
||||||
|
|
||||||
|
ConfigureSampleRate(_px4_gyro.get_max_rate_hz()); |
||||||
|
} |
||||||
|
|
||||||
|
ICM42670P::~ICM42670P() |
||||||
|
{ |
||||||
|
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 ICM42670P::init() |
||||||
|
{ |
||||||
|
int ret = SPI::init(); |
||||||
|
|
||||||
|
if (ret != PX4_OK) { |
||||||
|
DEVICE_DEBUG("SPI::init failed (%i)", ret); |
||||||
|
return ret; |
||||||
|
} |
||||||
|
|
||||||
|
return Reset() ? 0 : -1; |
||||||
|
} |
||||||
|
|
||||||
|
bool ICM42670P::Reset() |
||||||
|
{ |
||||||
|
_state = STATE::RESET; |
||||||
|
DataReadyInterruptDisable(); |
||||||
|
ScheduleClear(); |
||||||
|
ScheduleNow(); |
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
void ICM42670P::exit_and_cleanup() |
||||||
|
{ |
||||||
|
DataReadyInterruptDisable(); |
||||||
|
I2CSPIDriverBase::exit_and_cleanup(); |
||||||
|
} |
||||||
|
|
||||||
|
void ICM42670P::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 ICM42670P::probe() |
||||||
|
{ |
||||||
|
const uint8_t whoami = RegisterRead(Register::BANK_0::WHO_AM_I); |
||||||
|
|
||||||
|
if (whoami != WHOAMI) { |
||||||
|
DEVICE_DEBUG("unexpected WHO_AM_I 0x%02x", whoami); |
||||||
|
return PX4_ERROR; |
||||||
|
} |
||||||
|
|
||||||
|
return PX4_OK; |
||||||
|
} |
||||||
|
|
||||||
|
void ICM42670P::RunImpl() |
||||||
|
{ |
||||||
|
const hrt_abstime now = hrt_absolute_time(); |
||||||
|
|
||||||
|
switch (_state) { |
||||||
|
case STATE::RESET: |
||||||
|
// DEVICE_CONFIG: Software reset configuration
|
||||||
|
RegisterWrite(Register::BANK_0::SIGNAL_PATH_RESET, SIGNAL_PATH_RESET_BIT::SOFT_RESET_DEVICE_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) == 0x04) |
||||||
|
&& (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: { |
||||||
|
uint32_t samples = 0; |
||||||
|
|
||||||
|
if (_data_ready_interrupt_enabled) { |
||||||
|
// scheduled from interrupt if _drdy_fifo_read_samples was set as expected
|
||||||
|
if (_drdy_fifo_read_samples.fetch_and(0) != _fifo_gyro_samples) { |
||||||
|
perf_count(_drdy_missed_perf); |
||||||
|
|
||||||
|
} else { |
||||||
|
samples = _fifo_gyro_samples; |
||||||
|
} |
||||||
|
|
||||||
|
// push backup schedule back
|
||||||
|
ScheduleDelayed(_fifo_empty_interval_us * 2); |
||||||
|
} |
||||||
|
|
||||||
|
if (samples == 0) { |
||||||
|
// check current FIFO count
|
||||||
|
const uint16_t fifo_count = FIFOReadCount(); |
||||||
|
|
||||||
|
// PX4_WARN("fifo_count = %d ",fifo_count);
|
||||||
|
|
||||||
|
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)); |
||||||
|
|
||||||
|
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; |
||||||
|
// PX4_WARN("samples 1 = %d ",samples);
|
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
bool success = false; |
||||||
|
|
||||||
|
if (samples >= 1) { |
||||||
|
// PX4_WARN("samples 2 = %d ",samples);
|
||||||
|
if (FIFORead(now, samples)) { |
||||||
|
success = true; |
||||||
|
|
||||||
|
// PX4_WARN("success = %d ",success);
|
||||||
|
|
||||||
|
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]) |
||||||
|
) { |
||||||
|
_last_config_check_timestamp = now; |
||||||
|
_checked_register_bank0 = (_checked_register_bank0 + 1) % size_register_bank0_cfg; |
||||||
|
|
||||||
|
} else { |
||||||
|
// register check failed, force reset
|
||||||
|
perf_count(_bad_register_perf); |
||||||
|
Reset(); |
||||||
|
} |
||||||
|
|
||||||
|
} else { |
||||||
|
// periodically update temperature (~1 Hz)
|
||||||
|
if (hrt_elapsed_time(&_temperature_update_timestamp) >= 1_s) { |
||||||
|
UpdateTemperature(); |
||||||
|
_temperature_update_timestamp = now; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void ICM42670P::ConfigureAccel() |
||||||
|
{ |
||||||
|
const uint8_t ACCEL_FS_SEL = RegisterRead(Register::BANK_0::ACCEL_CONFIG0) & (Bit7 | Bit6 | Bit5); // 7:5 ACCEL_FS_SEL
|
||||||
|
|
||||||
|
switch (ACCEL_FS_SEL) { |
||||||
|
case ACCEL_FS_SEL_2G: |
||||||
|
_px4_accel.set_scale(CONSTANTS_ONE_G / 16384.f); |
||||||
|
_px4_accel.set_range(2.f * CONSTANTS_ONE_G); |
||||||
|
break; |
||||||
|
|
||||||
|
case ACCEL_FS_SEL_4G: |
||||||
|
_px4_accel.set_scale(CONSTANTS_ONE_G / 8192.f); |
||||||
|
_px4_accel.set_range(4.f * CONSTANTS_ONE_G); |
||||||
|
break; |
||||||
|
|
||||||
|
case ACCEL_FS_SEL_8G: |
||||||
|
_px4_accel.set_scale(CONSTANTS_ONE_G / 4096.f); |
||||||
|
_px4_accel.set_range(8.f * CONSTANTS_ONE_G); |
||||||
|
break; |
||||||
|
|
||||||
|
case ACCEL_FS_SEL_16G: |
||||||
|
_px4_accel.set_scale(CONSTANTS_ONE_G / 2048.f); |
||||||
|
_px4_accel.set_range(16.f * CONSTANTS_ONE_G); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
void ICM42670P::ConfigureGyro() |
||||||
|
{ |
||||||
|
const uint8_t GYRO_FS_SEL = RegisterRead(Register::BANK_0::GYRO_CONFIG0) & (Bit7 | Bit6 | Bit5); // 7:5 GYRO_FS_SEL
|
||||||
|
|
||||||
|
float range_dps = 0.f; |
||||||
|
|
||||||
|
switch (GYRO_FS_SEL) { |
||||||
|
|
||||||
|
case GYRO_FS_SEL_250_DPS: |
||||||
|
range_dps = 250.f; |
||||||
|
break; |
||||||
|
|
||||||
|
case GYRO_FS_SEL_500_DPS: |
||||||
|
range_dps = 500.f; |
||||||
|
break; |
||||||
|
|
||||||
|
case GYRO_FS_SEL_1000_DPS: |
||||||
|
range_dps = 1000.f; |
||||||
|
break; |
||||||
|
|
||||||
|
case GYRO_FS_SEL_2000_DPS: |
||||||
|
range_dps = 2000.f; |
||||||
|
break; |
||||||
|
} |
||||||
|
|
||||||
|
_px4_gyro.set_scale(math::radians(range_dps / 32768.f)); |
||||||
|
_px4_gyro.set_range(math::radians(range_dps)); |
||||||
|
} |
||||||
|
|
||||||
|
void ICM42670P::ConfigureSampleRate(int sample_rate) |
||||||
|
{ |
||||||
|
if (sample_rate == 0) { |
||||||
|
sample_rate = 800; // default to 800 Hz
|
||||||
|
} |
||||||
|
|
||||||
|
// 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 ICM42670P::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; |
||||||
|
} |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
bool ICM42670P::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); |
||||||
|
} |
||||||
|
|
||||||
|
Mreg1Config(); |
||||||
|
|
||||||
|
// now check that all are configured
|
||||||
|
bool success = true; |
||||||
|
|
||||||
|
for (const auto ®_cfg : _register_bank0_cfg) { |
||||||
|
if (!RegisterCheck(reg_cfg)) { |
||||||
|
success = false; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
success = Mreg1Check(); |
||||||
|
|
||||||
|
|
||||||
|
ConfigureAccel(); |
||||||
|
ConfigureGyro(); |
||||||
|
|
||||||
|
return success; |
||||||
|
} |
||||||
|
|
||||||
|
int ICM42670P::DataReadyInterruptCallback(int irq, void *context, void *arg) |
||||||
|
{ |
||||||
|
static_cast<ICM42670P *>(arg)->DataReady(); |
||||||
|
return 0; |
||||||
|
} |
||||||
|
|
||||||
|
void ICM42670P::DataReady() |
||||||
|
{ |
||||||
|
uint32_t expected = 0; |
||||||
|
|
||||||
|
if (_drdy_fifo_read_samples.compare_exchange(&expected, _fifo_gyro_samples)) { |
||||||
|
ScheduleNow(); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
bool ICM42670P::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 ICM42670P::DataReadyInterruptDisable() |
||||||
|
{ |
||||||
|
if (_drdy_gpio == 0) { |
||||||
|
return false; |
||||||
|
} |
||||||
|
|
||||||
|
return px4_arch_gpiosetevent(_drdy_gpio, false, false, false, nullptr, nullptr) == 0; |
||||||
|
} |
||||||
|
|
||||||
|
template <typename T> |
||||||
|
bool ICM42670P::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)) { |
||||||
|
success = false; |
||||||
|
} |
||||||
|
|
||||||
|
if (reg_cfg.clear_bits && ((reg_value & reg_cfg.clear_bits) != 0)) { |
||||||
|
success = false; |
||||||
|
} |
||||||
|
|
||||||
|
return success; |
||||||
|
} |
||||||
|
|
||||||
|
template <typename T> |
||||||
|
uint8_t ICM42670P::RegisterRead(T reg) |
||||||
|
{ |
||||||
|
uint8_t cmd[2] {}; |
||||||
|
cmd[0] = static_cast<uint8_t>(reg) | DIR_READ; |
||||||
|
transfer(cmd, cmd, sizeof(cmd)); |
||||||
|
return cmd[1]; |
||||||
|
} |
||||||
|
|
||||||
|
template <typename T> |
||||||
|
void ICM42670P::RegisterWrite(T reg, uint8_t value) |
||||||
|
{ |
||||||
|
uint8_t cmd[2] { (uint8_t)reg, value }; |
||||||
|
|
||||||
|
transfer(cmd, cmd, sizeof(cmd)); |
||||||
|
} |
||||||
|
|
||||||
|
template <typename T> |
||||||
|
void ICM42670P::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 ICM42670P::FIFOReadCount() |
||||||
|
{ |
||||||
|
// read FIFO count
|
||||||
|
uint8_t fifo_count_buf[3] {}; |
||||||
|
fifo_count_buf[0] = static_cast<uint8_t>(Register::BANK_0::FIFO_COUNTH) | DIR_READ; |
||||||
|
|
||||||
|
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 ICM42670P::FIFORead(const hrt_abstime ×tamp_sample, uint8_t samples) |
||||||
|
{ |
||||||
|
FIFOTransferBuffer buffer{}; |
||||||
|
const size_t transfer_size = math::min(samples * sizeof(FIFO::DATA) + 4 + 2, FIFO::SIZE); |
||||||
|
|
||||||
|
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; |
||||||
|
} |
||||||
|
|
||||||
|
if (valid) { |
||||||
|
valid_samples++; |
||||||
|
|
||||||
|
} else { |
||||||
|
perf_count(_bad_transfer_perf); |
||||||
|
break; |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
// PX4_WARN("valid_samples = %d ",valid_samples);
|
||||||
|
if (valid_samples > 0) { |
||||||
|
ProcessGyro(timestamp_sample, buffer.f, valid_samples); |
||||||
|
ProcessAccel(timestamp_sample, buffer.f, valid_samples); |
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
return false; |
||||||
|
} |
||||||
|
|
||||||
|
void ICM42670P::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_fifo_read_samples.store(0); |
||||||
|
} |
||||||
|
|
||||||
|
void ICM42670P::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; |
||||||
|
|
||||||
|
for (int i = 0; i < samples; i++) { |
||||||
|
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); |
||||||
|
|
||||||
|
// 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[accel.samples] = accel_x; |
||||||
|
accel.y[accel.samples] = (accel_y == INT16_MIN) ? INT16_MAX : -accel_y; |
||||||
|
accel.z[accel.samples] = (accel_z == INT16_MIN) ? INT16_MAX : -accel_z; |
||||||
|
accel.samples++; |
||||||
|
} |
||||||
|
|
||||||
|
_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 ICM42670P::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 = samples; |
||||||
|
gyro.dt = FIFO_SAMPLE_DT; |
||||||
|
|
||||||
|
for (int i = 0; i < samples; i++) { |
||||||
|
const int16_t gyro_x = combine(fifo[i].GYRO_DATA_X1, fifo[i].GYRO_DATA_X0); |
||||||
|
const int16_t gyro_y = combine(fifo[i].GYRO_DATA_Y1, fifo[i].GYRO_DATA_Y0); |
||||||
|
const int16_t gyro_z = combine(fifo[i].GYRO_DATA_Z1, fifo[i].GYRO_DATA_Z0); |
||||||
|
|
||||||
|
// 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; |
||||||
|
gyro.y[i] = (gyro_y == INT16_MIN) ? INT16_MAX : -gyro_y; |
||||||
|
gyro.z[i] = (gyro_z == INT16_MIN) ? INT16_MAX : -gyro_z; |
||||||
|
} |
||||||
|
|
||||||
|
_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)); |
||||||
|
|
||||||
|
_px4_gyro.updateFIFO(gyro); |
||||||
|
} |
||||||
|
|
||||||
|
void ICM42670P::UpdateTemperature() |
||||||
|
{ |
||||||
|
// read current temperature
|
||||||
|
uint8_t temperature_buf[3] {}; |
||||||
|
temperature_buf[0] = static_cast<uint8_t>(Register::BANK_0::TEMP_DATA1) | DIR_READ; |
||||||
|
|
||||||
|
if (transfer(temperature_buf, temperature_buf, sizeof(temperature_buf)) != PX4_OK) { |
||||||
|
perf_count(_bad_transfer_perf); |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
const int16_t TEMP_DATA = combine(temperature_buf[1], temperature_buf[2]); |
||||||
|
|
||||||
|
// Temperature in Degrees Centigrade
|
||||||
|
const float TEMP_degC = (TEMP_DATA / TEMPERATURE_SENSITIVITY) + TEMPERATURE_OFFSET; |
||||||
|
|
||||||
|
if (PX4_ISFINITE(TEMP_degC)) { |
||||||
|
_px4_accel.set_temperature(TEMP_degC); |
||||||
|
_px4_gyro.set_temperature(TEMP_degC); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
uint8_t ICM42670P::RegisterReadBank1(uint8_t reg) |
||||||
|
{ |
||||||
|
uint8_t value; |
||||||
|
|
||||||
|
RegisterWrite((uint8_t)Register::BANK_0::BLK_SEL_R, 0x00); |
||||||
|
RegisterWrite((uint8_t)Register::BANK_0::MADDR_R, reg); |
||||||
|
ScheduleDelayed(10_us); |
||||||
|
value = RegisterRead((uint8_t)Register::BANK_0::M_R); |
||||||
|
ScheduleDelayed(10_us); |
||||||
|
RegisterWrite((uint8_t)Register::BANK_0::BLK_SEL_R, 0x00); |
||||||
|
|
||||||
|
return value; |
||||||
|
} |
||||||
|
|
||||||
|
void ICM42670P::RegisterWriteBank1(uint8_t reg, uint8_t value) |
||||||
|
{ |
||||||
|
RegisterWrite((uint8_t)Register::BANK_0::BLK_SEL_W, 0x00); |
||||||
|
RegisterWrite((uint8_t)Register::BANK_0::MADDR_W, reg); |
||||||
|
RegisterWrite((uint8_t)Register::BANK_0::M_W, value); |
||||||
|
ScheduleDelayed(10_us); |
||||||
|
RegisterWrite((uint8_t)Register::BANK_0::BLK_SEL_W, 0x00); |
||||||
|
} |
||||||
|
|
||||||
|
void ICM42670P::Mreg1Config() |
||||||
|
{ |
||||||
|
uint8_t data; |
||||||
|
uint8_t set_bits; |
||||||
|
uint8_t clear_bits; |
||||||
|
|
||||||
|
clear_bits = Bit7 | Bit6 | Bit4 | Bit3; |
||||||
|
set_bits = FIFO_CONFIG5_BIT::FIFO_WM_GT_TH | FIFO_CONFIG5_BIT::FIFO_TMST_FSYNC_EN | FIFO_CONFIG5_BIT::FIFO_GYRO_EN | |
||||||
|
FIFO_CONFIG5_BIT::FIFO_ACCEL_EN; |
||||||
|
|
||||||
|
data = RegisterReadBank1(0x01); |
||||||
|
data &= ~clear_bits; |
||||||
|
data |= set_bits; |
||||||
|
RegisterWriteBank1(0x01, data); |
||||||
|
|
||||||
|
|
||||||
|
clear_bits = Bit7 | Bit6 | Bit5 | Bit4 | Bit2 | Bit1 | Bit0; |
||||||
|
set_bits = INT_CONFIG0_BIT::CLEAR_ON_FIFO_READ; |
||||||
|
data = RegisterReadBank1(0x04); |
||||||
|
data &= ~clear_bits; |
||||||
|
data |= set_bits; |
||||||
|
RegisterWriteBank1(0x04, data); |
||||||
|
} |
||||||
|
|
||||||
|
bool ICM42670P::Mreg1Check() |
||||||
|
{ |
||||||
|
uint8_t set_bits; |
||||||
|
uint8_t clear_bits; |
||||||
|
uint8_t reg_value; |
||||||
|
bool success; |
||||||
|
success = true; |
||||||
|
|
||||||
|
reg_value = RegisterReadBank1(0x01); |
||||||
|
|
||||||
|
clear_bits = Bit7 | Bit6 | Bit4 | Bit3; |
||||||
|
set_bits = FIFO_CONFIG5_BIT::FIFO_WM_GT_TH | FIFO_CONFIG5_BIT::FIFO_TMST_FSYNC_EN | FIFO_CONFIG5_BIT::FIFO_GYRO_EN | |
||||||
|
FIFO_CONFIG5_BIT::FIFO_ACCEL_EN; |
||||||
|
|
||||||
|
if (set_bits && ((reg_value & set_bits) != set_bits)) { |
||||||
|
success = false; |
||||||
|
} |
||||||
|
|
||||||
|
if (clear_bits && ((reg_value & clear_bits) != 0)) { |
||||||
|
success = false; |
||||||
|
} |
||||||
|
|
||||||
|
reg_value = RegisterReadBank1(0x04); |
||||||
|
clear_bits = Bit7 | Bit6 | Bit5 | Bit4 | Bit2 | Bit1 | Bit0; |
||||||
|
set_bits = INT_CONFIG0_BIT::CLEAR_ON_FIFO_READ; |
||||||
|
|
||||||
|
if (set_bits && ((reg_value & set_bits) != set_bits)) { |
||||||
|
success = false; |
||||||
|
} |
||||||
|
|
||||||
|
if (clear_bits && ((reg_value & clear_bits) != 0)) { |
||||||
|
success = false; |
||||||
|
} |
||||||
|
|
||||||
|
return success; |
||||||
|
} |
@ -0,0 +1,184 @@ |
|||||||
|
/****************************************************************************
|
||||||
|
* |
||||||
|
* 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 ICM42688P.hpp |
||||||
|
* |
||||||
|
* Driver for the Invensense ICM42688P connected via SPI. |
||||||
|
* |
||||||
|
*/ |
||||||
|
|
||||||
|
#pragma once |
||||||
|
|
||||||
|
#include "InvenSense_ICM42670P_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/perf/perf_counter.h> |
||||||
|
#include <px4_platform_common/atomic.h> |
||||||
|
#include <px4_platform_common/i2c_spi_buses.h> |
||||||
|
|
||||||
|
using namespace InvenSense_ICM42670P; |
||||||
|
|
||||||
|
class ICM42670P : public device::SPI, public I2CSPIDriver<ICM42670P> |
||||||
|
{ |
||||||
|
public: |
||||||
|
ICM42670P(const I2CSPIDriverConfig &config); |
||||||
|
~ICM42670P() 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 / 800.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 uint32_t FIFO_MAX_SAMPLES{math::min(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<uint8_t>(Register::BANK_0::INT_STATUS) | DIR_READ}; |
||||||
|
uint8_t INT_STATUS{0}; |
||||||
|
uint8_t INT_STATUS2{0}; |
||||||
|
uint8_t INT_STATUS3{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 + 2 + 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}; |
||||||
|
}; |
||||||
|
|
||||||
|
int probe() override; |
||||||
|
|
||||||
|
bool Reset(); |
||||||
|
|
||||||
|
bool Configure(); |
||||||
|
void ConfigureAccel(); |
||||||
|
void ConfigureGyro(); |
||||||
|
void ConfigureSampleRate(int sample_rate); |
||||||
|
void ConfigureFIFOWatermark(uint8_t samples); |
||||||
|
|
||||||
|
static int DataReadyInterruptCallback(int irq, void *context, void *arg); |
||||||
|
void DataReady(); |
||||||
|
bool DataReadyInterruptConfigure(); |
||||||
|
bool DataReadyInterruptDisable(); |
||||||
|
|
||||||
|
template <typename T> bool RegisterCheck(const T ®_cfg); |
||||||
|
template <typename T> uint8_t RegisterRead(T reg); |
||||||
|
template <typename T> void RegisterWrite(T reg, uint8_t value); |
||||||
|
template <typename T> void RegisterSetAndClearBits(T reg, uint8_t setbits, uint8_t clearbits); |
||||||
|
template <typename T> void RegisterSetBits(T reg, uint8_t setbits) { RegisterSetAndClearBits(reg, setbits, 0); } |
||||||
|
template <typename T> 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); |
||||||
|
void UpdateTemperature(); |
||||||
|
|
||||||
|
uint8_t RegisterReadBank1(uint8_t reg); |
||||||
|
void RegisterWriteBank1(uint8_t reg, uint8_t value); |
||||||
|
|
||||||
|
void Mreg1Config(); |
||||||
|
bool Mreg1Check(); |
||||||
|
|
||||||
|
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<uint32_t> _drdy_fifo_read_samples{0}; |
||||||
|
bool _data_ready_interrupt_enabled{false}; |
||||||
|
|
||||||
|
enum class STATE : uint8_t { |
||||||
|
RESET, |
||||||
|
WAIT_FOR_RESET, |
||||||
|
CONFIGURE, |
||||||
|
FIFO_READ, |
||||||
|
}; |
||||||
|
|
||||||
|
STATE _state{STATE::RESET}; |
||||||
|
|
||||||
|
uint16_t _fifo_empty_interval_us{1250}; // default 1250 us / 800 Hz transfer interval
|
||||||
|
uint32_t _fifo_gyro_samples{static_cast<uint32_t>(_fifo_empty_interval_us / (1000000 / GYRO_RATE))}; |
||||||
|
|
||||||
|
uint8_t _checked_register_bank0{0}; |
||||||
|
static constexpr uint8_t size_register_bank0_cfg{10}; |
||||||
|
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_CONFIG1, FIFO_CONFIG1_BIT::FIFO_MODE_STOP_ON_FULL, Bit0 }, |
||||||
|
{ 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_ODR_1600Hz | GYRO_CONFIG0_BIT::GYRO_FS_SEL_2000_DPS, Bit7 | Bit3 | Bit0 }, |
||||||
|
{ Register::BANK_0::ACCEL_CONFIG0, ACCEL_CONFIG0_BIT::ACCEL_ODR_1600Hz | ACCEL_CONFIG0_BIT::ACCEL_FS_SEL_16G, Bit6 | Bit5 | Bit3 | Bit0 }, |
||||||
|
{ Register::BANK_0::GYRO_CONFIG1, GYRO_CONFIG1_BIT::GYRO_UI_FILT_BW_34Hz, Bit1 }, |
||||||
|
{ Register::BANK_0::ACCEL_CONFIG1, ACCEL_CONFIG1_BIT::ACCEL_UI_FILT_BW_34Hz, Bit1 }, |
||||||
|
{ 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_SOURCE0, INT_SOURCE0_BIT::FIFO_THS_INT1_EN, 0 }, |
||||||
|
}; |
||||||
|
}; |
@ -0,0 +1,293 @@ |
|||||||
|
/****************************************************************************
|
||||||
|
* |
||||||
|
* 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 InvenSense_ICM42670P_registers.hpp |
||||||
|
* |
||||||
|
* Invensense ICM-42670-P registers. |
||||||
|
* |
||||||
|
*/ |
||||||
|
|
||||||
|
#pragma once |
||||||
|
|
||||||
|
#include <cstdint> |
||||||
|
|
||||||
|
namespace InvenSense_ICM42670P |
||||||
|
{ |
||||||
|
// 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 = 12 * 1000 * 1000; // 24 MHz SPI
|
||||||
|
static constexpr uint8_t DIR_READ = 0x80; |
||||||
|
|
||||||
|
static constexpr uint8_t WHOAMI = 0x67; |
||||||
|
|
||||||
|
static constexpr float TEMPERATURE_SENSITIVITY = 128.0f; // LSB/C
|
||||||
|
static constexpr float TEMPERATURE_OFFSET = 25.f; // C
|
||||||
|
|
||||||
|
namespace Register |
||||||
|
{ |
||||||
|
|
||||||
|
enum class BANK_0 : uint8_t { |
||||||
|
DEVICE_CONFIG = 0x01, |
||||||
|
|
||||||
|
INT_CONFIG = 0x06, |
||||||
|
|
||||||
|
|
||||||
|
TEMP_DATA1 = 0x09, |
||||||
|
TEMP_DATA0 = 0x0A, |
||||||
|
|
||||||
|
INT_STATUS = 0x3A, |
||||||
|
FIFO_COUNTH = 0x3D, |
||||||
|
FIFO_COUNTL = 0x3E, |
||||||
|
FIFO_DATA = 0x3F, |
||||||
|
|
||||||
|
SIGNAL_PATH_RESET = 0x02, |
||||||
|
|
||||||
|
PWR_MGMT0 = 0x1F, |
||||||
|
GYRO_CONFIG0 = 0x20, |
||||||
|
ACCEL_CONFIG0 = 0x21, |
||||||
|
GYRO_CONFIG1 = 0x23, |
||||||
|
ACCEL_CONFIG1 = 0x24, |
||||||
|
|
||||||
|
FIFO_CONFIG1 = 0x28, |
||||||
|
FIFO_CONFIG2 = 0x29, |
||||||
|
FIFO_CONFIG3 = 0x2A, |
||||||
|
|
||||||
|
INT_SOURCE0 = 0x2B, |
||||||
|
|
||||||
|
WHO_AM_I = 0x75, |
||||||
|
// REG_BANK_SEL = 0x76,
|
||||||
|
|
||||||
|
BLK_SEL_W = 0x79, |
||||||
|
MADDR_W = 0x7A, |
||||||
|
M_W = 0x7B, |
||||||
|
|
||||||
|
BLK_SEL_R = 0x7C, |
||||||
|
MADDR_R = 0x7D, |
||||||
|
M_R = 0x7E, |
||||||
|
|
||||||
|
}; |
||||||
|
|
||||||
|
enum class MREG_1 : uint8_t { |
||||||
|
FIFO_CONFIG5_MREG1 = 0x01, |
||||||
|
INT_CONFIG0_MREG1 = 0x04, |
||||||
|
}; |
||||||
|
|
||||||
|
enum class MREG_2 : uint8_t { |
||||||
|
OTP_CTRL7_MREG2 = 0x06, |
||||||
|
}; |
||||||
|
|
||||||
|
enum class MREG_3 : uint8_t { |
||||||
|
XA_ST_DATA_MREG3 = 0x00, |
||||||
|
YA_ST_DATA_MREG3 = 0x01, |
||||||
|
ZA_ST_DATA_MREG3 = 0x02, |
||||||
|
XG_ST_DATA_MREG3 = 0x03, |
||||||
|
YG_ST_DATA_MREG3 = 0x04, |
||||||
|
ZG_ST_DATA_MREG3 = 0x05, |
||||||
|
}; |
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}; |
||||||
|
|
||||||
|
//---------------- BANK0 Register bits
|
||||||
|
|
||||||
|
// SIGNAL_PATH_RESET
|
||||||
|
enum SIGNAL_PATH_RESET_BIT : uint8_t { |
||||||
|
SOFT_RESET_DEVICE_CONFIG = Bit4, //
|
||||||
|
FIFO_FLUSH = Bit2, |
||||||
|
}; |
||||||
|
|
||||||
|
// INT_CONFIG
|
||||||
|
enum INT_CONFIG_BIT : uint8_t { |
||||||
|
INT1_MODE = Bit2, |
||||||
|
INT1_DRIVE_CIRCUIT = Bit1, |
||||||
|
INT1_POLARITY = Bit0, |
||||||
|
}; |
||||||
|
// GYRO_CONFIG1
|
||||||
|
enum GYRO_CONFIG1_BIT : uint8_t { |
||||||
|
|
||||||
|
// 2:0 GYRO_ODR
|
||||||
|
GYRO_UI_FILT_BW_16Hz = Bit2 | Bit1 | Bit0, // 111: 16Hz
|
||||||
|
GYRO_UI_FILT_BW_25Hz = Bit2 | Bit1, // 110: 25Hz
|
||||||
|
GYRO_UI_FILT_BW_34Hz = Bit2 | Bit0, // 101: 34Hz
|
||||||
|
GYRO_UI_FILT_BW_53Hz = Bit2, // 100: 53Hz
|
||||||
|
GYRO_UI_FILT_BW_73Hz = Bit1 | Bit0, // 011: 73Hz
|
||||||
|
GYRO_UI_FILT_BW_121Hz = Bit1, // 010: 121Hz
|
||||||
|
GYRO_UI_FILT_BW_180Hz = Bit0, // 001: 180Hz
|
||||||
|
}; |
||||||
|
|
||||||
|
// ACCEL_CONFIG1
|
||||||
|
enum ACCEL_CONFIG1_BIT : uint8_t { |
||||||
|
|
||||||
|
// 2:0 ACCEL_ODR
|
||||||
|
ACCEL_UI_FILT_BW_16Hz = Bit2 | Bit1 | Bit0, // 111: 16Hz
|
||||||
|
ACCEL_UI_FILT_BW_25Hz = Bit2 | Bit1, // 110: 25Hz
|
||||||
|
ACCEL_UI_FILT_BW_34Hz = Bit2 | Bit0, // 101: 34Hz
|
||||||
|
ACCEL_UI_FILT_BW_53Hz = Bit2, // 100: 53Hz
|
||||||
|
ACCEL_UI_FILT_BW_73Hz = Bit1 | Bit0, // 011: 73Hz
|
||||||
|
ACCEL_UI_FILT_BW_121Hz = Bit1, // 010: 121Hz
|
||||||
|
ACCEL_UI_FILT_BW_180Hz = Bit0, // 001: 180Hz
|
||||||
|
}; |
||||||
|
// FIFO_CONFIG1
|
||||||
|
enum FIFO_CONFIG1_BIT : uint8_t { |
||||||
|
// 1 FIFO_MODE
|
||||||
|
FIFO_MODE_STOP_ON_FULL = Bit1, // 11: STOP-on-FULL Mode
|
||||||
|
}; |
||||||
|
|
||||||
|
// INT_STATUS
|
||||||
|
enum INT_STATUS_BIT : uint8_t { |
||||||
|
RESET_DONE_INT = Bit4, |
||||||
|
FIFO_THS_INT = Bit2, |
||||||
|
FIFO_FULL_INT = 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 { |
||||||
|
// 6:5 GYRO_FS_SEL
|
||||||
|
GYRO_FS_SEL_2000_DPS = 0, // 0b000 = ±2000dps
|
||||||
|
GYRO_FS_SEL_1000_DPS = Bit5, // 0b001 = ±1000 dps
|
||||||
|
GYRO_FS_SEL_500_DPS = Bit6, // 0b010 = ±500 dps
|
||||||
|
GYRO_FS_SEL_250_DPS = Bit6 | Bit5, // 0b011 = ±250 dps
|
||||||
|
|
||||||
|
// 3:0 GYRO_ODR
|
||||||
|
GYRO_ODR_1600Hz = Bit2 | Bit0, // 0101: 1600Hz
|
||||||
|
GYRO_ODR_800Hz = Bit2 | Bit1, // 0110: 800Hz
|
||||||
|
GYRO_ODR_400Hz = Bit2 | Bit1 | Bit0, // 0111: 400Hz
|
||||||
|
GYRO_ODR_200Hz = Bit3, // 1000: 200Hz
|
||||||
|
}; |
||||||
|
|
||||||
|
// ACCEL_CONFIG0
|
||||||
|
enum ACCEL_CONFIG0_BIT : uint8_t { |
||||||
|
// 6:5 ACCEL_FS_SEL
|
||||||
|
ACCEL_FS_SEL_16G = 0, // 000: ±16g
|
||||||
|
ACCEL_FS_SEL_8G = Bit5, // 001: ±8g
|
||||||
|
ACCEL_FS_SEL_4G = Bit6, // 010: ±4g
|
||||||
|
ACCEL_FS_SEL_2G = Bit6 | Bit5, // 011: ±2g
|
||||||
|
|
||||||
|
// 3:0 ACCEL_ODR
|
||||||
|
ACCEL_ODR_1600Hz = Bit2 | Bit0, // 0101: 1600Hz
|
||||||
|
ACCEL_ODR_800Hz = Bit2 | Bit1, // 0110: 800Hz
|
||||||
|
ACCEL_ODR_400Hz = Bit2 | Bit1 | Bit0, // 0111: 400Hz
|
||||||
|
ACCEL_ODR_200Hz = Bit3, // 1000: 200Hz
|
||||||
|
}; |
||||||
|
|
||||||
|
// FIFO_CONFIG5
|
||||||
|
enum FIFO_CONFIG5_BIT : uint8_t { |
||||||
|
FIFO_RESUME_PARTIAL_RD = Bit4, |
||||||
|
FIFO_WM_GT_TH = Bit5, |
||||||
|
FIFO_HIRES_EN = Bit3, |
||||||
|
FIFO_TMST_FSYNC_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 { |
||||||
|
ST_INT1_END = Bit7, |
||||||
|
FSYNC_INT1_EN = Bit6, |
||||||
|
PLL_RDY_INT1_EN = Bit5, |
||||||
|
RESET_DONE_INT1_EN = Bit4, |
||||||
|
DRDY_INT1_EN = Bit3, |
||||||
|
FIFO_THS_INT1_EN = Bit2, // FIFO threshold interrupt routed to INT1
|
||||||
|
FIFO_FULL_INT1_EN = Bit1, |
||||||
|
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.
|
||||||
|
}; |
||||||
|
|
||||||
|
namespace FIFO |
||||||
|
{ |
||||||
|
static constexpr size_t SIZE = 2048; |
||||||
|
|
||||||
|
// FIFO_DATA layout when FIFO_CONFIG1 has FIFO_GYRO_EN and FIFO_ACCEL_EN set
|
||||||
|
|
||||||
|
// Packet 3
|
||||||
|
struct DATA { |
||||||
|
uint8_t FIFO_Header; |
||||||
|
uint8_t ACCEL_DATA_X1; |
||||||
|
uint8_t ACCEL_DATA_X0; |
||||||
|
uint8_t ACCEL_DATA_Y1; |
||||||
|
uint8_t ACCEL_DATA_Y0; |
||||||
|
uint8_t ACCEL_DATA_Z1; |
||||||
|
uint8_t ACCEL_DATA_Z0; |
||||||
|
uint8_t GYRO_DATA_X1; |
||||||
|
uint8_t GYRO_DATA_X0; |
||||||
|
uint8_t GYRO_DATA_Y1; |
||||||
|
uint8_t GYRO_DATA_Y0; |
||||||
|
uint8_t GYRO_DATA_Z1; |
||||||
|
uint8_t GYRO_DATA_Z0; |
||||||
|
uint8_t temperature; // Temperature[7:0]
|
||||||
|
uint8_t timestamp_l; |
||||||
|
uint8_t timestamp_h; |
||||||
|
}; |
||||||
|
|
||||||
|
// 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, |
||||||
|
HEADER_GYRO = Bit5, |
||||||
|
HEADER_20 = Bit4, |
||||||
|
HEADER_TIMESTAMP_FSYNC = Bit3 | Bit2, |
||||||
|
HEADER_ODR_ACCEL = Bit1, |
||||||
|
HEADER_ODR_GYRO = Bit0, |
||||||
|
}; |
||||||
|
|
||||||
|
} |
||||||
|
} // namespace InvenSense_ICM42670P
|
@ -0,0 +1,89 @@ |
|||||||
|
/****************************************************************************
|
||||||
|
* |
||||||
|
* 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 "ICM42670P.hpp" |
||||||
|
|
||||||
|
#include <px4_platform_common/getopt.h> |
||||||
|
#include <px4_platform_common/module.h> |
||||||
|
|
||||||
|
void ICM42670P::print_usage() |
||||||
|
{ |
||||||
|
PRINT_MODULE_USAGE_NAME("icm42670p", "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 icm42670p_main(int argc, char *argv[]) |
||||||
|
{ |
||||||
|
int ch; |
||||||
|
using ThisDriver = ICM42670P; |
||||||
|
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_ICM42670P); |
||||||
|
|
||||||
|
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; |
||||||
|
} |
Loading…
Reference in new issue