NTRT Simulator  Version: Master
 All Classes Namespaces Files Functions Variables Typedefs Friends Pages
tgUtil.h
Go to the documentation of this file.
1 /*
2  * Copyright © 2012, United States Government, as represented by the
3  * Administrator of the National Aeronautics and Space Administration.
4  * All rights reserved.
5  *
6  * The NASA Tensegrity Robotics Toolkit (NTRT) v1 platform is licensed
7  * under the Apache License, Version 2.0 (the "License");
8  * you may not use this file except in compliance with the License.
9  * You may obtain a copy of the License at
10  * http://www.apache.org/licenses/LICENSE-2.0.
11  *
12  * Unless required by applicable law or agreed to in writing,
13  * software distributed under the License is distributed on an
14  * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
15  * either express or implied. See the License for the specific language
16  * governing permissions and limitations under the License.
17 */
18 
20 
21 #ifndef TG_UTIL_H
22 #define TG_UTIL_H
23 
33 #include "btBulletDynamicsCommon.h" // stream operations for collision shapes
34 #include "LinearMath/btQuaternion.h"
35 #include "LinearMath/btTransform.h"
36 #include "LinearMath/btVector3.h"
37 #include <cmath>
38 #include <iostream>
39 #include <sstream>
40 #include <string>
41 
42 #include "tgRigidInfo.h"
43 
48 class tgUtil
49 {
50 public:
51 
56  inline static btVector3 upVector()
57  {
58  return btVector3(0.0, 1.0, 0.0);
59  };
60 
65  inline static std::string degSymbol()
66  {
67  return "\u00B0";
68  }
69 
76  inline static btVector3 center(const btVector3& start,
77  const btVector3& end)
78  {
79  return (start + end) / 2.0;
80  }
81 
92  inline static btTransform getTransform(const btVector3& startOrientation,
93  const btVector3& start,
94  const btVector3& end)
95  {
96 
97  const btVector3 origin = center(start, end);
98  btTransform t = btTransform();
99  t.setIdentity();
100  t.setOrigin(origin);
101  // If they for some reason gave us the same vector, keep identity
102 
103  t.setRotation(getQuaternionBetween(startOrientation,
104  getVector(start, end)));
105 
106  return t;
107  }
108 
114  inline static btTransform getTransform(const btVector3& start,
115  const btVector3& end)
116  {
117  return getTransform(upVector(), start, end);
118  }
119 
120  inline static btTransform getTransform(const btVector3& center)
121  {
122  btTransform t = btTransform();
123  t.setIdentity();
124  t.setOrigin(center);
125  // No point in rotating, keep identity
126  return t;
127  }
128 
135  static btVector3 getVector(const btVector3& from,
136  const btVector3& to)
137  {
138  return to - from;
139  }
140 
159  static btVector3 getRadiusVector(btVector3 axis,
160  double radius,
161  btVector3 target)
162  {
163  // NOTE: axis and target are passed by value,
164  // so we can alter them.
165  axis.normalize();
166  target.normalize();
167  // Get a vector normal to both
168  const btVector3 norm = axis.cross(target);
169  // Rotate the axis by 90 degrees around the normal vector
170  axis.rotate(norm, (M_PI / 2.0));
171  return axis;
172  }
173 
182  static bool almostEqual(const btVector3& from,
183  const btVector3& to,
184  int precision = 5)
185  {
186  return from.distance(to) < pow(10.0, (precision < 0 ? 5 : -precision));
187  }
188 
199  static btQuaternion getQuaternionBetween(btVector3 a, btVector3 b, const btVector3& fallbackAxis = btVector3(0,0,0))
200  {
201  a.normalize();
202  b.normalize();
203 
204  // The return value
205  btQuaternion result;
206 
207  // Account for equal vectors (can't calculate c in this case)
208  if (almostEqual(a, b)) {
209  result = btQuaternion::getIdentity();
210  } else if (almostEqual(a, -b)) {
211  // Account for opposing vectors (can't calculate c in
212  // this case either)
213  if (!fallbackAxis.isZero())
214  {
215  result = btQuaternion(fallbackAxis, M_PI).normalize();
216  }
217  else if (a.dot(btVector3(1.0, 0.0, 0.0)) == 0.0)
218  {
219  // Gets around bad btTransforms with an up vector
220  result = btQuaternion (-1.0, 0.0, 0.0, 0.0);
221  }
222  else
223  {
224  const btVector3 arb =
226  const btVector3 c = (a.cross(arb)).normalize();
227  result = btQuaternion(c, M_PI).normalize();
228  }
229  } else {
230  // Create a vector normal to both a and b
231  const btVector3 c = (a.cross(b)).normalize();
232 
233  // Create a quaternion that represents a rotation about
234  // c by the angle between a and b
235  result = btQuaternion(c, acos(a.dot(b))).normalize();
236  }
237  return result;
238  }
239 
246  static btVector3 getCentroid(const std::vector<btVector3>& points) {
247  int numPoints = points.size();
248  btVector3 centroid = btVector3(0, 0, 0);
249  for (int i = 0; i < numPoints; i++) {
250  centroid += points[i];
251  }
252  centroid /= numPoints;
253  return centroid;
254  }
255 
261  inline static btVector3 getArbitraryNonParallelVector(btVector3 v)
262  {
263  btVector3 arb;
264  v.normalize();
265  do {
266  arb = btVector3(rand()%10, rand()%10, rand()%10).normalize();
267  } while (arb == v || arb == -v);
268  return arb;
269  }
270 
274  inline static void addRotation(btVector3& v,
275  const btVector3& fixedPoint,
276  const btVector3& axis,
277  double angle)
278  {
279  // Get a vector from fixedPoint to this
280  btVector3 relative = v - fixedPoint;
281 
282  // Rotate the relative vector
283  btVector3 rotated = relative.rotate(axis, angle);
284 
285  // Set our new values
286  v.setX(fixedPoint.x() + rotated.x());
287  v.setY(fixedPoint.y() + rotated.y());
288  v.setZ(fixedPoint.z() + rotated.z());
289  }
290 
294  inline static void addRotation(btVector3& v,
295  const btVector3& fixedPoint,
296  const btVector3& fromOrientation,
297  const btVector3& toOrientation)
298  {
299  btQuaternion rotation = getQuaternionBetween(fromOrientation, toOrientation);
300  addRotation(v, fixedPoint, rotation);
301  }
302 
306  inline static void addRotation(btVector3& v,
307  const btVector3& fixedPoint,
308  const btQuaternion& rotation)
309  {
310  addRotation(v, fixedPoint, rotation.getAxis(), rotation.getAngle());
311  }
312 
324  inline static double rad2deg(double radians)
325  {
326  return radians * 180.0 / M_PI;
327  }
328 
335  inline static double deg2rad(double degrees)
336  {
337  return degrees * (M_PI / 180.0);
338  }
339 
347  inline static std::string strDeg(double degrees) {
348  std::ostringstream s;
349  s << degrees << degSymbol();
350  return s.str();
351  }
352  //static std::string strDeg(double degrees);
353 
354  inline static double round(double d, int precision = 5)
355  {
356  const double base = 10.0;
357  const int m = static_cast<int>(pow(base, precision));
358  return floor(d * m + 0.5)/m;
359  }
360 
361  static void seedRandom();
362 
365  static void seedRandom(int seed);
366 };
367 
375 inline std::ostream&
376 operator<<(std::ostream& os, const btQuaternion& q)
377 {
378  os << "btQuaternion( "
379  << q.x() << ", " << q.y() << ", " << q.z() << ", " << q.w()
380  << " )";
381  return os;
382 }
383 
391 inline std::ostream&
392 operator<<(std::ostream& os, const btVector3& v)
393 {
394  os << "btVector3( " << v.x() << ", " << v.y() << ", " << v.z() << " )";
395  return os;
396 }
397 
405 inline std::ostream&
406 operator<<(std::ostream& os, const btTransform& xf)
407 {
408  os << "btTransform: origin = " << xf.getOrigin()
409  << "; rotation = " << xf.getRotation();
410  return os;
411 }
412 
420 inline std::ostream&
421 operator<<(std::ostream& os, const btRigidBody& rb)
422 {
423  os << "btRigidBody: " << rb.getCollisionShape();
424  return os;
425 }
426 
434 inline std::ostream&
435 operator<<(std::ostream& os, const btCollisionShape& cs)
436 {
437  os << "btCollisionShape: " << cs.getShapeType();
438  return os;
439 }
440 
448 inline std::ostream&
449 operator<<(std::ostream& os, const btCompoundShape& cs)
450 {
451  os << "btCompoundShape: " << cs.getShapeType() << std::endl
452  << " # Children: " << cs.getNumChildShapes() << std::endl;
453  return os;
454 }
455 
456 
457 
458 #endif // TG_UTIL_H
static btQuaternion getQuaternionBetween(btVector3 a, btVector3 b, const btVector3 &fallbackAxis=btVector3(0, 0, 0))
Definition: tgUtil.h:199
Definition of abstract class tgRigidInfo.
std::ostream & operator<<(std::ostream &os, const btQuaternion &q)
Definition: tgUtil.h:376
static btVector3 getVector(const btVector3 &from, const btVector3 &to)
Definition: tgUtil.h:135
static btVector3 getArbitraryNonParallelVector(btVector3 v)
Definition: tgUtil.h:261
Definition: tgUtil.h:48
static std::string degSymbol()
Definition: tgUtil.h:65
static bool almostEqual(const btVector3 &from, const btVector3 &to, int precision=5)
Definition: tgUtil.h:182
static btVector3 upVector()
Definition: tgUtil.h:56
static void addRotation(btVector3 &v, const btVector3 &fixedPoint, const btVector3 &fromOrientation, const btVector3 &toOrientation)
Definition: tgUtil.h:294
static double deg2rad(double degrees)
Definition: tgUtil.h:335
static btVector3 center(const btVector3 &start, const btVector3 &end)
Definition: tgUtil.h:76
static btVector3 getCentroid(const std::vector< btVector3 > &points)
Definition: tgUtil.h:246
static void addRotation(btVector3 &v, const btVector3 &fixedPoint, const btQuaternion &rotation)
Definition: tgUtil.h:306
static btVector3 getRadiusVector(btVector3 axis, double radius, btVector3 target)
Definition: tgUtil.h:159
static btTransform getTransform(const btVector3 &startOrientation, const btVector3 &start, const btVector3 &end)
Definition: tgUtil.h:92
static btTransform getTransform(const btVector3 &start, const btVector3 &end)
Definition: tgUtil.h:114
static std::string strDeg(double degrees)
Definition: tgUtil.h:347
static void addRotation(btVector3 &v, const btVector3 &fixedPoint, const btVector3 &axis, double angle)
Definition: tgUtil.h:274
static double rad2deg(double radians)
Definition: tgUtil.h:324