27 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT && defined(INVENSENSE_DRDY_PIN) 44 #define debug(fmt, args ...) do {printf("MPU: " fmt "\n", ## args); } while(0) 50 #ifndef INVENSENSE_EXT_SYNC_ENABLE 51 #define INVENSENSE_EXT_SYNC_ENABLE 0 55 #define MPU_SAMPLE_SIZE 14 56 #define MPU_FIFO_DOWNSAMPLE_COUNT 8 57 #define MPU_FIFO_BUFFER_LEN 64// ms of samples 59 #define int16_val(v, idx) ((int16_t)(((uint16_t)v[2*idx] << 8) | v[2*idx+1])) 60 #define uint16_val(v, idx)(((uint16_t)v[2*idx] << 8) | v[2*idx+1]) 66 static const float GYRO_SCALE = (0.0174532f / 16.4f);
70 uint16_t AP_InertialSensor_Revo::mpu_log_ptr=0;
87 , _dev(
std::move(dev))
95 if (_fifo_buffer !=
nullptr) {
120 if (!sensor || !sensor->
_init()) {
124 if (sensor->
_mpu_type == Invensense_MPU9250) {
126 }
else if (sensor->
_mpu_type == Invensense_MPU6500) {
140 bool success = _hardware_init();
151 _set_filter_register();
163 if (_mpu_type == Invensense_MPU6000 &&
179 if (_mpu_type == Invensense_ICM20608 ||
180 _mpu_type == Invensense_ICM20602) {
216 case Invensense_MPU9250:
220 case Invensense_MPU6000:
221 case Invensense_MPU6500:
222 case Invensense_ICM20608:
223 case Invensense_ICM20602:
235 case Invensense_MPU9250:
237 temp_sensitivity = 1.0/340;
240 case Invensense_MPU6000:
241 case Invensense_MPU6500:
243 temp_sensitivity = 1.0/340;
246 case Invensense_ICM20608:
247 case Invensense_ICM20602:
249 temp_sensitivity = 1.0/326.8;
261 _dev->get_semaphore()->give();
269 if (_fifo_buffer ==
nullptr) {
313 return _drdy_pin->read() != 0;
331 uint16_t new_wp = write_ptr+1;
335 if(new_wp == read_ptr) {
337 REVOMINIScheduler::MPU_buffer_overflow();
349 if(Scheduler::get_current_task() != (
void *)
task_handle) {
354 Scheduler::task_resume(task_handle);
369 for (uint8_t i = 0; i < n_samples; i++) {
372 bool fsync_set =
false;
386 float temp = t2 * temp_sensitivity + temp_zero;
395 #if 0 // filter out samples if vector length changed by 100% This is cool for debug but drops samples in the case of even weak blows 397 #define FILTER_KOEF 0.1 398 float len = accel.
length();
402 float d = abs(accel_len-len)/(accel_len+len);
404 debug(
"accel len error: mean %f got %f", accel_len, len );
407 accel_len = accel_len * (1-k) + len*k;
415 uint8_t kG = hal_param_helper->_correct_gyro;
417 float gyro_koef = 1.0 / (kG * 1000);
418 gyro_mean = gyro_mean * (1-gyro_koef) + gyro*gyro_koef;
444 bool clipped =
false;
447 for (uint8_t i = 0; i < n_samples; i++) {
462 if ((_accum.count & 1) == 0) {
467 if (fabsf(a.x) > clip_limit ||
468 fabsf(a.y) > clip_limit ||
469 fabsf(a.z) > clip_limit) {
472 _accum.accel += _accum.accel_filter.apply(a);
479 _accum.gyro += _accum.gyro_filter.apply(g);
482 if (_accum.count == MPU_FIFO_DOWNSAMPLE_COUNT) {
483 float ascale = _accel_scale / (MPU_FIFO_DOWNSAMPLE_COUNT/2);
484 _accum.accel *= ascale;
486 float gscale =
GYRO_SCALE / MPU_FIFO_DOWNSAMPLE_COUNT;
487 _accum.gyro *= gscale;
506 float temp = (
static_cast<float>(tsum)/n_samples)*temp_sensitivity + temp_zero;
514 #define MAX_NODATA_TIME 5000 // 5ms 518 uint32_t now=Scheduler::_micros();
521 uint16_t old_log_ptr=mpu_log_ptr;
523 if(mpu_log_ptr>=MPU_LOG_SIZE) mpu_log_ptr=0;
529 if(read_ptr == write_ptr) {
533 if(now - last_sample > MAX_NODATA_TIME) {
537 REVOMINIScheduler::MPU_restarted();
551 while(read_ptr != write_ptr) {
559 if (_fast_sampling) {
560 if (!_accumulate_sensor_rate_sampling(rx, 1)) {
566 if (!_accumulate(rx, 1)) {
573 now = Scheduler::_micros();
578 mpu_log_ptr = old_log_ptr;
583 REVOMINIScheduler::MPU_stats(count,dt);
588 Scheduler::resume_boost();
596 if (abs(t2 - _raw_temp) < 400) {
604 return (abs(t2 - _raw_temp) < 400);
610 return _dev->read_registers(reg, buf, size);
616 _dev->read_registers(reg, &val, 1);
622 _dev->write_register(reg, val, checked);
632 #if INVENSENSE_EXT_SYNC_ENABLE 641 if (_fast_sampling) {
660 if (_fast_sampling) {
671 if (_mpu_type != Invensense_MPU6000) {
672 if (_fast_sampling) {
689 _mpu_type = Invensense_MPU6000;
692 _mpu_type = Invensense_MPU6500;
696 _mpu_type = Invensense_MPU9250;
699 _mpu_type = Invensense_ICM20608;
702 _mpu_type = Invensense_ICM20602;
717 _dev->setup_checked_registers(7, 20);
722 if (!_check_whoami()) {
723 _dev->get_semaphore()->give();
729 for (tries = 0; tries < 5; tries++) {
736 _last_stat_user_ctrl &= ~BIT_USER_CTRL_I2C_MST_EN;
777 _dev->get_semaphore()->give();
781 printf(
"Failed to boot Invensense 5 times\n");
786 if (_mpu_type == Invensense_ICM20608 ||
787 _mpu_type == Invensense_ICM20602) {
int printf(const char *fmt,...)
#define HAL_INS_MPU60XX_SPI
#define MPUREG_SMPLRT_DIV
void set_gyro_orientation(uint8_t instance, enum Rotation rotation)
#define BITS_DLPF_CFG_188HZ
Vector3< float > Vector3f
#define HAL_INS_MPU9250_SPI
#define MPUREG_INT_PIN_CFG
uint8_t _gyro_instance[INS_MAX_INSTANCES]
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
#define BITS_GYRO_FS_2000DPS
#define MPUREG_INT_ENABLE
#define MPU_FIFO_BUFFER_LEN
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
#define ICM_ACC_FCHOICE_B
#define BIT_USER_CTRL_I2C_MST_EN
#define MPUREG_PRODUCT_ID
#define BITS_DLPF_CFG_256HZ_NOLPF2
bool _check_raw_temp(int16_t t2)
virtual T apply(T sample)
#define HAL_SEMAPHORE_BLOCK_FOREVER
bool enable_fast_sampling(uint8_t instance)
AP_InertialSensor_Revo(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation rotation)
#define MPUREG_I2C_SLV4_CTRL
#define ICM_ACC_DLPF_CFG_218HZ
void _set_gyro_oversampling(uint8_t instance, uint8_t n)
virtual void free_type(void *ptr, size_t size, Memory_Type mem_type)
void _set_filter_register(void)
#define BIT_USER_CTRL_I2C_IF_DIS
void _register_write(uint8_t reg, uint8_t val, bool checked=false)
#define debug(fmt, args ...)
enum Invensense_Type _mpu_type
#define MPUREG_CONFIG_EXT_SYNC_SHIFT
virtual void mode(uint8_t output)=0
#define MPUREG_ACCEL_CONFIG
virtual void delay(uint16_t ms)=0
#define BIT_PWR_MGMT_1_CLK_ZGYRO
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
uint8_t _accel_instance[INS_MAX_INSTANCES]
static AP_HAL::OwnPtr< AP_HAL::Device > dev
static void * task_handle
bool is_zero(const T fVal1)
#define MPU_WHOAMI_MPU9250
void increment_clip_count(uint8_t instance)
#define MPU_WHOAMI_MPU9255
virtual ~AP_InertialSensor_Revo()
virtual AP_HAL::DigitalSource * channel(uint16_t n)=0
void _notify_new_gyro_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0)
#define int16_val(v, idx)
#define MPUREG_ICM_UNDOC1_VALUE
void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro)
#define ICMREG_ACCEL_CONFIG2
AverageFilterUInt16_Size4 _temp_filter
#define INVENSENSE_DRDY_PIN
static constexpr float FILTER_KOEF
bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size)
#define MPUREG_PWR_MGMT_1
void _notify_new_accel_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0, bool fsync_set=false)
#define MPUREG_INT_STATUS
virtual void * malloc_type(size_t size, Memory_Type mem_type)
void _publish_temperature(uint8_t instance, float temperature)
uint8_t _register_read(uint8_t reg)
#define MPUREG_GYRO_CONFIG
void set_read_flag(uint8_t flag)
void set_accel_orientation(uint8_t instance, enum Rotation rotation)
#define MPUREG_ICM_UNDOC1
void update_gyro(uint8_t instance)
#define MPUREG_PWR_MGMT_2
#define MPUREG_TEMP_OUT_H
#define MPUREG_CONFIG_EXT_SYNC_AZ
virtual void delay_microseconds(uint16_t us)=0
void _set_accel_oversampling(uint8_t instance, uint8_t n)
bool _accumulate_sensor_rate_sampling(uint8_t *samples, uint8_t n_samples)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
bool _accumulate(uint8_t *samples, uint8_t n_samples)
void accumulate() override
void panic(const char *errormsg,...) FMT_PRINTF(1
static const float GYRO_SCALE
#define BIT_PWR_MGMT_1_DEVICE_RESET
void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel)
#define MPUREG_CONFIG_FIFO_MODE_STOP
void update_accel(uint8_t instance)
#define MPUREG_ACCEL_XOUT_H
#define AP_INERTIAL_SENSOR_ACCEL_CLIP_THRESH_MSS
AP_HAL::Scheduler * scheduler