DoubleFusedGeomagneticAttitudeEstimator2

class DoubleFusedGeomagneticAttitudeEstimator2(val context: Context, location: Location? = null, val sensorDelay: SensorDelay = SensorDelay.GAME, val useAccelerometer: Boolean = true, val startOffsetEnabled: Boolean = true, val accelerometerSensorType: AccelerometerSensorType = AccelerometerSensorType.ACCELEROMETER_UNCALIBRATED, val magnetometerSensorType: MagnetometerSensorType = MagnetometerSensorType.MAGNETOMETER_UNCALIBRATED, val accelerometerAveragingFilter: AveragingFilter = LowPassAveragingFilter(), val gyroscopeSensorType: GyroscopeSensorType = GyroscopeSensorType.GYROSCOPE_UNCALIBRATED, worldMagneticModel: WorldMagneticModel? = null, timestamp: Date = Date(), useWorldMagneticModel: Boolean = false, useAccurateLevelingEstimator: Boolean = false, useAccurateRelativeGyroscopeAttitudeEstimator: Boolean = false, val estimateCoordinateTransformation: Boolean = false, val estimateEulerAngles: Boolean = true, var attitudeAvailableListener: DoubleFusedGeomagneticAttitudeEstimator2.OnAttitudeAvailableListener? = null, var accuracyChangedListener: DoubleFusedGeomagneticAttitudeEstimator2.OnAccuracyChangedListener? = null, var bufferFilledListener: DoubleFusedGeomagneticAttitudeEstimator2.OnBufferFilledListener? = null, adjustGravityNorm: Boolean = true)

Estimates a double fused absolute attitude, where accelerometer + magnetometer measurements are fused with leveled relative attitude obtained from gyroscope ones.

Parameters

location

Device location.

worldMagneticModel

Earth's magnetic model. Null to use default model when useWorldMagneticModel is true. If useWorldMagneticModel is false, this is ignored.

timestamp

Timestamp when World Magnetic Model will be evaluated to obtain current. Only taken into account if useWorldMagneticModel is tue.

useWorldMagneticModel

true so that world magnetic model is taken into account to adjust attitude yaw angle by current magnetic declination based on current World Magnetic Model, location and timestamp, false to ignore declination.

useAccurateLevelingEstimator

true to use accurate leveling, false to use a normal one.

useAccurateRelativeGyroscopeAttitudeEstimator

true to use accurate non-leveled relative attitude estimator, false to use non-accurate non-leveled relative attitude estimator.

Constructors

Link copied to clipboard
constructor(context: Context, location: Location? = null, sensorDelay: SensorDelay = SensorDelay.GAME, useAccelerometer: Boolean = true, startOffsetEnabled: Boolean = true, accelerometerSensorType: AccelerometerSensorType = AccelerometerSensorType.ACCELEROMETER_UNCALIBRATED, magnetometerSensorType: MagnetometerSensorType = MagnetometerSensorType.MAGNETOMETER_UNCALIBRATED, accelerometerAveragingFilter: AveragingFilter = LowPassAveragingFilter(), gyroscopeSensorType: GyroscopeSensorType = GyroscopeSensorType.GYROSCOPE_UNCALIBRATED, worldMagneticModel: WorldMagneticModel? = null, timestamp: Date = Date(), useWorldMagneticModel: Boolean = false, useAccurateLevelingEstimator: Boolean = false, useAccurateRelativeGyroscopeAttitudeEstimator: Boolean = false, estimateCoordinateTransformation: Boolean = false, estimateEulerAngles: Boolean = true, attitudeAvailableListener: DoubleFusedGeomagneticAttitudeEstimator2.OnAttitudeAvailableListener? = null, accuracyChangedListener: DoubleFusedGeomagneticAttitudeEstimator2.OnAccuracyChangedListener? = null, bufferFilledListener: DoubleFusedGeomagneticAttitudeEstimator2.OnBufferFilledListener? = null, adjustGravityNorm: Boolean = true)

Types

Link copied to clipboard

Interface to notify when sensor (either accelerometer, gravity or magnetometer) accuracy changes.

Link copied to clipboard

Interface to notify when a new attitude measurement is available.

Link copied to clipboard

Interface to notify when a buffer gets completely filled. When buffers get filled, internal collectors will continue collection at the expense of loosing old data. Consumers of this listener should device what to do at this point (which might require stopping this estimator)..

Properties

Link copied to clipboard

an averaging filter for accelerometer samples to obtain sensed gravity component of specific force. (Only used if useAccelerometer is true).

Link copied to clipboard

One of the supported accelerometer sensor types. (Only used if useAccelerometer is true).

Link copied to clipboard

Indicates whether gravity norm must be adjusted to either Earth standard norm, or norm at provided location. If no location is provided, this should only be enabled when device is close to sea level.

Link copied to clipboard

listener to notify when a new attitude measurement is available.

Link copied to clipboard

listener to notify that some buffer has been filled. This usually happens when consumer of measurements cannot keep up with the rate at which measurements are generated.

Link copied to clipboard

Android context.

Link copied to clipboard

true to estimate coordinate transformation, false otherwise. If not needed, it can be disabled to improve performance and decrease cpu load.

Link copied to clipboard

true to estimate euler angles, false otherwise. If not needed, it can be disabled to improve performance and decrease cpu load.

Link copied to clipboard

One of the supported gyroscope sensor types.

Link copied to clipboard

Time interval expressed in seconds between consecutive gyroscope measurements

Link copied to clipboard

Factor to take into account when interpolation value is computed and useIndirectInterpolation is enabled to determine actual interpolation value based on current relative attitude rotation velocity.

Link copied to clipboard

Interpolation value to be used to combine both geomagnetic and relative attitudes. Must be between 0.0 and 1.0 (both included). The closer to 0.0 this value is, the more resemblance the result will have to a pure geomagnetic (which feels more jerky when using accelerometer). On the contrary, the closer to 1.0 this value is, the more resemblance the result will have to a pure non-leveled relative attitude (which feels softer but might have arbitrary roll pitch and yaw Euler angles).

Link copied to clipboard

Gets or sets device location

Link copied to clipboard

One of the supported magnetometer sensor types.

Link copied to clipboard

Threshold to determine that geomagnetic attitude has largely diverged and if situation is not reverted soon, attitude will be reset to geomagnetic one.

Link copied to clipboard

Threshold to determine that current geomagnetic attitude appears to be an outlier respect to estimated fused attitude. When geomagnetic attitude and fused attitudes diverge, fusion is not performed, and instead only gyroscope relative attitude is used for fusion estimation.

Link copied to clipboard

Threshold to determine when fused attitude has largely diverged for a given number of samples and must be reset.

Link copied to clipboard

Indicates whether this estimator is running or not.

Link copied to clipboard

Delay of sensors between samples.

Link copied to clipboard

indicates whether start offsets will be computed when first measurement is received or not. True indicates that offset is computed, false assumes that offset is null.

Link copied to clipboard

Gets or sets timestamp when World Magnetic Model will be evaluated to obtain current magnetic declination. Only taken into account if useWorldMagneticModel is true.

Link copied to clipboard

true to use accelerometer sensor, false to use system gravity sensor for leveling purposes.

Link copied to clipboard

Indicates whether accurate leveling must be used or not.

Indicates whether accurate non-leveled relative attitude estimator must be used or not.

Link copied to clipboard

Indicates whether fusion between leveling and relative attitudes occurs based on changing interpolation value that depends on actual relative attitude rotation velocity.

Link copied to clipboard

Indicates whether world magnetic model is taken into account to adjust attitude yaw angle by current magnetic declination based on current World Magnetic Model, location and timestamp.

Link copied to clipboard
var worldMagneticModel: WorldMagneticModel?

Earth's magnetic model. If null, the default model is used if useWorldMagneticModel is true. If useWorldMagneticModel is false, this is ignored.

Functions

Link copied to clipboard
fun start(startTimestamp: Long = SystemClock.elapsedRealtimeNanos()): Boolean

Starts this estimator.

Link copied to clipboard
fun stop()

Stops this estimator.