GAMS  1.4.0
Euler.h
Go to the documentation of this file.
1 
56 #include "ReferenceFrame.h"
57 
58 #ifndef _GAMS_POSE_EULER_H_
59 #define _GAMS_POSE_EULER_H_
60 
61 #include <iostream>
62 #include <cmath>
63 #include "Orientation.h"
64 #include "AngleUnits.h"
65 #include "Quaternion.h"
66 
67 namespace gams
68 {
69  namespace pose
70  {
75  namespace euler
76  {
83  namespace conv
84  {
85  struct Intr
86  {
87  static const char *name() { return "Intr"; }
88 
89  static const bool reverse = false;
90  };
91 
92  struct Extr
93  {
94  static const char *name() { return "Extr"; }
95 
96  /* Conversion formulas are in terms of intrinsic convention; to use
97  * them for extrinsic convention, we just need to pass the arguments
98  * in reverse order. This flag communicates this need. */
99  static const bool reverse = true;
100  };
101 
102  struct X
103  {
104  static const char *name() { return "X"; }
105  };
106 
107  struct Y
108  {
109  static const char *name() { return "Y"; }
110  };
111 
112  struct Z
113  {
114  static const char *name() { return "Z"; }
115  };
116  } // namespace conv
117  }
118  }
119 }
120 
121 #include "gams/pose/EulerFormulas.inl"
122 
123 namespace gams
124 {
125  namespace pose
126  {
127  namespace euler
128  {
156  template<typename A, typename B, typename C, typename Conv = conv::Intr>
157  class Euler
158  {
159  private:
160  typedef typename detail::GetTypes<A,B,C,Conv>::F F;
161  typedef typename detail::GetTypes<A,B,C,Conv>::Trig Trig;
162  public:
166  Euler() : a_(0), b_(0), c_(0) {}
167 
175  Euler(double a, double b, double c) : a_(a), b_(b), c_(c) {}
176 
187  template<typename Unit>
188  Euler(double a, double b, double c, Unit u);
189 
198  explicit Euler(const Quaternion &quat);
199 
205  template<typename A2, typename B2, typename C2, typename Conv2>
206  explicit Euler(const Euler<A2, B2, C2, Conv2> &o);
207 
213  explicit Euler(const OrientationVector &r);
214 
216  double a() const { return a_; }
218  double b() const { return b_; }
220  double c() const { return c_; }
221 
223  void a(double n) { a_ = n; }
225  void b(double n) { b_ = n; }
227  void c(double n) { c_ = n; }
228 
235 
243 
252 
259  static Euler from_quat(const Quaternion &quat);
260  private:
261  double a_, b_, c_;
262 
263  void set_from_quat(const Quaternion &quat);
264  };
265 
275 
278 
281 
284 
287 
289  template<typename A, typename B, typename C, typename Conv>
290  std::ostream &operator<<(std::ostream &o, const Euler<A, B, C, Conv> &e);
291  }
292  }
293 }
294 
295 #include "Euler.inl"
296 
297 #endif
Used internally to implement angle operations.
Definition: Quaternion.h:75
Provides Reference Frame (i.e., coordinate systemm) transforms.
Class template for representing an angle in Euler notation.
Definition: Euler.h:158
Euler(const Euler< A2, B2, C2, Conv2 > &o)
Constructor to convert from a different Euler convention.
double a() const
Getter for the first angular angle, around axis A.
Definition: Euler.h:216
void c(double n)
Setter for the first angular angle, around axis C.
Definition: Euler.h:227
detail::GetTypes< A, B, C, Conv >::F F
Definition: Euler.h:160
void b(double n)
Setter for the first angular angle, around axis B.
Definition: Euler.h:225
Quaternion to_quat() const
Convert this Euler angle to a Quaternion.
static Euler from_quat(const Quaternion &quat)
Convert a Quaternion into a Euler angle.
Euler(const OrientationVector &r)
Constructor to convert from a Orientation (or OrientationVector)
Euler(double a, double b, double c)
Constructor from radians.
Definition: Euler.h:175
Orientation to_orientation(const ReferenceFrame &frame) const
Convert this Euler angle to an Orientation (axis-angle notation), within the specified frame.
void a(double n)
Setter for the first angular angle, around axis A.
Definition: Euler.h:223
Orientation to_orientation() const
Convert this Euler angle to a Orientation (axis-angle notation), within the default frame.
detail::GetTypes< A, B, C, Conv >::Trig Trig
Definition: Euler.h:161
Euler()
Default constructor.
Definition: Euler.h:166
double c() const
Getter for the first angular angle, around axis C.
Definition: Euler.h:220
Euler(const Quaternion &quat)
Constructor to convert from a unit Quaternion.
double b() const
Getter for the first angular angle, around axis B.
Definition: Euler.h:218
Euler(double a, double b, double c, Unit u)
Constructor from specified units.
void set_from_quat(const Quaternion &quat)
Euler< conv::Y, conv::X, conv::Z, conv::Intr > EulerIntrYXZ
Definition: Euler.h:269
Euler< conv::X, conv::Y, conv::Z, conv::Extr > EulerExtrXYZ
Definition: Euler.h:270
Euler< conv::Z, conv::Y, conv::X, conv::Extr > EulerExtrZYX
Definition: Euler.h:274
Euler< conv::Z, conv::Y, conv::X > EulerZYX
Definition: Euler.h:272
std::ostream & operator<<(std::ostream &o, const Euler< A, B, C, Conv > &e)
Stream operator for Euler angles.
EulerIntrXYZ EulerVREP
The Euler convention used by VREP.
Definition: Euler.h:277
EulerYPR YawPitchRoll
A commonly used Euler convention: Yaw-Pitch-Roll.
Definition: Euler.h:283
Euler< conv::Z, conv::Y, conv::X, conv::Intr > EulerIntrZYX
Definition: Euler.h:273
EulerIntrZYX EulerYPR
A commonly used Euler convention: Yaw-Pitch-Roll.
Definition: Euler.h:280
Euler< conv::Y, conv::X, conv::Z > EulerYXZ
Definition: Euler.h:267
Euler< conv::X, conv::Y, conv::Z, conv::Intr > EulerIntrXYZ
Definition: Euler.h:268
Euler< conv::X, conv::Y, conv::Z > EulerXYZ
Definition: Euler.h:266
Euler< conv::Y, conv::X, conv::Z, conv::Extr > EulerExtrYXZ
Definition: Euler.h:271
EulerExtrXYZ RollPitchYaw
The most common vernacular usage of roll, pitch and yaw.
Definition: Euler.h:286
Contains all GAMS-related tools, classes and code.
static const char * name()
Definition: Euler.h:94
static const bool reverse
Definition: Euler.h:99
static const bool reverse
Definition: Euler.h:89
static const char * name()
Definition: Euler.h:87
static const char * name()
Definition: Euler.h:104
static const char * name()
Definition: Euler.h:109
static const char * name()
Definition: Euler.h:114
Copyright (c) 2015 Carnegie Mellon University.
Copyright (c) 2015 Carnegie Mellon University.
Copyright (c) 2015 Carnegie Mellon University.
Copyright (c) 2015 Carnegie Mellon University.