LocalPoseEstimator

constructor(context: Context, location: Location, initialVelocity: NEDVelocity = NEDVelocity(), sensorDelay: SensorDelay = SensorDelay.GAME, useAccelerometerForAttitudeEstimation: Boolean = false, accelerometerSensorType: AccelerometerSensorType = AccelerometerSensorType.ACCELEROMETER_UNCALIBRATED, gyroscopeSensorType: GyroscopeSensorType = GyroscopeSensorType.GYROSCOPE_UNCALIBRATED, magnetometerSensorType: MagnetometerSensorType = MagnetometerSensorType.MAGNETOMETER_UNCALIBRATED, accelerometerAveragingFilter: AveragingFilter = LowPassAveragingFilter(), worldMagneticModel: WorldMagneticModel? = null, timestamp: Date = Date(), useWorldMagneticModel: Boolean = false, useAccurateLevelingEstimator: Boolean = true, useAccurateRelativeGyroscopeAttitudeEstimator: Boolean = true, useAccurateAttitudeEstimator: Boolean = true, estimatePoseTransformation: Boolean = false, poseAvailableListener: LocalPoseEstimator.OnPoseAvailableListener? = null, accelerometerMeasurementListener: AccelerometerSensorCollector.OnMeasurementListener? = null, gyroscopeMeasurementListener: GyroscopeSensorCollector.OnMeasurementListener? = null, magnetometerMeasurementListener: MagnetometerSensorCollector.OnMeasurementListener? = null, gravityEstimationListener: GravityEstimator.OnEstimationListener? = null)

Constructor.

Parameters

context

Android context.

location

current device location.

initialVelocity

initial velocity of device expressed in NED coordinates.

sensorDelay

Delay of sensors between samples.

accelerometerSensorType

One of the supported accelerometer sensor types. It is suggested to avoid using non-calibrated accelerometers.

gyroscopeSensorType

One of the supported gyroscope sensor types. It is suggested to avoid using non-calibrated gyroscopes.

magnetometerSensorType

One of the supported magnetometer sensor types.

accelerometerAveragingFilter

an averaging filter for accelerometer samples to obtain sensed gravity component of specific force.

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.

useAccurateAttitudeEstimator

true to use accurate absolute attitude estimator, false otherwise.

estimatePoseTransformation

true to estimate 3D metric pose transformation, false to skip transformation computation.

poseAvailableListener

notifies when a new estimated pose is available.

accelerometerMeasurementListener

listener to notify new accelerometer measurements.

gyroscopeMeasurementListener

listener to notify new gyroscope measurements.

magnetometerMeasurementListener

listener to notify new magnetometer measurements.

gravityEstimationListener

listener to notify when a new gravity estimation is available.