@ -40,6 +40,8 @@
@@ -40,6 +40,8 @@
extern const AP_HAL : : HAL & hal ;
# if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
# define DEFAULT_GYRO_FILTER 20
# define DEFAULT_ACCEL_FILTER 20
@ -54,6 +56,12 @@ extern const AP_HAL::HAL& hal;
@@ -54,6 +56,12 @@ extern const AP_HAL::HAL& hal;
# define DEFAULT_STILL_THRESH 0.1f
# endif
# if defined(STM32H7) || defined(STM32F7)
# define MPU_FIFO_FASTSAMPLE_DEFAULT 1
# else
# define MPU_FIFO_FASTSAMPLE_DEFAULT 0
# endif
# define SAMPLE_UNIT 1
# define GYRO_INIT_MAX_DIFF_DPS 0.1f
@ -493,6 +501,14 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = {
@@ -493,6 +501,14 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = {
// @Path: ../Filter/HarmonicNotchFilter.cpp
AP_SUBGROUPINFO ( _harmonic_notch_filter , " HNTCH_ " , 41 , AP_InertialSensor , HarmonicNotchFilterParams ) ,
// @Param: GYRO_RATE
// @DisplayName: Gyro rate for IMUs with Fast Sampling enabled
// @Description: Gyro rate for IMUs with fast sampling enabled. The gyro rate is the sample rate at which the IMU filters operate and needs to be at least double the maximum filter frequency. If the sensor does not support the selected rate the next highest supported rate will be used. For IMUs which do not support fast sampling this setting is ignored and the default gyro rate of 1Khz is used.
// @User: Advanced
// @Values: 0:1 kHz,1:2 kHz,3:4 kHz
// @RebootRequired: True
AP_GROUPINFO ( " GYRO_RATE " , 42 , AP_InertialSensor , _fast_sampling_rate , MPU_FIFO_FASTSAMPLE_DEFAULT ) ,
/*
NOTE : parameter indexes have gaps above . When adding new
parameters check for conflicts carefully
@ -681,11 +697,11 @@ bool AP_InertialSensor::set_gyro_window_size(uint16_t size) {
@@ -681,11 +697,11 @@ bool AP_InertialSensor::set_gyro_window_size(uint16_t size) {
}
void
AP_InertialSensor : : init ( uint16_t sample _rate)
AP_InertialSensor : : init ( uint16_t loop _rate)
{
// remember the sample rate
_sample_rate = sample _rate ;
_loop_delta_t = 1.0f / sample _rate;
_loop_rate = loop _rate ;
_loop_delta_t = 1.0f / loop _rate;
// we don't allow deltat values greater than 10x the normal loop
// time to be exposed outside of INS. Large deltat values can
@ -709,7 +725,7 @@ AP_InertialSensor::init(uint16_t sample_rate)
@@ -709,7 +725,7 @@ AP_InertialSensor::init(uint16_t sample_rate)
init_gyro ( ) ;
}
_sample_period_usec = 1000 * 1000UL / _sample _rate ;
_sample_period_usec = 1000 * 1000UL / _loop _rate ;
// establish the baseline time between samples
_delta_time = 0 ;
@ -979,6 +995,16 @@ AP_InertialSensor::init_gyro()
@@ -979,6 +995,16 @@ AP_InertialSensor::init_gyro()
_save_gyro_calibration ( ) ;
}
// output GCS startup messages
bool AP_InertialSensor : : get_output_banner ( uint8_t backend_id , char * banner , uint8_t banner_len )
{
if ( backend_id > = INS_MAX_BACKENDS | | _backends [ backend_id ] = = nullptr ) {
return false ;
}
return _backends [ backend_id ] - > get_output_banner ( banner , banner_len ) ;
}
// accelerometer clipping reporting
uint32_t AP_InertialSensor : : get_accel_clip_count ( uint8_t instance ) const
{
@ -1055,7 +1081,7 @@ bool AP_InertialSensor::calibrate_trim(float &trim_roll, float &trim_pitch)
@@ -1055,7 +1081,7 @@ bool AP_InertialSensor::calibrate_trim(float &trim_roll, float &trim_pitch)
_calibrating = true ;
const uint8_t update_dt_milliseconds = ( uint8_t ) ( 1000.0f / get_sample_rate ( ) + 0.5f ) ;
const uint8_t update_dt_milliseconds = ( uint8_t ) ( 1000.0f / get_loop_rate_hz ( ) + 0.5f ) ;
// wait 100ms for ins filter to rise
for ( uint8_t k = 0 ; k < 100 / update_dt_milliseconds ; k + + ) {