Bike-X  0.8
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros
OVR_SensorFusion.h
Go to the documentation of this file.
1 /************************************************************************************
2 
3 PublicHeader: OVR.h
4 Filename : OVR_SensorFusion.h
5 Content : Methods that determine head orientation from sensor data over time
6 Created : October 9, 2012
7 Authors : Michael Antonov, Steve LaValle, Dov Katz, Max Katsev, Dan Gierl
8 
9 Copyright : Copyright 2014 Oculus VR, Inc. All Rights reserved.
10 
11 Licensed under the Oculus VR Rift SDK License Version 3.1 (the "License");
12 you may not use the Oculus VR Rift SDK except in compliance with the License,
13 which is provided at the time of installation or download, or which
14 otherwise accompanies this software in either electronic or hard copy form.
15 
16 You may obtain a copy of the License at
17 
18 http://www.oculusvr.com/licenses/LICENSE-3.1
19 
20 Unless required by applicable law or agreed to in writing, the Oculus VR SDK
21 distributed under the License is distributed on an "AS IS" BASIS,
22 WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
23 See the License for the specific language governing permissions and
24 limitations under the License.
25 
26 *************************************************************************************/
27 
28 #ifndef OVR_SensorFusion_h
29 #define OVR_SensorFusion_h
30 
31 #include "OVR_Device.h"
32 #include "OVR_SensorFilter.h"
33 #include "Kernel/OVR_Timer.h"
34 #include "Kernel/OVR_Threads.h"
35 #include "Kernel/OVR_Lockless.h"
36 
37 // CAPI forward declarations.
40 
41 namespace OVR {
42 
43 struct HmdRenderInfo;
44 
45 //-------------------------------------------------------------------------------------
46 // ***** Sensor State
47 
48 // These values are reported as compatible with C API.
49 
50 
51 // PoseState describes the complete pose, or a rigid body configuration, at a
52 // point in time, including first and second derivatives. It is used to specify
53 // instantaneous location and movement of the headset.
54 // SensorState is returned as a part of the sensor state.
55 
56 template<class T>
57 class PoseState
58 {
59 public:
60  typedef typename CompatibleTypes<Transform<T> >::Type CompatibleType;
61 
62  PoseState() : TimeInSeconds(0.0) { }
63  // float <-> double conversion constructor.
64  explicit PoseState(const PoseState<typename Math<T>::OtherFloatType> &src)
65  : Pose(src.Pose),
69  { }
70 
71  // C-interop support: PoseStatef <-> ovrPoseStatef
72  PoseState(const typename CompatibleTypes<PoseState<T> >::Type& src)
73  : Pose(src.Pose),
77  { }
78 
79  operator typename CompatibleTypes<PoseState<T> >::Type () const
80  {
81  typename CompatibleTypes<PoseState<T> >::Type result;
82  result.Pose = Pose;
83  result.AngularVelocity = AngularVelocity;
84  result.LinearVelocity = LinearVelocity;
85  result.AngularAcceleration = AngularAcceleration;
86  result.LinearAcceleration = LinearAcceleration;
87  result.TimeInSeconds = TimeInSeconds;
88  return result;
89  }
90 
91 
97  // Absolute time of this state sample; always a double measured in seconds.
98  double TimeInSeconds;
99 
100 
101  // ***** Helpers for Pose integration
102 
103  // Stores and integrates gyro angular velocity reading for a given time step.
104  void StoreAndIntegrateGyro(Vector3d angVel, double dt);
105  // Stores and integrates position/velocity from accelerometer reading for a given time step.
106  void StoreAndIntegrateAccelerometer(Vector3d linearAccel, double dt);
107 
108  // Performs integration of state by adding next state delta to it
109  // to produce a combined state change
110  void AdvanceByDelta(const PoseState<T>& delta);
111 };
112 
113 
114 
115 // External API returns pose as float, but uses doubles internally for quaternion precision.
118 
119 
120 //-------------------------------------------------------------------------------------
121 // ***** Sensor State
122 
123 
124 // Bit flags describing the current status of sensor tracking.
126 {
127  Status_OrientationTracked = 0x0001, // Orientation is currently tracked (connected and in use).
128  Status_PositionTracked = 0x0002, // Position is currently tracked (false if out of range).
129  Status_PositionConnected = 0x0020, // Position tracking HW is conceded.
130  // Status_HMDConnected = 0x0080 // HMD Display is available & connected.
131 };
132 
133 
134 // Full state of of the sensor reported by GetSensorState() at a given absolute time.
136 {
137 public:
139 
140  // C-interop support
141  SensorState(const ovrSensorState& s);
142  operator ovrSensorState () const;
143 
144  // Pose state at the time that SensorState was requested.
146  // Actual recorded pose configuration based on sensor sample at a
147  // moment closest to the requested time.
149 
150  // Calibrated magnetometer reading, in Gauss, at sample time.
152  // Sensor temperature reading, in degrees Celsius, at sample time.
153  float Temperature;
154  // Sensor status described by ovrStatusBits.
155  unsigned int StatusFlags;
156 };
157 
158 
159 
160 //-------------------------------------------------------------------------------------
161 
163 {
164 public:
165  virtual void OnVisionSuccess(const Transform<double>& cameraFromImu, UInt32 exposureCounter) = 0;
166  virtual void OnVisionPreviousFrame(const Transform<double>& cameraFromImu) = 0;
167  virtual void OnVisionFailure() = 0;
168 
169  // Get a configuration that represents the change over a short time interval
170  virtual Transform<double> GetVisionPrediction(UInt32 exposureCounter) = 0;
171 };
172 
173 //-------------------------------------------------------------------------------------
174 // ***** SensorFusion
175 
176 // SensorFusion class accumulates Sensor notification messages to keep track of
177 // orientation, which involves integrating the gyro and doing correction with gravity.
178 // Magnetometer based yaw drift correction is also supported; it is usually enabled
179 // automatically based on loaded magnetometer configuration.
180 // Orientation is reported as a quaternion, from which users can obtain either the
181 // rotation matrix or Euler angles.
182 //
183 // The class can operate in two ways:
184 // - By user manually passing MessageBodyFrame messages to the OnMessage() function.
185 // - By attaching SensorFusion to a SensorDevice, in which case it will
186 // automatically handle notifications from that device.
187 
188 
190 {
191  friend class SensorFusionDebug;
192 
193  enum
194  {
196  };
197 
198 public:
199 
200  // -------------------------------------------------------------------------------
201  // Critical components for tiny API
202 
203  SensorFusion(SensorDevice* sensor = 0);
204  ~SensorFusion();
205 
206  // Attaches this SensorFusion to the IMU sensor device, from which it will receive
207  // notification messages. If a sensor is attached, manual message notification
208  // is not necessary. Calling this function also resets SensorFusion state.
209  bool AttachToSensor(SensorDevice* sensor);
210 
211  // Returns true if this Sensor fusion object is attached to the IMU.
212  bool IsAttachedToSensor() const;
213 
214  // Sets up head-and-neck model and device-to-pupil dimensions from the user's profile and the HMD stats.
215  // This copes elegantly if profile is NULL.
216  void SetUserHeadDimensions(Profile const &profile, HmdRenderInfo const &hmdRenderInfo);
217 
218  // Get the predicted pose (orientation, position) of the center pupil frame (CPF) at a specific point in time.
219  Transformf GetPoseAtTime(double absoluteTime) const;
220 
221  // Get the full dynamical system state of the CPF, which includes velocities and accelerations,
222  // predicted at a specified absolute point in time.
223  SensorState GetSensorStateAtTime(double absoluteTime) const;
224 
225  // Get the sensor status (same as GetSensorStateAtTime(...).Status)
226  unsigned int GetStatus() const;
227 
228  // End tiny API components
229  // -------------------------------------------------------------------------------
230 
231  // Resets the current orientation.
232  void Reset ();
233 
234  // Configuration
235  void EnableMotionTracking(bool enable = true) { MotionTrackingEnabled = enable; }
237 
238  // Accelerometer/Gravity Correction Control
239  // Enables/disables gravity correction (on by default).
240  void SetGravityEnabled (bool enableGravity);
241  bool IsGravityEnabled () const;
242 
243  // Vision Position and Orientation Configuration
244  // -----------------------------------------------
245  bool IsVisionPositionEnabled () const;
246  void SetVisionPositionEnabled (bool enableVisionPosition);
247 
248  // compensates for a tilted camera
249  void SetCameraTiltCorrectionEnabled(bool enable);
250  bool IsCameraTiltCorrectionEnabled () const;
251 
252  // Message Handling Logic
253  // -----------------------------------------------
254  // Notifies SensorFusion object about a new BodyFrame
255  // message from a sensor.
256  // Should be called by user if not attached to sensor.
257  void OnMessage (const MessageBodyFrame& msg);
258 
259 
260  // Interaction with vision
261  // -----------------------------------------------
262  // Handle observation from vision system (orientation, position, time)
263  virtual void OnVisionSuccess(const Transform<double>& cameraFromImu, UInt32 exposureCounter);
264 
265  virtual void OnVisionPreviousFrame(const Transform<double>& cameraFromImu);
266  virtual void OnVisionFailure();
267  // Get a configuration that represents the change over a short time interval
268  virtual Transform<double> GetVisionPrediction(UInt32 exposureCounter);
269 
270  double GetTime () const;
271  double GetVisionLatency () const;
272 
273 
274  // Detailed head dimension control
275  // -----------------------------------------------
276  // These are now deprecated in favour of SetUserHeadDimensions()
277  Vector3f GetHeadModel() const;
278  void SetHeadModel(const Vector3f &headModel, bool resetNeckPivot = true );
279  float GetCenterPupilDepth() const;
280  void SetCenterPupilDepth(float centerPupilDepth);
281 
282 
283  // Magnetometer and Yaw Drift Section:
284  // ---------------------------------------
285 
286  // Enables/disables magnetometer based yaw drift correction.
287  // Must also have mag calibration data for this correction to work.
288  void SetYawCorrectionEnabled(bool enable);
289  // Determines if yaw correction is enabled.
290  bool IsYawCorrectionEnabled () const;
291 
292  // Clear the reference points associating
293  // mag readings with orientations
294  void ClearMagReferences ();
295 
296  // Sets the focus filter direction to the current HMD direction
297  void SetFocusDirection();
298  // Sets the focus filter to a direction in the body frame. Once set, a complementary filter
299  // will very slowly drag the world to keep the direction of the HMD within the FOV of the focus
300  void SetFocusDirection(Vector3d direction);
301  // Sets the FOV (in radians) of the focus. When the yaw difference between the HMD's current pose
302  // and the focus is smaller than the FOV, the complementary filter does not act.
303  void SetFocusFOV(double rads);
304  // Turns off the focus filter (equivalent to setting the focus to 0
305  void ClearFocus();
306 
307 private:
308 
309  // -----------------------------------------------
310 
312  {
314  public:
316  : pFusion(fusion) {}
317 
319 
320  virtual void OnMessage(const Message& msg);
321  virtual bool SupportsMessageType(MessageType type) const;
322  };
323 
324 
325  // -----------------------------------------------
326 
327  // State version stored in lockless updater "queue" and used for
328  // prediction by GetPoseAtTime/GetSensorStateAtTime
330  {
332  float Temperature;
334  unsigned int StatusFlags;
335 
337  };
338 
339 
340  // -----------------------------------------------
341 
342  // Entry describing the state of the headset at the time of an exposure as reported by the DK2 board.
343  // This is used in combination with the vision data for
344  // incremental tracking based on IMU change and for drift correction
346  {
348  double ExposureTime;
349  // State of the headset at the time of exposure
351  // Change in state since the last exposure based on IMU data only
353  // Did we have tracking for the entire interval between exposures
355 
357  ExposureRecord(UInt32 exposureCounter, double exposureTime,
358  const PoseState<double>& worldFromImu, const PoseState<double>& imuOnlyDelta)
359  : ExposureCounter(exposureCounter), ExposureTime(exposureTime),
360  WorldFromImu(worldFromImu), ImuOnlyDelta(imuOnlyDelta), VisionTrackingAvailable(true) { }
361  };
362 
363  // -----------------------------------------------
364 
365  // Entry describing the magnetometer reference point
366  // Used for mag yaw correction
368  {
371  int Score;
372 
374  MagReferencePoint(const Vector3d& inImuFrame, const Transformd& worldFromImu, int score)
375  : InImuFrame(inImuFrame), WorldFromImu(worldFromImu), Score(score) { }
376  };
377 
378  // -----------------------------------------------
379 
380  // The phase of the head as estimated by sensor fusion
382 
383  // State that can be read without any locks, so that high priority rendering thread
384  // doesn't have to worry about being blocked by a sensor/vision threads that got preempted.
386 
387  // The pose we got from Vision, augmented with velocity information from numerical derivatives
389  // Difference between the vision and sensor fusion poses at the time of last exposure adjusted
390  // by all the corrections applied since then
391  // NB: this one is unlike all the other poses/transforms we use, since it's a difference
392  // between 2 WorldFromImu transforms, but is stored in the world frame, not the IMU frame
393  // (see computeVisionError() for details)
394  // For composition purposes it should be considered a WorldFromWorld transform, where the left
395  // side comes from vision and the right - from sensor fusion
397  // Past exposure records between the last update from vision and now
398  // (should only be one record unless vision latency is high)
400  // ExposureRecord that corresponds to the last pose we got from vision
402  // Incomplete ExposureRecord that will go into the history buffer when
403  // the new MessageExposureFrame is received
405  // Timings of the previous exposure, used to populate ExposureRecordHistory
407  // Time of the last vision update
409 
410  unsigned int Stage;
412 
414  double FocusFOV;
415 
418 
420 
422 
428 
430  // Describes the pose of the camera in the world coordinate system
433 
436 
437  // This is a signed distance, but positive because Z increases looking inward.
438  // This is expressed relative to the IMU in the HMD and corresponds to the location
439  // of the cyclopean virtual camera focal point if both the physical and virtual
440  // worlds are isometrically mapped onto each other. -Steve
442  // Describes the position of the user eyes relative to the IMU
444  // Position of the center of the screen relative to the IMU (loaded from the headset firmware)
446  // Built-in head model for faking position using orientation only
448  // Last known base of the neck pose used for head model computations
450 
451  //---------------------------------------------
452 
453  // Internal handler for messages
454  // bypasses error checking.
455  void handleMessage(const MessageBodyFrame& msg);
456  void handleExposure(const MessageExposureFrame& msg);
457 
458  // Compute the difference between vision and sensor fusion data
460  // Apply headset yaw correction from magnetometer
461  // for models without camera or when camera isn't available
462  void applyMagYawCorrection(Vector3d mag, double deltaT);
463  // Apply headset tilt correction from the accelerometer
464  void applyTiltCorrection(double deltaT);
465  // Apply headset yaw correction from the camera
466  void applyVisionYawCorrection(double deltaT);
467  // Apply headset position correction from the camera
468  void applyPositionCorrection(double deltaT);
469  // Apply camera tilt correction from the accelerometer
470  void applyCameraTiltCorrection(Vector3d accel, double deltaT);
471  // Apply camera focus correction
472  void applyFocusCorrection(double deltaT);
473 
474  // If you have a known-good pose, this sets the neck pivot position.
475  void setNeckPivotFromPose ( Transformd const &pose );
476 };
477 
478 
479 
480 //-------------------------------------------------------------------------------------
481 // ***** SensorFusion - Inlines
482 
484 {
485  return pHandler->IsHandlerInstalled();
486 }
487 
488 inline void SensorFusion::SetGravityEnabled(bool enableGravity)
489 {
490  EnableGravity = enableGravity;
491 }
492 
494 {
495  return EnableGravity;
496 }
497 
499 {
500  EnableYawCorrection = enable;
501 }
502 
504 {
505  return EnableYawCorrection;
506 }
507 
509 {
510  return VisionPositionEnabled;
511 }
512 
513 inline void SensorFusion::SetVisionPositionEnabled(bool enableVisionPosition)
514 {
515  VisionPositionEnabled = enableVisionPosition;
516 }
517 
519 {
520  EnableCameraTiltCorrection = enable;
521 }
522 
524 {
526 }
527 
528 inline double SensorFusion::GetVisionLatency() const
529 {
531 }
532 
533 inline double SensorFusion::GetTime() const
534 {
535  return Timer::GetSeconds();
536 }
537 
539 {
541 }
542 
544 {
545  return (type == Message_BodyFrame || type == Message_ExposureFrame);
546 }
547 
548 
549 //-------------------------------------------------------------------------------------
550 // ***** PoseState - Inlines
551 
552 // Stores and integrates gyro angular velocity reading for a given time step.
553 template<class T>
555 {
556  AngularVelocity = angVel;
557  double angle = angVel.Length() * dt;
558  if (angle > 0)
559  Pose.Rotation = Pose.Rotation * Quatd(angVel, angle);
560 }
561 
562 template<class T>
564 {
565  LinearAcceleration = linearAccel;
566  Pose.Translation += LinearVelocity * dt + LinearAcceleration * (dt * dt * 0.5);
567  LinearVelocity += LinearAcceleration * dt;
568 }
569 
570 // Performs integration of state by adding next state delta to it
571 // to produce a combined state change
572 template<class T>
574 {
575  Pose.Rotation = Pose.Rotation * delta.Pose.Rotation;
576  Pose.Translation += delta.Pose.Translation + LinearVelocity * delta.TimeInSeconds;
577  LinearVelocity += delta.LinearVelocity;
578  TimeInSeconds += delta.TimeInSeconds;
579 }
580 
581 } // namespace OVR
582 #endif
BodyFrameHandler(SensorFusion *fusion)
SensorState GetSensorStateAtTime(double absoluteTime) const
void ClearMagReferences()
virtual void OnVisionPreviousFrame(const Transform< double > &cameraFromImu)
float GetCenterPupilDepth() const
bool IsVisionPositionEnabled() const
virtual void OnVisionPreviousFrame(const Transform< double > &cameraFromImu)=0
void SetCenterPupilDepth(float centerPupilDepth)
void StoreAndIntegrateGyro(Vector3d angVel, double dt)
T Length() const
Definition: OVR_Math.h:509
void applyMagYawCorrection(Vector3d mag, double deltaT)
LocklessUpdater< LocklessState > UpdatedState
PoseState< double > WorldFromImu
virtual void OnMessage(const Message &msg)
MagReferencePoint(const Vector3d &inImuFrame, const Transformd &worldFromImu, int score)
bool AttachToSensor(SensorDevice *sensor)
CompatibleTypes< Transform< T > >::Type CompatibleType
double WorldFromCameraConfidence
uint32_t UInt32
Definition: OVR_Types.h:253
ExposureRecord(UInt32 exposureCounter, double exposureTime, const PoseState< double > &worldFromImu, const PoseState< double > &imuOnlyDelta)
virtual Transform< double > GetVisionPrediction(UInt32 exposureCounter)
void SetVisionPositionEnabled(bool enableVisionPosition)
void SetHeadModel(const Vector3f &headModel, bool resetNeckPivot=true)
void AdvanceByDelta(const PoseState< T > &delta)
Transformd WorldFromNeck
virtual bool SupportsMessageType(MessageType type) const
void applyTiltCorrection(double deltaT)
Vector3< T > AngularAcceleration
unsigned int StatusFlags
void handleMessage(const MessageBodyFrame &msg)
void applyPositionCorrection(double deltaT)
SensorFilterBodyFrame FAccelInCameraFrame
virtual void OnVisionSuccess(const Transform< double > &cameraFromImu, UInt32 exposureCounter)
void SetCameraTiltCorrectionEnabled(bool enable)
BodyFrameHandler * pHandler
Transformd ImuFromScreen
Transformf GetPoseAtTime(double absoluteTime) const
Quat< double > Quatd
Definition: OVR_Math.h:1086
bool IsCameraTiltCorrectionEnabled() const
Array< MagReferencePoint > MagRefs
Vector3< T > AngularVelocity
void OnMessage(const MessageBodyFrame &msg)
float OtherFloatType
Definition: OVR_Math.h:170
Vector3f GetHeadModel() const
SensorFusion(SensorDevice *sensor=0)
PoseState< double > CameraFromImu
void SetFocusFOV(double rads)
struct ovrSensorState_ ovrSensorState
PoseState< double > VisionError
void applyFocusCorrection(double deltaT)
double GetVisionLatency() const
void applyVisionYawCorrection(double deltaT)
CircularBuffer< ExposureRecord > ExposureRecordHistory
void SetYawCorrectionEnabled(bool enable)
void handleExposure(const MessageExposureFrame &msg)
SensorFilterd FAngV
SensorFilterBodyFrame FAccelInImuFrame
PoseState(const PoseState< typename Math< T >::OtherFloatType > &src)
Vector3< T > LinearVelocity
unsigned int GetStatus() const
virtual void OnVisionSuccess(const Transform< double > &cameraFromImu, UInt32 exposureCounter)=0
void SetUserHeadDimensions(Profile const &profile, HmdRenderInfo const &hmdRenderInfo)
ExposureRecord NextExposureRecord
bool IsHandlerInstalled() const
ExposureRecord LastVisionExposureRecord
PoseStated computeVisionError()
PoseState< float > PoseStatef
void StoreAndIntegrateAccelerometer(Vector3d linearAccel, double dt)
PoseState(const typename CompatibleTypes< PoseState< T > >::Type &src)
static double OVR_STDCALL GetSeconds()
Definition: OVR_Timer.cpp:51
bool IsMotionTrackingEnabled() const
virtual void OnVisionFailure()
double GetTime() const
void SetGravityEnabled(bool enableGravity)
void EnableMotionTracking(bool enable=true)
bool IsGravityEnabled() const
virtual void OnVisionFailure()=0
PoseState< double > PoseStated
Transform< T > Pose
MessageExposureFrame LastMessageExposureFrame
virtual Transform< double > GetVisionPrediction(UInt32 exposureCounter)=0
bool IsYawCorrectionEnabled() const
Transformd WorldFromCamera
Vector3< T > LinearAcceleration
void setNeckPivotFromPose(Transformd const &pose)
void applyCameraTiltCorrection(Vector3d accel, double deltaT)
bool IsAttachedToSensor() const