mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
IMU: removed unused accel_filtered code
This commit is contained in:
parent
ac44b73951
commit
b32701e008
@ -232,10 +232,6 @@ AP_IMU_INS::update(void)
|
||||
_accel.y = _calibrated(4, accels[1]);
|
||||
_accel.z = _calibrated(5, accels[2]);
|
||||
|
||||
_accel_filtered.x = _accel_filtered.x / 2 + _accel.x / 2;
|
||||
_accel_filtered.y = _accel_filtered.y / 2 + _accel.y / 2;
|
||||
_accel_filtered.z = _accel_filtered.z / 2 + _accel.z / 2;
|
||||
|
||||
// always updated
|
||||
return true;
|
||||
}
|
||||
|
@ -75,12 +75,6 @@ public:
|
||||
Vector3f get_accel(void) { return _accel; }
|
||||
|
||||
|
||||
/// Fetch the current accelerometer values
|
||||
///
|
||||
/// @returns vector of current accelerations in m/s/s
|
||||
///
|
||||
Vector3f get_accel_filtered(void) { return _accel_filtered; }
|
||||
|
||||
/// return the number of seconds that the last update represents
|
||||
///
|
||||
/// @returns number of seconds
|
||||
@ -112,7 +106,6 @@ protected:
|
||||
|
||||
/// Most recent accelerometer reading obtained by ::update
|
||||
Vector3f _accel;
|
||||
Vector3f _accel_filtered;
|
||||
|
||||
/// Most recent gyro reading obtained by ::update
|
||||
Vector3f _gyro;
|
||||
|
Loading…
Reference in New Issue
Block a user