00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef CONVERSIONS_HPP_
00038 #define CONVERSIONS_HPP_
00039 #include <Eigen/Dense>
00040
00041 #include <geometry_msgs/Quaternion.h>
00042
00043 namespace labust
00044 {
00045 namespace tools
00046 {
00050 template <class Point, class Iterator>
00051 void pointToVector(const Point& point, Iterator& vec, int offset = 0)
00052 {
00053 vec[offset+0] = point.x;
00054 vec[offset+1] = point.y;
00055 vec[offset+2] = point.z;
00056 }
00057
00061 template <class Point, class Iterator>
00062 void vectorToPoint(const Iterator& vec, Point& point, int offset = 0)
00063 {
00064 point.x = vec[offset+0];
00065 point.y = vec[offset+1];
00066 point.z = vec[offset+2];
00067 }
00068
00072 template <class Point, class Iterator>
00073 void nedToVector(const Point& point, Iterator& vec, int offset = 0)
00074 {
00075 vec[offset+0] = point.north;
00076 vec[offset+1] = point.east;
00077 vec[offset+2] = point.depth;
00078 }
00079
00083 template <class Point, class Iterator>
00084 void vectorToNED(const Iterator& vec, Point& point, int offset = 0)
00085 {
00086 point.north = vec[offset+0];
00087 point.east = vec[offset+1];
00088 point.depth = vec[offset+2];
00089 }
00090
00094 template <class Point, class Iterator>
00095 void rpyToVector(const Point& point, Iterator& vec, int offset = 0)
00096 {
00097 vec[offset+0] = point.roll;
00098 vec[offset+1] = point.pitch;
00099 vec[offset+2] = point.yaw;
00100 }
00101
00105 template <class Point, class Iterator>
00106 void vectorToRPY(const Iterator& vec, Point& point, int offset = 0)
00107 {
00108 point.roll = vec[offset+0];
00109 point.pitch = vec[offset+1];
00110 point.yaw = vec[offset+2];
00111 }
00112
00116 template <class Point, class Iterator>
00117 void vectorToDisableAxis(const Iterator& vec, Point& point)
00118 {
00119 point.x = vec[0];
00120 point.y = vec[1];
00121 point.z = vec[2];
00122 point.roll = vec[3];
00123 point.pitch = vec[4];
00124 point.yaw = vec[5];
00125 }
00126
00127 template <class Point, class Iterator>
00128 void disableAxisToVector(Point& point, const Iterator& vec)
00129 {
00130 vec[0] = point.x;
00131 vec[1] = point.y;
00132 vec[2] = point.z;
00133 vec[3] = point.roll;
00134 vec[4] = point.pitch;
00135 vec[5] = point.yaw;
00136 }
00137
00138 template <class T>
00139 void quaternionFromEulerZYX(double roll, double pitch, double yaw, Eigen::Quaternion<T>& q)
00140 {
00141 using namespace Eigen;
00142 Matrix<T,3,3> Cx,Cy,Cz,m;
00143 typedef Matrix<T,3,1> Vector3;
00144 Cx = AngleAxis<T>(roll, Vector3::UnitX());
00145 Cy = AngleAxis<T>(pitch, Vector3::UnitY());
00146 Cz = AngleAxis<T>(yaw, Vector3::UnitZ());
00147
00148 m = (Cz*Cy*Cx);
00149
00150 q = Quaternion<T>(m);
00151 }
00152
00153 template <class T>
00154 void quaternionFromEulerZYX(double roll, double pitch, double yaw, T& q)
00155 {
00156 Eigen::Quaternion<double> t;
00157 quaternionFromEulerZYX(roll, pitch, yaw, t);
00158 q.x = t.x();
00159 q.y = t.y();
00160 q.z = t.z();
00161 q.w = t.w();
00162 }
00163
00164
00165 template <class T>
00166 void eulerZYXFromQuaternion(const T& q, double& roll, double& pitch, double& yaw)
00167 {
00168 using namespace Eigen;
00169
00170 roll = atan2(2*(q.y()*q.z() + q.x()*q.w()),1-2*(q.x()*q.x() + q.y()*q.y()));
00171 pitch = -asin(2*(q.x()*q.z()-q.y()*q.w()));
00172 yaw = atan2(2*(q.y()*q.x()+q.w()*q.z()),1-2*(q.y()*q.y()+q.z()*q.z()));
00173
00174
00175
00176
00177 }
00178
00179
00180 template <class T, class V>
00181 void eulerZYXFromQuaternion(const T& q, V& vect)
00182 {
00183 using namespace Eigen;
00184
00185 enum {roll=0, pitch, yaw};
00186 vect(roll) = atan2(2*(q.y()*q.z() + q.x()*q.w()),1-2*(q.x()*q.x() + q.y()*q.y()));
00187 vect(pitch) = -asin(2*(q.x()*q.z()-q.y()*q.w()));
00188 vect(yaw) = atan2(2*(q.y()*q.x()+q.w()*q.z()),1-2*(q.y()*q.y()+q.z()*q.z()));
00189
00190
00191
00192
00193 }
00194
00195
00196 inline void eulerZYXFromQuaternion(const geometry_msgs::Quaternion& q,
00197 double& roll, double& pitch, double& yaw)
00198 {
00199 using namespace Eigen;
00200
00201 roll = atan2(2*(q.y*q.z + q.x*q.w),1-2*(q.x*q.x + q.y*q.y));
00202 pitch = -asin(2*(q.x*q.z-q.y*q.w));
00203 yaw = atan2(2*(q.y*q.x+q.w*q.z),1-2*(q.y*q.y+q.z*q.z));
00204
00205
00206
00207
00208 }
00209 }
00210 }
00211
00212
00213 #endif