mirror of https://github.com/ArduPilot/ardupilot
Added heavily filtered Accelerometer values for experimentation.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2779 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
5e163c6052
commit
a16b00b5bf
|
@ -278,6 +278,10 @@ AP_IMU_Oilpan::update(void)
|
||||||
_accel.y = _accel_scale * _sensor_in(4, tc_temp);
|
_accel.y = _accel_scale * _sensor_in(4, tc_temp);
|
||||||
_accel.z = _accel_scale * _sensor_in(5, tc_temp);
|
_accel.z = _accel_scale * _sensor_in(5, tc_temp);
|
||||||
|
|
||||||
|
_accel_filtered.x = _accel_filtered.x * .98 + _accel.x * .02;
|
||||||
|
_accel_filtered.y = _accel_filtered.y * .98 + _accel.y * .02;
|
||||||
|
_accel_filtered.z = _accel_filtered.z * .98 + _accel.z * .02;
|
||||||
|
|
||||||
// always updated
|
// always updated
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -70,6 +70,12 @@ public:
|
||||||
///
|
///
|
||||||
Vector3f get_accel(void) { return _accel; }
|
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; }
|
||||||
|
|
||||||
/// A count of bad sensor readings
|
/// A count of bad sensor readings
|
||||||
///
|
///
|
||||||
/// @todo This should be renamed, as there's no guarantee that sensors
|
/// @todo This should be renamed, as there's no guarantee that sensors
|
||||||
|
@ -80,6 +86,7 @@ public:
|
||||||
protected:
|
protected:
|
||||||
/// Most recent accelerometer reading obtained by ::update
|
/// Most recent accelerometer reading obtained by ::update
|
||||||
Vector3f _accel;
|
Vector3f _accel;
|
||||||
|
Vector3f _accel_filtered;
|
||||||
|
|
||||||
/// Most recent gyro reading obtained by ::update
|
/// Most recent gyro reading obtained by ::update
|
||||||
Vector3f _gyro;
|
Vector3f _gyro;
|
||||||
|
|
Loading…
Reference in New Issue