@@ -348,10 +348,6 @@ void AP_InertialSensor_Invensensev3::start()
348
348
return ;
349
349
}
350
350
351
- // update backend sample rate
352
- _set_accel_raw_sample_rate (accel_instance, backend_rate_hz);
353
- _set_gyro_raw_sample_rate (gyro_instance, backend_rate_hz);
354
-
355
351
// indicate what multiplier is appropriate for the sensors'
356
352
// readings to fit them into an int16_t:
357
353
_set_raw_sample_accel_multiplier (accel_instance, multiplier_accel);
@@ -381,16 +377,15 @@ void AP_InertialSensor_Invensensev3::start()
381
377
382
378
// get a startup banner to output to the GCS
383
379
bool AP_InertialSensor_Invensensev3::get_output_banner (char * banner, uint8_t banner_len) {
384
- if (fast_sampling) {
385
- snprintf (banner, banner_len, " IMU%u: fast%s sampling enabled %.1fkHz " ,
386
- gyro_instance ,
380
+ snprintf (banner, banner_len, " IMU%u:%s%s sampling BR:%.1fkHz SR:%.1fkHz " ,
381
+ gyro_instance ,
382
+ fast_sampling ? " fast " : " normal " ,
387
383
#if HAL_INS_HIGHRES_SAMPLE
388
- highres_sampling ? " , high-resolution " :
384
+ highres_sampling ? " hi-res " :
389
385
#endif
390
- " " , backend_rate_hz * 0.001 );
391
- return true ;
392
- }
393
- return false ;
386
+ " " , backend_rate_hz * 0.001 ,
387
+ sampling_rate_hz * 0.001 );
388
+ return true ;
394
389
}
395
390
396
391
/*
@@ -806,6 +801,7 @@ void AP_InertialSensor_Invensensev3::set_filter_and_scaling(void)
806
801
}
807
802
}
808
803
}
804
+ sampling_rate_hz = backend_rate_hz; // sampling rate and backend rate are the same
809
805
810
806
// disable gyro and accel as per 12.9 in the ICM-42688 docs
811
807
register_write (INV3REG_PWR_MGMT0, 0x00 );
@@ -862,6 +858,7 @@ void AP_InertialSensor_Invensensev3::set_filter_and_scaling(void)
862
858
void AP_InertialSensor_Invensensev3::set_filter_and_scaling_icm42670 (void )
863
859
{
864
860
backend_rate_hz = 1600 ;
861
+ sampling_rate_hz = 1600 ;
865
862
// use low-noise mode
866
863
register_write (INV3REG_70_PWR_MGMT0, 0x0f );
867
864
hal.scheduler ->delay_microseconds (300 );
@@ -886,27 +883,24 @@ void AP_InertialSensor_Invensensev3::set_filter_and_scaling_icm42670(void)
886
883
*/
887
884
void AP_InertialSensor_Invensensev3::set_filter_and_scaling_icm456xy (void )
888
885
{
889
- uint8_t odr_config = 4 ;
890
- backend_rate_hz = 1600 ;
891
- // always fast sampling
892
- fast_sampling = dev->bus_type () == AP_HAL::Device::BUS_TYPE_SPI;
886
+ uint8_t odr_config;
887
+ backend_rate_hz = 800 ;
893
888
894
- if (enable_fast_sampling (accel_instance) && get_fast_sampling_rate () > 1 ) {
895
- backend_rate_hz = calculate_fast_sampling_backend_rate (backend_rate_hz, backend_rate_hz * 4 );
889
+ fast_sampling = dev->bus_type () == AP_HAL::Device::BUS_TYPE_SPI;
890
+ if (enable_fast_sampling (accel_instance) && get_fast_sampling_rate () && fast_sampling) {
891
+ // For ICM45686 we only set 3200 or 6400Hz as sampling rates
892
+ // we don't need to read FIFO faster than requested rate
893
+ backend_rate_hz = calculate_fast_sampling_backend_rate (800 , 6400 );
894
+ } else {
895
+ fast_sampling = false ;
896
896
}
897
897
898
- // this sensor actually only supports 2 speeds
899
- backend_rate_hz = constrain_int16 (backend_rate_hz, 3200 , 6400 );
900
-
901
- switch (backend_rate_hz) {
902
- case 6400 : // 6.4Khz
903
- odr_config = 3 ;
904
- break ;
905
- case 3200 : // 3.2Khz
906
- odr_config = 4 ;
907
- break ;
908
- default :
909
- break ;
898
+ if (backend_rate_hz <= 3200 ) {
899
+ odr_config = 0x04 ; // 3200Hz
900
+ sampling_rate_hz = 3200 ;
901
+ } else {
902
+ odr_config = 0x03 ; // 6400Hz
903
+ sampling_rate_hz = 6400 ;
910
904
}
911
905
912
906
// Disable FIFO first
0 commit comments