OSVR Framework (Internal Development Docs)  0.6-1962-g59773924
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
TransformsC.cpp
Go to the documentation of this file.
1 
11 // Copyright 2015 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 // Internal Includes
30 #include <osvr/Common/Transform.h>
32 #include <osvr/Util/EigenInterop.h>
33 #include <osvr/Util/ExtractYaw.h>
34 
35 // Library/third-party includes
36 // - none
37 
38 // Standard includes
39 #include <chrono>
40 
42  if (nullptr == ctx) {
44  return OSVR_RETURN_FAILURE;
45  }
46  auto xform = ctx->getRoomToWorldTransform();
47 
48  auto iface = osvr::client::InternalInterfaceOwner{ctx, "/me/head"};
52  using std::chrono::system_clock;
53  const auto deadline = system_clock::now() + std::chrono::milliseconds(200);
54  do {
55  if (OSVR_RETURN_SUCCESS ==
56  osvrGetOrientationState(&(*iface), &t, &state)) {
57  // OK, we've gotten state successfully: extract yaw, update
58  // transform, and return success.
59  auto q = osvr::util::eigen_interop::map(state);
60  auto yaw = osvr::util::extractYaw(q);
61  Eigen::AngleAxisd correction(-yaw, Eigen::Vector3d::UnitY());
62  xform.concatPost(Eigen::Isometry3d(correction).matrix());
63  ctx->setRoomToWorldTransform(xform);
64  return OSVR_RETURN_SUCCESS;
65  }
66  ctx->update();
67  } while (system_clock::now() < deadline);
68  return OSVR_RETURN_FAILURE;
69 }
70 
72  if (nullptr == ctx) {
74  return OSVR_RETURN_FAILURE;
75  }
76  osvr::common::Transform nullTransform;
77  ctx->setRoomToWorldTransform(nullTransform);
78  return OSVR_RETURN_SUCCESS;
79 }
OSVR_ReturnCode osvrClientClearRoomToWorldTransform(OSVR_ClientContext ctx)
Clears/resets the internal "room to world" transformation back to an identity transformation - that i...
Definition: TransformsC.cpp:71
Header.
osvr::common::Transform const & getRoomToWorldTransform() const
Gets the transform from room space to world space.
auto extractYaw(T const &quat) -> decltype(std::atan(quat.w()))
Definition: ExtractYaw.h:47
A structure defining a quaternion, often a unit quaternion representing 3D rotation.
Definition: QuaternionC.h:49
Class that should be used for all internally-used client interface objects as it handles ownership wi...
Header controlling the OSVR transformation hierarchy.
Header.
#define OSVR_RETURN_FAILURE
The "failure" value for an OSVR_ReturnCode.
Definition: ReturnCodesC.h:47
void setRoomToWorldTransform(osvr::common::Transform const &xform)
Sets the transform from room space to world space.
#define OSVR_RETURN_SUCCESS
The "success" value for an OSVR_ReturnCode.
Definition: ReturnCodesC.h:45
OSVR_ReturnCode osvrClientSetRoomRotationUsingHead(OSVR_ClientContext ctx)
Updates the internal "room to world" transformation (applied to all tracker data for this client cont...
Definition: TransformsC.cpp:41
Header for interoperation between the Eigen math library, the internal mini math library, and VRPN's quatlib.
OSVR_ReturnCode osvrGetOrientationState(OSVR_ClientInterface iface, struct OSVR_TimeValue *timestamp, OSVR_OrientationState *state)
Get Orientation state from an interface, returning failure if none \ * exists.
Standardized, portable parallel to struct timeval for representing both absolute times and time inter...
Definition: TimeValueC.h:81
void update()
System-wide update method.
Spatial transformation, consisting of both pre and post components.
Definition: Transform.h:44