mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_InertialSensor: removed unused variables
thanks to Francisco for noticing
This commit is contained in:
parent
86c8145bd9
commit
6af00027ab
@ -443,7 +443,6 @@ void AP_InertialSensor_MPU9250::_accumulate(uint8_t *samples, uint8_t n_samples)
|
||||
|
||||
void AP_InertialSensor_MPU9250::_accumulate_fast_sampling(uint8_t *samples, uint8_t n_samples)
|
||||
{
|
||||
Vector3l asum, gsum;
|
||||
float tsum = 0;
|
||||
const int32_t clip_limit = AP_INERTIAL_SENSOR_ACCEL_CLIP_THRESH_MSS / MPU9250_ACCEL_SCALE_1G;
|
||||
bool clipped = false;
|
||||
|
Loading…
Reference in New Issue
Block a user