imu/invensense/mpu6000: minor improvements

- at start perform full sensor signal path reset and wait for max time
 - issue full sensor reset on any error
 - only allocate DRDY perf counter if GPIO is available
 - allow running faster than accel ODR (safe limit of 2 kHz in place)
This commit is contained in:
Daniel Agar 2020-06-02 13:25:42 -04:00
parent 01f4486b32
commit 5286ed3a11
3 changed files with 205 additions and 182 deletions

View File

@ -64,30 +64,27 @@ static constexpr float TEMPERATURE_SENSITIVITY = 340.f; // LSB/C
static constexpr float TEMPERATURE_OFFSET = 36.53f; // C
enum class Register : uint8_t {
CONFIG = 0x1A,
GYRO_CONFIG = 0x1B,
ACCEL_CONFIG = 0x1C,
CONFIG = 0x1A,
GYRO_CONFIG = 0x1B,
ACCEL_CONFIG = 0x1C,
FIFO_EN = 0x23,
I2C_MST_CTRL = 0x24,
FIFO_EN = 0x23,
INT_PIN_CFG = 0x37,
INT_ENABLE = 0x38,
INT_PIN_CFG = 0x37,
INT_ENABLE = 0x38,
INT_STATUS = 0x3A,
TEMP_OUT_H = 0x41,
TEMP_OUT_L = 0x42,
TEMP_OUT_H = 0x41,
TEMP_OUT_L = 0x42,
SIGNAL_PATH_RESET = 0x68,
USER_CTRL = 0x6A,
PWR_MGMT_1 = 0x6B,
USER_CTRL = 0x6A,
PWR_MGMT_1 = 0x6B,
FIFO_COUNTH = 0x72,
FIFO_COUNTL = 0x73,
FIFO_R_W = 0x74,
WHO_AM_I = 0x75,
FIFO_COUNTH = 0x72,
FIFO_COUNTL = 0x73,
FIFO_R_W = 0x74,
WHO_AM_I = 0x75,
};
// CONFIG
@ -124,22 +121,12 @@ enum FIFO_EN_BIT : uint8_t {
// INT_PIN_CFG
enum INT_PIN_CFG_BIT : uint8_t {
INT_LEVEL = Bit7,
INT_RD_CLEAR = Bit4,
INT_LEVEL = Bit7,
};
// INT_ENABLE
enum INT_ENABLE_BIT : uint8_t {
FIFO_OFLOW_EN = Bit4,
DATA_RDY_INT_EN = Bit0
};
// INT_STATUS
enum INT_STATUS_BIT : uint8_t {
FIFO_OFLOW_INT = Bit4,
DATA_RDY_INT = Bit0,
DATA_RDY_INT_EN = Bit0,
};
// SIGNAL_PATH_RESET
@ -152,11 +139,8 @@ enum SIGNAL_PATH_RESET_BIT : uint8_t {
// USER_CTRL
enum USER_CTRL_BIT : uint8_t {
FIFO_EN = Bit6,
I2C_MST_EN = Bit5,
I2C_IF_DIS = Bit4,
FIFO_RESET = Bit2,
SIG_COND_RESET = Bit0,
};
@ -165,8 +149,7 @@ enum PWR_MGMT_1_BIT : uint8_t {
DEVICE_RESET = Bit7,
SLEEP = Bit6,
CLKSEL_2 = Bit2,
CLKSEL_1 = Bit1,
// CLKSEL[2:0]
CLKSEL_0 = Bit0,
};

View File

@ -48,6 +48,10 @@ MPU6000::MPU6000(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rota
_px4_accel(get_device_id(), ORB_PRIO_HIGH, rotation),
_px4_gyro(get_device_id(), ORB_PRIO_HIGH, rotation)
{
if (drdy_gpio != 0) {
_drdy_interval_perf = perf_alloc(PC_INTERVAL, MODULE_NAME": DRDY interval");
}
ConfigureSampleRate(_px4_gyro.get_max_rate_hz());
}
@ -77,6 +81,7 @@ int MPU6000::init()
bool MPU6000::Reset()
{
_state = STATE::RESET;
DataReadyInterruptDisable();
ScheduleClear();
ScheduleNow();
return true;
@ -91,8 +96,8 @@ void MPU6000::exit_and_cleanup()
void MPU6000::print_status()
{
I2CSPIDriverBase::print_status();
PX4_INFO("FIFO empty interval: %d us (%.3f Hz)", _fifo_empty_interval_us,
static_cast<double>(1000000 / _fifo_empty_interval_us));
PX4_INFO("FIFO empty interval: %d us (%.3f Hz)", _fifo_empty_interval_us, 1e6 / _fifo_empty_interval_us);
perf_print_counter(_transfer_perf);
perf_print_counter(_bad_register_perf);
@ -120,13 +125,17 @@ int MPU6000::probe()
void MPU6000::RunImpl()
{
const hrt_abstime now = hrt_absolute_time();
switch (_state) {
case STATE::RESET:
// PWR_MGMT_1: Device Reset
RegisterWrite(Register::PWR_MGMT_1, PWR_MGMT_1_BIT::DEVICE_RESET);
_reset_timestamp = hrt_absolute_time();
_reset_timestamp = now;
_consecutive_failures = 0;
_total_failures = 0;
_state = STATE::WAIT_FOR_RESET;
ScheduleDelayed(100_ms);
ScheduleDelayed(100_ms); // Wait 100ms (Document Number: RM-MPU-6000A-00 Page 41 of 46)
break;
case STATE::WAIT_FOR_RESET:
@ -136,17 +145,19 @@ void MPU6000::RunImpl()
if ((RegisterRead(Register::WHO_AM_I) == WHOAMI)
&& (RegisterRead(Register::PWR_MGMT_1) == 0x40)) {
// SIGNAL_PATH_RESET: ensure the reset is performed properly
// Wakeup and reset digital signal path
RegisterWrite(Register::PWR_MGMT_1, 0);
RegisterWrite(Register::SIGNAL_PATH_RESET,
SIGNAL_PATH_RESET_BIT::GYRO_RESET | SIGNAL_PATH_RESET_BIT::ACCEL_RESET | SIGNAL_PATH_RESET_BIT::TEMP_RESET);
RegisterSetAndClearBits(Register::USER_CTRL, USER_CTRL_BIT::SIG_COND_RESET, USER_CTRL_BIT::I2C_IF_DIS);
// if reset succeeded then configure
_state = STATE::CONFIGURE;
ScheduleDelayed(100_ms);
ScheduleDelayed(100_ms); // Wait another 100ms (Document Number: RM-MPU-6000A-00 Page 41 of 46)
} else {
// RESET not complete
if (hrt_elapsed_time(&_reset_timestamp) > 100_ms) {
if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) {
PX4_DEBUG("Reset failed, retrying");
_state = STATE::RESET;
ScheduleDelayed(100_ms);
@ -168,7 +179,7 @@ void MPU6000::RunImpl()
_data_ready_interrupt_enabled = true;
// backup schedule as a watchdog timeout
ScheduleDelayed(10_ms);
ScheduleDelayed(100_ms);
} else {
_data_ready_interrupt_enabled = false;
@ -178,73 +189,87 @@ void MPU6000::RunImpl()
FIFOReset();
} else {
PX4_DEBUG("Configure failed, retrying");
// try again in 10 ms
// 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(10_ms);
}
break;
case STATE::FIFO_READ: {
hrt_abstime timestamp_sample = 0;
if (_data_ready_interrupt_enabled) {
// re-schedule as watchdog timeout
ScheduleDelayed(10_ms);
}
if (_data_ready_interrupt_enabled && (hrt_elapsed_time(&timestamp_sample) < (_fifo_empty_interval_us / 2))) {
// use timestamp from data ready interrupt if enabled and seems valid
timestamp_sample = _fifo_watermark_interrupt_timestamp;
} else {
// use the time now roughly corresponding with the last sample we'll pull from the FIFO
timestamp_sample = hrt_absolute_time();
}
const uint16_t fifo_count = FIFOReadCount();
const uint8_t samples = (fifo_count / sizeof(FIFO::DATA) / SAMPLES_PER_TRANSFER) *
SAMPLES_PER_TRANSFER; // round down to nearest
bool failure = false;
if (samples > FIFO_MAX_SAMPLES) {
// not technically an overflow, but more samples than we expected or can publish
perf_count(_fifo_overflow_perf);
failure = true;
FIFOReset();
} else if (samples >= SAMPLES_PER_TRANSFER) {
// require at least SAMPLES_PER_TRANSFER (we want at least 1 new accel sample per transfer)
if (!FIFORead(timestamp_sample, samples)) {
failure = true;
_px4_accel.increase_error_count();
_px4_gyro.increase_error_count();
// scheduled from interrupt if _drdy_fifo_read_samples was set
if (_drdy_fifo_read_samples.fetch_and(0) == _fifo_gyro_samples) {
perf_count_interval(_drdy_interval_perf, now);
}
} else if (samples == 0) {
failure = true;
perf_count(_fifo_empty_perf);
// push backup schedule back
ScheduleDelayed(_fifo_empty_interval_us * 2);
}
if (failure || hrt_elapsed_time(&_last_config_check_timestamp) > 10_ms) {
// check registers incrementally
if (RegisterCheck(_register_cfg[_checked_register], true)) {
_last_config_check_timestamp = timestamp_sample;
// always check current FIFO count
bool success = false;
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) should be a multiple of the FIFO::DATA structure
const uint8_t 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);
} else if (samples >= 1) {
if (FIFORead(now, samples)) {
success = true;
_consecutive_failures = 0;
}
}
}
if (!success) {
_consecutive_failures++;
_total_failures++;
// full reset if things are failing consistently
if (_consecutive_failures > 100 || _total_failures > 1000) {
Reset();
return;
}
}
if (!success || hrt_elapsed_time(&_last_config_check_timestamp) > 10_ms) {
// check configuration registers periodically or immediately following any failure
if (RegisterCheck(_register_cfg[_checked_register])) {
_last_config_check_timestamp = now;
_checked_register = (_checked_register + 1) % size_register_cfg;
} else {
// register check failed, force reconfigure
PX4_DEBUG("Health check failed, reconfiguring");
_state = STATE::CONFIGURE;
ScheduleNow();
// 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) {
// periodically update temperature (~1 Hz)
if (hrt_elapsed_time(&_temperature_update_timestamp) >= 1_s) {
UpdateTemperature();
_temperature_update_timestamp = timestamp_sample;
_temperature_update_timestamp = now;
}
}
}
@ -259,23 +284,23 @@ void MPU6000::ConfigureAccel()
switch (AFS_SEL) {
case AFS_SEL_2G:
_px4_accel.set_scale(CONSTANTS_ONE_G / 16384);
_px4_accel.set_range(2 * CONSTANTS_ONE_G);
_px4_accel.set_scale(CONSTANTS_ONE_G / 16384.f);
_px4_accel.set_range(2.f * CONSTANTS_ONE_G);
break;
case AFS_SEL_4G:
_px4_accel.set_scale(CONSTANTS_ONE_G / 8192);
_px4_accel.set_range(4 * CONSTANTS_ONE_G);
_px4_accel.set_scale(CONSTANTS_ONE_G / 8192.f);
_px4_accel.set_range(4.f * CONSTANTS_ONE_G);
break;
case AFS_SEL_8G:
_px4_accel.set_scale(CONSTANTS_ONE_G / 4096);
_px4_accel.set_range(8 * CONSTANTS_ONE_G);
_px4_accel.set_scale(CONSTANTS_ONE_G / 4096.f);
_px4_accel.set_range(8.f * CONSTANTS_ONE_G);
break;
case AFS_SEL_16G:
_px4_accel.set_scale(CONSTANTS_ONE_G / 2048);
_px4_accel.set_range(16 * CONSTANTS_ONE_G);
_px4_accel.set_scale(CONSTANTS_ONE_G / 2048.f);
_px4_accel.set_range(16.f * CONSTANTS_ONE_G);
break;
}
}
@ -310,27 +335,31 @@ void MPU6000::ConfigureGyro()
void MPU6000::ConfigureSampleRate(int sample_rate)
{
if (sample_rate == 0) {
sample_rate = 800; // default to 800 Hz
sample_rate = 1000; // default to 1000 Hz
}
// round down to nearest FIFO sample dt * SAMPLES_PER_TRANSFER
const float min_interval = SAMPLES_PER_TRANSFER * FIFO_SAMPLE_DT;
// round down to nearest FIFO sample dt
const float min_interval = FIFO_SAMPLE_DT * 4; // limit to 2 kHz (500 us interval)
_fifo_empty_interval_us = math::max(roundf((1e6f / (float)sample_rate) / min_interval) * min_interval, min_interval);
_fifo_gyro_samples = math::min((float)_fifo_empty_interval_us / (1e6f / GYRO_RATE), (float)FIFO_MAX_SAMPLES);
_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);
_fifo_accel_samples = math::min(_fifo_empty_interval_us / (1e6f / ACCEL_RATE), (float)FIFO_MAX_SAMPLES);
}
bool MPU6000::Configure()
{
// first set and clear all configured register bits
for (const auto &reg_cfg : _register_cfg) {
RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits);
}
// now check that all are configured
bool success = true;
for (const auto &reg : _register_cfg) {
if (!RegisterCheck(reg)) {
for (const auto &reg_cfg : _register_cfg) {
if (!RegisterCheck(reg_cfg)) {
success = false;
}
}
@ -349,12 +378,13 @@ int MPU6000::DataReadyInterruptCallback(int irq, void *context, void *arg)
void MPU6000::DataReady()
{
perf_count(_drdy_interval_perf);
const uint8_t count = _drdy_count.fetch_add(1) + 1;
if (_data_ready_count.fetch_add(1) >= (_fifo_gyro_samples - 1)) {
_data_ready_count.store(0);
_fifo_watermark_interrupt_timestamp = hrt_absolute_time();
_fifo_read_samples.store(_fifo_gyro_samples);
uint8_t expected = 0;
// at least the required number of samples in the FIFO
if ((count >= _fifo_gyro_samples) && _drdy_fifo_read_samples.compare_exchange(&expected, _fifo_gyro_samples)) {
_drdy_count.store(0);
ScheduleNow();
}
}
@ -366,7 +396,7 @@ bool MPU6000::DataReadyInterruptConfigure()
}
// Setup data ready on falling edge
return px4_arch_gpiosetevent(_drdy_gpio, false, true, true, &MPU6000::DataReadyInterruptCallback, this) == 0;
return px4_arch_gpiosetevent(_drdy_gpio, false, true, true, &DataReadyInterruptCallback, this) == 0;
}
bool MPU6000::DataReadyInterruptDisable()
@ -378,7 +408,7 @@ bool MPU6000::DataReadyInterruptDisable()
return px4_arch_gpiosetevent(_drdy_gpio, false, false, false, nullptr, nullptr) == 0;
}
bool MPU6000::RegisterCheck(const register_config_t &reg_cfg, bool notify)
bool MPU6000::RegisterCheck(const register_config_t &reg_cfg)
{
bool success = true;
@ -394,16 +424,6 @@ bool MPU6000::RegisterCheck(const register_config_t &reg_cfg, bool notify)
success = false;
}
if (!success) {
RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits);
if (notify) {
perf_count(_bad_register_perf);
_px4_accel.increase_error_count();
_px4_gyro.increase_error_count();
}
}
return success;
}
@ -426,17 +446,12 @@ void MPU6000::RegisterWrite(Register reg, uint8_t value)
void MPU6000::RegisterSetAndClearBits(Register reg, uint8_t setbits, uint8_t clearbits)
{
const uint8_t orig_val = RegisterRead(reg);
uint8_t val = orig_val;
if (setbits) {
val |= setbits;
uint8_t val = (orig_val & ~clearbits) | setbits;
if (orig_val != val) {
RegisterWrite(reg, val);
}
if (clearbits) {
val &= ~clearbits;
}
RegisterWrite(reg, val);
}
uint16_t MPU6000::FIFOReadCount()
@ -454,10 +469,9 @@ uint16_t MPU6000::FIFOReadCount()
return combine(fifo_count_buf[1], fifo_count_buf[2]);
}
bool MPU6000::FIFORead(const hrt_abstime &timestamp_sample, uint16_t samples)
bool MPU6000::FIFORead(const hrt_abstime &timestamp_sample, uint8_t samples)
{
perf_begin(_transfer_perf);
FIFOTransferBuffer buffer{};
const size_t transfer_size = math::min(samples * sizeof(FIFO::DATA) + 1, FIFO::SIZE);
set_frequency(SPI_SPEED_SENSOR);
@ -470,8 +484,8 @@ bool MPU6000::FIFORead(const hrt_abstime &timestamp_sample, uint16_t samples)
perf_end(_transfer_perf);
ProcessGyro(timestamp_sample, buffer, samples);
return ProcessAccel(timestamp_sample, buffer, samples);
ProcessGyro(timestamp_sample, buffer.f, samples);
return ProcessAccel(timestamp_sample, buffer.f, samples);
}
void MPU6000::FIFOReset()
@ -485,9 +499,8 @@ void MPU6000::FIFOReset()
RegisterSetAndClearBits(Register::USER_CTRL, USER_CTRL_BIT::FIFO_RESET, USER_CTRL_BIT::FIFO_EN);
// reset while FIFO is disabled
_data_ready_count.store(0);
_fifo_watermark_interrupt_timestamp = 0;
_fifo_read_samples.store(0);
_drdy_count.store(0);
_drdy_fifo_read_samples.store(0);
// FIFO_EN: enable both gyro and accel
// USER_CTRL: re-enable FIFO
@ -498,51 +511,74 @@ void MPU6000::FIFOReset()
}
}
bool MPU6000::ProcessAccel(const hrt_abstime &timestamp_sample, const FIFOTransferBuffer &buffer, const uint8_t samples)
static bool fifo_accel_equal(const FIFO::DATA &f0, const FIFO::DATA &f1)
{
return (memcmp(&f0.ACCEL_XOUT_H, &f1.ACCEL_XOUT_H, 6) == 0);
}
bool MPU6000::ProcessAccel(const hrt_abstime &timestamp_sample, const FIFO::DATA fifo[], const uint8_t samples)
{
PX4Accelerometer::FIFOSample accel;
accel.timestamp_sample = timestamp_sample;
accel.dt = _fifo_empty_interval_us / _fifo_accel_samples;
accel.samples = 0;
accel.dt = FIFO_SAMPLE_DT * SAMPLES_PER_TRANSFER;
bool bad_data = false;
// FIFO contains 8 duplicated accel samples per gyro sample
int accel_samples = 0;
for (int i = 0; i < samples; i++) {
_fifo_accel_samples_count++;
for (int i = 0; i < samples; i = i + 8) {
const FIFO::DATA &fifo_sample = buffer.f[i];
int16_t accel_x = combine(fifo_sample.ACCEL_XOUT_H, fifo_sample.ACCEL_XOUT_L);
int16_t accel_y = combine(fifo_sample.ACCEL_YOUT_H, fifo_sample.ACCEL_YOUT_L);
int16_t accel_z = combine(fifo_sample.ACCEL_ZOUT_H, fifo_sample.ACCEL_ZOUT_L);
// only process new FIFO samples (1 every 8 samples expected)
const bool new_sample = !fifo_accel_equal(fifo[i], _fifo_sample_last_new_accel);
// 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++;
// process every 8th sample
if (_fifo_accel_samples_count == SAMPLES_PER_TRANSFER) {
int16_t accel_x = combine(fifo[i].ACCEL_XOUT_H, fifo[i].ACCEL_XOUT_L);
int16_t accel_y = combine(fifo[i].ACCEL_YOUT_H, fifo[i].ACCEL_YOUT_L);
int16_t accel_z = combine(fifo[i].ACCEL_ZOUT_H, fifo[i].ACCEL_ZOUT_L);
// 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++;
} else if (new_sample && (_fifo_accel_samples_count > 1)) {
// a new unique sample after fewer than 8 samples is an error
bad_data = true;
perf_count(_bad_transfer_perf);
}
// reset previous unique sample and counter
if (new_sample || (_fifo_accel_samples_count == SAMPLES_PER_TRANSFER)) {
_fifo_accel_samples_count = 0;
_fifo_sample_last_new_accel = fifo[i];
}
}
accel.samples = 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));
_px4_accel.updateFIFO(accel);
if (accel.samples > 0) {
_px4_accel.updateFIFO(accel);
}
return !bad_data;
}
void MPU6000::ProcessGyro(const hrt_abstime &timestamp_sample, const FIFOTransferBuffer &buffer, const uint8_t samples)
void MPU6000::ProcessGyro(const hrt_abstime &timestamp_sample, const FIFO::DATA fifo[], const uint8_t samples)
{
PX4Gyroscope::FIFOSample gyro;
gyro.timestamp_sample = timestamp_sample;
gyro.samples = samples;
gyro.dt = _fifo_empty_interval_us / _fifo_gyro_samples;
gyro.dt = FIFO_SAMPLE_DT;
for (int i = 0; i < samples; i++) {
const FIFO::DATA &fifo_sample = buffer.f[i];
const int16_t gyro_x = combine(fifo_sample.GYRO_XOUT_H, fifo_sample.GYRO_XOUT_L);
const int16_t gyro_y = combine(fifo_sample.GYRO_YOUT_H, fifo_sample.GYRO_YOUT_L);
const int16_t gyro_z = combine(fifo_sample.GYRO_ZOUT_H, fifo_sample.GYRO_ZOUT_L);
const int16_t gyro_x = combine(fifo[i].GYRO_XOUT_H, fifo[i].GYRO_XOUT_L);
const int16_t gyro_y = combine(fifo[i].GYRO_YOUT_H, fifo[i].GYRO_YOUT_L);
const int16_t gyro_z = combine(fifo[i].GYRO_ZOUT_H, fifo[i].GYRO_ZOUT_L);
// 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)
@ -551,6 +587,9 @@ void MPU6000::ProcessGyro(const hrt_abstime &timestamp_sample, const FIFOTransfe
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);
}

View File

@ -73,10 +73,10 @@ private:
void exit_and_cleanup() override;
// Sensor Configuration
static constexpr float FIFO_SAMPLE_DT{125.f};
static constexpr uint32_t SAMPLES_PER_TRANSFER{8}; // ensure at least 1 new accel sample per transfer
static constexpr float GYRO_RATE{1e6f / FIFO_SAMPLE_DT}; // 8 kHz gyro
static constexpr float ACCEL_RATE{GYRO_RATE / 8.f}; // 1 kHz accel
static constexpr float FIFO_SAMPLE_DT{1e6f / 8000.f};
static constexpr uint32_t SAMPLES_PER_TRANSFER{8}; // ensure at least 1 new accel sample per transfer
static constexpr float GYRO_RATE{1e6f / FIFO_SAMPLE_DT}; // 8000 Hz gyro
static constexpr float ACCEL_RATE{GYRO_RATE / SAMPLES_PER_TRANSFER}; // 1000 Hz accel
static constexpr uint32_t FIFO_MAX_SAMPLES{math::min(FIFO::SIZE / sizeof(FIFO::DATA), sizeof(PX4Gyroscope::FIFOSample::x) / sizeof(PX4Gyroscope::FIFOSample::x[0]))};
@ -108,20 +108,18 @@ private:
bool DataReadyInterruptConfigure();
bool DataReadyInterruptDisable();
bool RegisterCheck(const register_config_t &reg_cfg, bool notify = false);
bool RegisterCheck(const register_config_t &reg_cfg);
uint8_t RegisterRead(Register reg);
void RegisterWrite(Register reg, uint8_t value);
void RegisterSetAndClearBits(Register reg, uint8_t setbits, uint8_t clearbits);
void RegisterSetBits(Register reg, uint8_t setbits) { RegisterSetAndClearBits(reg, setbits, 0); }
void RegisterClearBits(Register reg, uint8_t clearbits) { RegisterSetAndClearBits(reg, 0, clearbits); }
uint16_t FIFOReadCount();
bool FIFORead(const hrt_abstime &timestamp_sample, uint16_t samples);
bool FIFORead(const hrt_abstime &timestamp_sample, uint8_t samples);
void FIFOReset();
bool ProcessAccel(const hrt_abstime &timestamp_sample, const FIFOTransferBuffer &buffer, const uint8_t samples);
void ProcessGyro(const hrt_abstime &timestamp_sample, const FIFOTransferBuffer &buffer, const uint8_t samples);
bool ProcessAccel(const hrt_abstime &timestamp_sample, const FIFO::DATA fifo[], const uint8_t samples);
void ProcessGyro(const hrt_abstime &timestamp_sample, const FIFO::DATA fifo[], const uint8_t samples);
void UpdateTemperature();
const spi_drdy_gpio_t _drdy_gpio;
@ -135,15 +133,19 @@ private:
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_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": DRDY interval")};
perf_counter_t _drdy_interval_perf{nullptr};
hrt_abstime _reset_timestamp{0};
hrt_abstime _last_config_check_timestamp{0};
hrt_abstime _fifo_watermark_interrupt_timestamp{0};
hrt_abstime _temperature_update_timestamp{0};
unsigned _consecutive_failures{0};
unsigned _total_failures{0};
px4::atomic<uint8_t> _data_ready_count{0};
px4::atomic<uint8_t> _fifo_read_samples{0};
FIFO::DATA _fifo_sample_last_new_accel{};
int _fifo_accel_samples_count{0};
px4::atomic<uint8_t> _drdy_fifo_read_samples{0};
px4::atomic<uint8_t> _drdy_count{0};
bool _data_ready_interrupt_enabled{false};
enum class STATE : uint8_t {
@ -157,18 +159,17 @@ private:
uint16_t _fifo_empty_interval_us{1250}; // default 1250 us / 800 Hz transfer interval
uint8_t _fifo_gyro_samples{static_cast<uint8_t>(_fifo_empty_interval_us / (1000000 / GYRO_RATE))};
uint8_t _fifo_accel_samples{static_cast<uint8_t>(_fifo_empty_interval_us / (1000000 / ACCEL_RATE))};
uint8_t _checked_register{0};
static constexpr uint8_t size_register_cfg{7};
register_config_t _register_cfg[size_register_cfg] {
// Register | Set bits, Clear bits
{ Register::PWR_MGMT_1, PWR_MGMT_1_BIT::CLKSEL_0, PWR_MGMT_1_BIT::DEVICE_RESET | PWR_MGMT_1_BIT::SLEEP },
{ Register::ACCEL_CONFIG, ACCEL_CONFIG_BIT::AFS_SEL_16G, 0 },
{ Register::GYRO_CONFIG, GYRO_CONFIG_BIT::FS_SEL_2000_DPS, 0 },
{ Register::USER_CTRL, USER_CTRL_BIT::FIFO_EN | USER_CTRL_BIT::I2C_IF_DIS, USER_CTRL_BIT::I2C_MST_EN},
{ Register::ACCEL_CONFIG, ACCEL_CONFIG_BIT::AFS_SEL_16G, 0 },
{ Register::FIFO_EN, FIFO_EN_BIT::XG_FIFO_EN | FIFO_EN_BIT::YG_FIFO_EN | FIFO_EN_BIT::ZG_FIFO_EN | FIFO_EN_BIT::ACCEL_FIFO_EN, FIFO_EN_BIT::TEMP_FIFO_EN },
{ Register::INT_PIN_CFG, INT_PIN_CFG_BIT::INT_LEVEL, 0 },
{ Register::INT_ENABLE, INT_ENABLE_BIT::DATA_RDY_INT_EN, 0 }
{ Register::INT_ENABLE, INT_ENABLE_BIT::DATA_RDY_INT_EN, 0 },
{ Register::USER_CTRL, USER_CTRL_BIT::FIFO_EN | USER_CTRL_BIT::I2C_IF_DIS, 0 },
{ Register::PWR_MGMT_1, PWR_MGMT_1_BIT::CLKSEL_0, PWR_MGMT_1_BIT::DEVICE_RESET | PWR_MGMT_1_BIT::SLEEP },
};
};