53 : ExposureRecordHistory(100), LastMessageExposureFrame(
NULL),
54 FocusDirection(
Vector3d(0, 0, 0)), FocusFOV(0.0),
55 FAccelInImuFrame(1000), FAccelInCameraFrame(1000), FAngV(20),
56 EnableGravity(true), EnableYawCorrection(true), MagCalibrated(false),
57 EnableCameraTiltCorrection(true),
58 MotionTrackingEnabled(true), VisionPositionEnabled(true),
256 record.ImuOnlyDelta = delta;
260 if (record.VisionTrackingAvailable)
334 if ((
Stage & 0xFF) == 0)
425 double angle = from.
Angle(to);
426 return Quatd(axis, angle);
434 double phi = atan2(error.
w, error.
y);
444 const Vector3d gainAccel = gainVel * 0.5;
445 const double snapThreshold = 0.1;
447 Vector3d correctionPos, correctionVel;
487 const double gain = 0.25;
488 const double snapThreshold = 0.1;
493 if (
Alg::Abs(yawError.
w) < cos(snapThreshold / 2))
495 correction = yawError;
497 correction = yawError.
Nlerp(
Quatd(), gain * deltaT);
513 const double maxMagRefDist = 0.1;
514 const double maxTiltError = 0.05;
515 const double proportionalGain = 0.01;
516 const double integralGain = 0.0005;
520 if (magInWorldFrame.
x * magInWorldFrame.
x + magInWorldFrame.
z * magInWorldFrame.
z < minMagLengthSq)
536 double bestDist = maxMagRefDist;
537 for (
unsigned int i = 0; i <
MagRefs.GetSize(); i++)
560 if (
Alg::Abs(magRefInWorldFrame.
y - magInWorldFrame.
y) > maxTiltError)
573 magInWorldFrame.
y = magRefInWorldFrame.
y = 0;
576 Quatd correction = yawError.
Nlerp(
Quatd(), proportionalGain * deltaT) *
586 const double gain = 0.25;
587 const double snapThreshold = 0.1;
600 correction = error.
Nlerp(
Quatd(), gain * deltaT);
610 const double snapThreshold = 0.02;
611 const double maxCameraPositionOffset = 0.2;
612 const Vector3d up(0, 1, 0), forward(0, 0, -1);
630 Quatd error = error2 * error1;
641 double confidenceThreshold = 0.75f;
652 (
Alg::Abs(error.
w) < cos(snapThreshold / 2) && confidence > confidenceThreshold))
672 if (newWorldFromCamera.
Translation.
DistanceSq(DefaultWorldFromCamera.Translation) > maxCameraPositionOffset * maxCameraPositionOffset)
673 newWorldFromCamera.
Translation = DefaultWorldFromCamera.Translation;
693 double angle = focusYawComponent.
Angle(currentYawComponent);
702 double lAngle = lFocus.
Angle(currentYawComponent);
703 double rAngle = rFocus.
Angle(currentYawComponent);
759 OVR_ASSERT ( ( neckeye[0] > 0.05f ) && ( neckeye[0] < 0.5f ) );
760 OVR_ASSERT ( ( neckeye[1] > 0.05f ) && ( neckeye[1] < 0.5f ) );
773 float screenCenterToMidplate = 0.02733f;
795 if ( resetNeckPivot )
827 const double linearCoef = 1.0;
829 double angularSpeed = angularVelocity.
Length();
834 const double slope = 0.2;
835 double candidateDt = slope * speed;
837 double dynamicDt = predictionDt;
840 if (candidateDt < predictionDt)
841 dynamicDt = candidateDt;
843 if (angularSpeed > 0.001)
Vector3d GetFilteredValue() const
SensorState GetSensorStateAtTime(double absoluteTime) const
virtual void OnVisionPreviousFrame(const Transform< double > &cameraFromImu)
float GetCenterPupilDepth() const
void LogText(const char *fmt,...) OVR_LOG_VAARG_ATTRIBUTE(1
PositionTypeEnum PositionType
void SetCenterPupilDepth(float centerPupilDepth)
void StoreAndIntegrateGyro(Vector3d angVel, double dt)
double LastVisionAbsoluteTime
double Confidence() const
void applyMagYawCorrection(Vector3d mag, double deltaT)
Vector3 Cross(const Vector3 &b) const
LocklessUpdater< LocklessState > UpdatedState
PoseState< double > WorldFromImu
PoseState< double > ImuOnlyDelta
T Distance(Vector3 const &b) const
double TPH_CameraPoseConfidenceThresholdOverrideIfNonZero
virtual UByte GetDeviceInterfaceVersion()=0
virtual void OnMessage(const Message &msg)
#define OVR_KEY_NECK_TO_EYE_DISTANCE
bool AttachToSensor(SensorDevice *sensor)
double WorldFromCameraConfidence
virtual Transform< double > GetVisionPrediction(UInt32 exposureCounter)
Vector3 ProjectToPlane(const Vector3 &normal) const
void SetHeadModel(const Vector3f &headModel, bool resetNeckPivot=true)
void AdvanceByDelta(const PoseState< T > &delta)
OVR_FORCE_INLINE void RecordDeviceIfcVersion(UByte)
Quatd vectorAlignmentRotation(const Vector3d &from, const Vector3d &to)
static Transform< double > calcPredictedPose(const PoseState< double > &poseState, double predictionDt)
const Transformd DefaultWorldFromCamera(Quatd(), Vector3d(0, 0,-1))
void applyTiltCorrection(double deltaT)
Quatd extractYawRotation(const Quatd &error)
Vector3< T > Rotate(const Vector3< T > &v) const
Transform< double > Transformd
void Update(Vector3d value, double deltaT, Quatd deltaQ=Quatd())
virtual bool IsMagCalibrated()
Vector3< T > AngularAcceleration
void handleMessage(const MessageBodyFrame &msg)
bool VisionTrackingAvailable
void applyPositionCorrection(double deltaT)
virtual bool GetAllPositionCalibrationReports(Array< PositionCalibrationReport > *)
Transform< float > Transformf
bool VisionPositionEnabled
T DistanceSq(Vector3 const &b) const
Quatd MagCorrectionIntegralTerm
OVR_FORCE_INLINE void LogData(const char *, const T &)
SensorFilterBodyFrame FAccelInCameraFrame
virtual void OnVisionSuccess(const Transform< double > &cameraFromImu, UInt32 exposureCounter)
BodyFrameHandler * pHandler
Transformf GetPoseAtTime(double absoluteTime) const
OVR_FORCE_INLINE void RecordMessage(const Message &)
Array< MagReferencePoint > MagRefs
T SavitzkyGolayDerivative12() const
OVR_FORCE_INLINE void RecordUserParams(const Vector3f &, float)
Vector3< T > AngularVelocity
void OnMessage(const MessageBodyFrame &msg)
Vector3< double > Vector3d
double TPH_CameraPoseConfidence
Vector3f GetHeadModel() const
virtual UPInt GetSize(void) const
SensorFusion(SensorDevice *sensor=0)
PoseState< double > CameraFromImu
void SetFocusFOV(double rads)
int GetFloatValues(const char *key, float *values, int num_vals) const
PoseState< double > VisionError
Vector3 EntrywiseMultiply(const Vector3 &b) const
void applyFocusCorrection(double deltaT)
double GetVisionLatency() const
static const double Tolerance
Lock * GetHandlerLock() const
void applyVisionYawCorrection(double deltaT)
CircularBuffer< ExposureRecord > ExposureRecordHistory
void handleExposure(const MessageExposureFrame &msg)
SensorFilterBodyFrame FAccelInImuFrame
Vector3< T > LinearVelocity
unsigned int GetStatus() const
OVR_FORCE_INLINE void RecordVisionSuccess(UInt32)
void SetUserHeadDimensions(Profile const &profile, HmdRenderInfo const &hmdRenderInfo)
ExposureRecord NextExposureRecord
bool EnableCameraTiltCorrection
Quat Nlerp(const Quat &other, T a)
ExposureRecord LastVisionExposureRecord
float TPH_CameraPoseOrientationWxyz[4]
PoseStated computeVisionError()
float LensSurfaceToMidplateInMeters
OVR_FORCE_INLINE void RecordLedPositions(const Array< PositionCalibrationReport > &)
PoseState< float > PoseStatef
void StoreAndIntegrateAccelerometer(Vector3d linearAccel, double dt)
PoseState< double > WorldFromImu
EyeConfig GetEyeCenter() const
static double OVR_STDCALL GetSeconds()
virtual void AddMessageHandler(MessageHandler *handler)
bool IsMotionTrackingEnabled() const
virtual void OnVisionFailure()
void RemoveHandlerFromDevices()
PoseState< double > State
T Angle(const Vector3 &b) const
void PushBack(const T &e)
OVR_FORCE_INLINE Recorder & GetRecorder()
double AbsoluteTimeSeconds
Vector3< float > Vector3f
bool TPH_IsPositionTracked
MessageExposureFrame LastMessageExposureFrame
OVR_FORCE_INLINE const T Abs(const T v)
Transformd WorldFromCamera
Vector3< T > LinearAcceleration
void setNeckPivotFromPose(Transformd const &pose)
void applyCameraTiltCorrection(Vector3d accel, double deltaT)
bool IsAttachedToSensor() const