OSVR-Core
ThreadsafeBodyReporting.h
Go to the documentation of this file.
1 
11 // Copyright 2016 Sensics, Inc.
12 //
13 // Licensed under the Apache License, Version 2.0 (the "License");
14 // you may not use this file except in compliance with the License.
15 // You may obtain a copy of the License at
16 //
17 // http://www.apache.org/licenses/LICENSE-2.0
18 //
19 // Unless required by applicable law or agreed to in writing, software
20 // distributed under the License is distributed on an "AS IS" BASIS,
21 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
22 // See the License for the specific language governing permissions and
23 // limitations under the License.
24 
25 #ifndef INCLUDED_ThreadsafeBodyReporting_h_GUID_EB81AB60_6C5C_4A92_CD3D_ADFA62489F70
26 #define INCLUDED_ThreadsafeBodyReporting_h_GUID_EB81AB60_6C5C_4A92_CD3D_ADFA62489F70
27 
28 // Internal Includes
29 #include "ModelTypes.h"
30 
31 // Library/third-party includes
32 #include <boost/optional.hpp>
33 #include <folly/ProducerConsumerQueue.h>
35 #include <osvr/Util/TimeValue.h>
36 
37 // Standard includes
38 #include <array>
39 #include <memory>
40 
41 namespace osvr {
42 namespace vbtracker {
43  enum class ReportStatus { Valid, MutexLocked, NoReportAvailable };
44  struct BodyReport {
45 
46  static BodyReport
47  makeReportWithStatus(ReportStatus status = ReportStatus::Valid) {
48  BodyReport ret;
49  ret.status = status;
50  return ret;
51  }
52 
55  explicit operator bool() const { return status == ReportStatus::Valid; }
56 
57  ReportStatus status;
58  util::time::TimeValue timestamp;
59  OSVR_PoseState pose;
61  };
62 
65  class BodyReporting {
66  public:
68  static std::unique_ptr<BodyReporting> make();
69 
70  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
73 
80  bool getReport(double additionalPrediction, BodyReport &report);
82 
85 
88  bool updateState(util::time::TimeValue const &tv,
89  BodyState const &state);
90 
93  void initProcessModel(BodyProcessModel const &process);
94 
98  void setTrackerToRoomTransform(Eigen::Isometry3d const &xform);
100  private:
101  BodyReporting();
104  bool m_hasProcessModel = false;
105  BodyProcessModel m_process;
106  Eigen::Isometry3d m_trackerToRoom;
108 
109  template <std::size_t ArraySize> struct QueueValue {
110  util::time::TimeValue timestamp;
111  std::array<double, ArraySize> stateData;
112  };
115  using QueueValueType = QueueValue<13>;
118  folly::ProducerConsumerQueue<QueueValueType> m_queue;
119 
123  BodyState m_state;
124  util::time::TimeValue m_dataTime;
126  };
127  using BodyReportingPtr = std::unique_ptr<BodyReporting>;
128 
129  using BodyReportingVector = std::vector<BodyReportingPtr>;
130 } // namespace vbtracker
131 } // namespace osvr
132 
133 #endif // INCLUDED_ThreadsafeBodyReporting_h_GUID_EB81AB60_6C5C_4A92_CD3D_ADFA62489F70
The main namespace for all C++ elements of the framework, internal and external.
Definition: namespace_osvr.dox:3
Definition: ThreadsafeBodyReporting.h:44
Header providing a C++ wrapper around TimeValueC.h.
A per-body class intended to marshall data coming from the tracking/processing thread back to the mai...
Definition: ThreadsafeBodyReporting.h:65
A structure defining a 3D (6DOF) rigid body pose: translation and rotation.
Definition: Pose3C.h:54
Header.
Struct for combined velocity state.
Definition: ClientReportTypesC.h:87
Standardized, portable parallel to struct timeval for representing both absolute times and time inter...
Definition: TimeValueC.h:81
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:127
Definition: Transform.h:43
A basically-constant-velocity model, with the addition of some damping of the velocities inspired by ...
Definition: PoseSeparatelyDampedConstantVelocity.h:43