MathHelper.cpp
Go to the documentation of this file.
1 
21 
22 namespace next_best_view {
23 
25  static boost::mt19937 gen(5);
26  return gen;
27  }
28 
31  convertC2S(cartesian, ssc);
32  return ssc;
33  }
34 
36  sphere[0] = cartesian.lpNorm<2>();
37  sphere[1] = asin(cartesian[2]);
38  sphere[2] = atan2(cartesian[1], cartesian[0]);
39  }
40 
42  SimpleVector3 cartesian;
43  convertS2C(sphere, cartesian);
44  return cartesian;
45  }
46 
48  cartesian[0] = sphere[0] * cos(sphere[1]) * cos(sphere[2]);
49  cartesian[1] = sphere[0] * cos(sphere[1]) * sin(sphere[2]);
50  cartesian[2] = sphere[0] * sin(sphere[1]);
51  }
52 
54  SimpleVector3 resultAxis;
55  getVisualAxis(orientation, resultAxis);
56  return resultAxis;
57  }
58 
59  void MathHelper::getVisualAxis(const SimpleQuaternion &orientation, SimpleVector3 &resultAxis) {
60  resultAxis = orientation.toRotationMatrix() * SimpleVector3::UnitX();
61  }
62 
63  double MathHelper::getSignum(const double &value) {
64  return (value == 0 ? 0.0 : (value < 0 ? -1.0 : 1.0));
65  }
66 
67  SimpleVector3 MathHelper::getProjection(const std::size_t &idx, const SimpleVector3 &X) {
68  return SimpleVector3((idx == 0 ? 0 : X[0]), (idx == 1 ? 0 : X[1]), (idx == 2 ? 0 : X[2]));
69  }
70 
72  Precision xNorm = X.lpNorm<2>();
73  Precision yNorm = Y.lpNorm<2>();
74 
75  if (xNorm == 0 || yNorm == 0) {
76  return 0.0;
77  }
78  return X.dot(Y) / xNorm / yNorm;
79  }
80 
82  float cosinus = getCosinus(X, Y);
83  float angle = acos(cosinus);
84  return angle;
85  }
86 
87  Precision MathHelper::getMinimumAngleDifference(const Precision &firstAngle, const Precision &secondAngle) {
88  Precision angleDiff = std::fabs(firstAngle - secondAngle);
89  return fmin(angleDiff, 2 * M_PI - angleDiff);
90  }
91 
92  int MathHelper::getRandomInteger(const int &min, const int &max) {
93  boost::uniform_int<> uniform(min, max);
94  boost::variate_generator<boost::mt19937&, boost::uniform_int<> > random(getRandomnessGenerator(), uniform);
95  return random();
96  }
97 
98  Precision MathHelper::getRandomNumber(const Precision &mean, const Precision &standardDeviation) {
99  boost::normal_distribution<Precision> uniform(mean, standardDeviation);
100  boost::variate_generator<boost::mt19937&, boost::normal_distribution<Precision> > random(getRandomnessGenerator(), uniform);
101  return random();
102  }
103 
104  SimpleVectorX MathHelper::getRandomVector(const SimpleVectorX &mean, const SimpleVectorX &standardDeviation) {
105  SimpleVectorX result(mean.rows());
106 
107  for (int i = 0; i < mean.rows(); i++) {
108  result[i] = getRandomNumber(mean[i], standardDeviation[i]);
109  }
110  return result;
111  }
112 
114  SimpleVector3 randomAngles = getRandomVector(SimpleVector3(0.0, 0.0, 0.0), SimpleVector3(2 * M_PI, 2 * M_PI, 1.0));
115  return getQuaternionByAngles(randomAngles[0], randomAngles[1], 0);
116  }
117 
118  SimpleQuaternion MathHelper::getQuaternionByAngles(const Precision &heading, const Precision &attitude, const Precision &bank) {
119  double c1 = cos(heading / 2);
120  double c2 = cos(attitude / 2);
121  double c3 = cos(bank / 2);
122  double s1 = sin(heading / 2);
123  double s2 = sin(attitude / 2);
124  double s3 = sin(bank / 2);
125 
126  SimpleQuaternion quatHeading(c1, 0.0, 0.0, s1);
127  SimpleQuaternion quatAttitude(c2, 0.0, s2, 0.0);
128  SimpleQuaternion quatBank(c3, s3, 0.0, 0.0);
129 
130  //SimpleQuaternion result(c1 * c2 * c3, c1 * c2 * s3, c1 * s2 * c3, s1 * c2 * c3);
131  SimpleQuaternion result = quatHeading * quatAttitude * quatBank;
132 
133  return result.normalized();
134  }
135 
137  SimpleQuaternionCollectionPtr oritentationCollectionPtr(new SimpleQuaternionCollection());
138 
139  //Comment: Black magic.
140  float dlong = M_PI * (3.0 - sqrt(5.0));
141  float dz = 2.0 / numberOfPoints;
142  float longitude = 0.0;
143  float z = 1.0 - dz / 2.0;
144 
145  for (int k = 0; k < numberOfPoints; k += 1) {
146  float r = sqrt(1.0 - pow(z, 2));
147 
148  SimpleVector3 point;
149  point[0] = cos(longitude) * r;
150  point[1] = sin(longitude) * r;
151  point[2] = z;
152 
153  SimpleSphereCoordinates sphereCoords = convertC2S(point);
154  SimpleQuaternion orientation = MathHelper::getQuaternionByAngles(sphereCoords[2], sphereCoords[1], 0.0);
155  oritentationCollectionPtr->push_back(orientation);
156 
157  z -= dz;
158  longitude += dlong;
159  if (z < -1) {
160  break;
161  }
162  }
163 
164  return oritentationCollectionPtr;
165  }
166 
167 
168  double MathHelper::radToDeg(double input) {
169  return fmod(input / M_PI * 180.0, 360);
170  }
171 
172  double MathHelper::degToRad(double input) {
173  return fmod(input / 180.0 * M_PI, 2 * M_PI);
174  }
175 
177  {
178  return v1[0]*v2[0] + v1[1]*v2[1] + v1[2]*v2[2];
179  }
180 
182  return std::abs(v1[0] - v2[0]) < 0.0001 &&
183  std::abs(v1[1] - v2[1]) < 0.0001 &&
184  std::abs(v1[2] - v2[2]) < 0.0001;
185  }
186 }
Eigen::Matrix< Precision, Eigen::Dynamic, 1 > SimpleVectorX
Definition: typedef.hpp:56
static bool vector3Equal(SimpleVector3 v1, SimpleVector3 v2)
Definition: MathHelper.cpp:181
SimpleVector3 SimpleSphereCoordinates
Definition: typedef.hpp:54
static double getSignum(const double &value)
Definition: MathHelper.cpp:63
Eigen::Matrix< Precision, 3, 1 > SimpleVector3
Definition: typedef.hpp:53
static Precision getAngle(const SimpleVector3 &X, const SimpleVector3 &Y)
Definition: MathHelper.cpp:81
static Precision getCosinus(const SimpleVector3 &X, const SimpleVector3 &Y)
Definition: MathHelper.cpp:71
std::vector< SimpleQuaternion, Eigen::aligned_allocator< SimpleQuaternion > > SimpleQuaternionCollection
Definition: typedef.hpp:70
static Precision getMinimumAngleDifference(const Precision &firstAngle, const Precision &secondAngle)
Definition: MathHelper.cpp:87
static SimpleQuaternion getRandomQuaternion()
Definition: MathHelper.cpp:113
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
static Precision getRandomNumber(const Precision &mean, const Precision &standardDeviation)
Definition: MathHelper.cpp:98
this namespace contains all generally usable classes.
static boost::mt19937 & getRandomnessGenerator()
Definition: MathHelper.cpp:24
static SimpleVectorX getRandomVector(const SimpleVectorX &mean, const SimpleVectorX &standardDeviation)
Definition: MathHelper.cpp:104
static SimpleVector3 getVisualAxis(const SimpleQuaternion &orientation)
Definition: MathHelper.cpp:53
static SimpleVector3 getProjection(const std::size_t &idx, const SimpleVector3 &X)
Definition: MathHelper.cpp:67
static SimpleQuaternion getQuaternionByAngles(const Precision &heading, const Precision &attitude, const Precision &bank)
Definition: MathHelper.cpp:118
TFSIMD_FORCE_INLINE const tfScalar & z() const
static double degToRad(double input)
Definition: MathHelper.cpp:172
static double getDotProduct(SimpleVector3 v1, SimpleVector3 v2)
Definition: MathHelper.cpp:176
static double radToDeg(double input)
Definition: MathHelper.cpp:168
Eigen::Quaternion< Precision > SimpleQuaternion
Definition: typedef.hpp:67
static SimpleSphereCoordinates convertC2S(const SimpleVector3 &cartesian)
converts cartesian coordinates to sphere coordinates
Definition: MathHelper.cpp:29
static SimpleVector3 convertS2C(const SimpleSphereCoordinates &sphere)
converts sphere coordinates to cartesian coordinates (lightweight)
Definition: MathHelper.cpp:41
float Precision
Definition: typedef.hpp:36
static SimpleQuaternionCollectionPtr getOrientationsOnUnitSphere(const int &numberOfPoints)
Definition: MathHelper.cpp:136
static int getRandomInteger(const int &min, const int &max)
Definition: MathHelper.cpp:92


asr_next_best_view
Author(s): Aumann Florian, Borella Jocelyn, Heller Florian, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij
autogenerated on Thu Jan 9 2020 07:20:18