mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: stop sensors converging if motors arm
if the user arms within 30s of startup then stop the re-init of the sensors. This can give less accurate frequency as the sample rate may not have settled yet, but it is better than doing init of the filters while the vehicle may be flying also fix a 32 bit millis wrap
This commit is contained in:
parent
6a5889726c
commit
d34c1940c4
|
@ -54,6 +54,15 @@ void AP_InertialSensor_Backend::_set_gyro_oversampling(uint8_t instance, uint8_t
|
|||
_imu._gyro_over_sampling[instance] = n;
|
||||
}
|
||||
|
||||
/*
|
||||
while sensors are converging to get the true sample rate we re-init the notch filters.
|
||||
stop doing this if the user arms
|
||||
*/
|
||||
bool AP_InertialSensor_Backend::sensors_converging() const
|
||||
{
|
||||
return AP_HAL::millis64() < HAL_INS_CONVERGANCE_MS && !hal.util->get_soft_armed();
|
||||
}
|
||||
|
||||
/*
|
||||
update the sensor rate for FIFO sensors
|
||||
|
||||
|
|
|
@ -212,7 +212,7 @@ protected:
|
|||
void _update_sensor_rate(uint16_t &count, uint32_t &start_us, float &rate_hz) const __RAMFUNC__;
|
||||
|
||||
// return true if the sensors are still converging and sampling rates could change significantly
|
||||
bool sensors_converging() const { return AP_HAL::millis() < HAL_INS_CONVERGANCE_MS; }
|
||||
bool sensors_converging() const;
|
||||
|
||||
// set accelerometer max absolute offset for calibration
|
||||
void _set_accel_max_abs_offset(uint8_t instance, float offset);
|
||||
|
|
Loading…
Reference in New Issue