Mavlink Messages for Emaxx Nav Board

Dependents:   Madpulse_Speed_Control_temp Madpulse_Speed_Control_Students

Committer:
jdawkins
Date:
Fri Jan 20 13:20:58 2017 +0000
Revision:
0:bb2cacd02294
Child:
1:7e9af9a921f7
Initial Commit of Mavlink Messages for Emaxx Board custom messages for decawave ranging and bno055;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
jdawkins 0:bb2cacd02294 1 #ifndef _MAVLINK_CONVERSIONS_H_
jdawkins 0:bb2cacd02294 2 #define _MAVLINK_CONVERSIONS_H_
jdawkins 0:bb2cacd02294 3
jdawkins 0:bb2cacd02294 4 /* enable math defines on Windows */
jdawkins 0:bb2cacd02294 5 #ifdef _MSC_VER
jdawkins 0:bb2cacd02294 6 #ifndef _USE_MATH_DEFINES
jdawkins 0:bb2cacd02294 7 #define _USE_MATH_DEFINES
jdawkins 0:bb2cacd02294 8 #endif
jdawkins 0:bb2cacd02294 9 #endif
jdawkins 0:bb2cacd02294 10 #include <math.h>
jdawkins 0:bb2cacd02294 11
jdawkins 0:bb2cacd02294 12 #ifndef M_PI_2
jdawkins 0:bb2cacd02294 13 #define M_PI_2 ((float)asin(1))
jdawkins 0:bb2cacd02294 14 #endif
jdawkins 0:bb2cacd02294 15
jdawkins 0:bb2cacd02294 16 /**
jdawkins 0:bb2cacd02294 17 * @file mavlink_conversions.h
jdawkins 0:bb2cacd02294 18 *
jdawkins 0:bb2cacd02294 19 * These conversion functions follow the NASA rotation standards definition file
jdawkins 0:bb2cacd02294 20 * available online.
jdawkins 0:bb2cacd02294 21 *
jdawkins 0:bb2cacd02294 22 * Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free
jdawkins 0:bb2cacd02294 23 * (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free)
jdawkins 0:bb2cacd02294 24 * rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the
jdawkins 0:bb2cacd02294 25 * protocol as widely as possible.
jdawkins 0:bb2cacd02294 26 *
jdawkins 0:bb2cacd02294 27 * @author James Goppert
jdawkins 0:bb2cacd02294 28 * @author Thomas Gubler <thomasgubler@gmail.com>
jdawkins 0:bb2cacd02294 29 */
jdawkins 0:bb2cacd02294 30
jdawkins 0:bb2cacd02294 31
jdawkins 0:bb2cacd02294 32 /**
jdawkins 0:bb2cacd02294 33 * Converts a quaternion to a rotation matrix
jdawkins 0:bb2cacd02294 34 *
jdawkins 0:bb2cacd02294 35 * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
jdawkins 0:bb2cacd02294 36 * @param dcm a 3x3 rotation matrix
jdawkins 0:bb2cacd02294 37 */
jdawkins 0:bb2cacd02294 38 MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3])
jdawkins 0:bb2cacd02294 39 {
jdawkins 0:bb2cacd02294 40 double a = quaternion[0];
jdawkins 0:bb2cacd02294 41 double b = quaternion[1];
jdawkins 0:bb2cacd02294 42 double c = quaternion[2];
jdawkins 0:bb2cacd02294 43 double d = quaternion[3];
jdawkins 0:bb2cacd02294 44 double aSq = a * a;
jdawkins 0:bb2cacd02294 45 double bSq = b * b;
jdawkins 0:bb2cacd02294 46 double cSq = c * c;
jdawkins 0:bb2cacd02294 47 double dSq = d * d;
jdawkins 0:bb2cacd02294 48 dcm[0][0] = aSq + bSq - cSq - dSq;
jdawkins 0:bb2cacd02294 49 dcm[0][1] = 2 * (b * c - a * d);
jdawkins 0:bb2cacd02294 50 dcm[0][2] = 2 * (a * c + b * d);
jdawkins 0:bb2cacd02294 51 dcm[1][0] = 2 * (b * c + a * d);
jdawkins 0:bb2cacd02294 52 dcm[1][1] = aSq - bSq + cSq - dSq;
jdawkins 0:bb2cacd02294 53 dcm[1][2] = 2 * (c * d - a * b);
jdawkins 0:bb2cacd02294 54 dcm[2][0] = 2 * (b * d - a * c);
jdawkins 0:bb2cacd02294 55 dcm[2][1] = 2 * (a * b + c * d);
jdawkins 0:bb2cacd02294 56 dcm[2][2] = aSq - bSq - cSq + dSq;
jdawkins 0:bb2cacd02294 57 }
jdawkins 0:bb2cacd02294 58
jdawkins 0:bb2cacd02294 59
jdawkins 0:bb2cacd02294 60 /**
jdawkins 0:bb2cacd02294 61 * Converts a rotation matrix to euler angles
jdawkins 0:bb2cacd02294 62 *
jdawkins 0:bb2cacd02294 63 * @param dcm a 3x3 rotation matrix
jdawkins 0:bb2cacd02294 64 * @param roll the roll angle in radians
jdawkins 0:bb2cacd02294 65 * @param pitch the pitch angle in radians
jdawkins 0:bb2cacd02294 66 * @param yaw the yaw angle in radians
jdawkins 0:bb2cacd02294 67 */
jdawkins 0:bb2cacd02294 68 MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw)
jdawkins 0:bb2cacd02294 69 {
jdawkins 0:bb2cacd02294 70 float phi, theta, psi;
jdawkins 0:bb2cacd02294 71 theta = asin(-dcm[2][0]);
jdawkins 0:bb2cacd02294 72
jdawkins 0:bb2cacd02294 73 if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) {
jdawkins 0:bb2cacd02294 74 phi = 0.0f;
jdawkins 0:bb2cacd02294 75 psi = (atan2f(dcm[1][2] - dcm[0][1],
jdawkins 0:bb2cacd02294 76 dcm[0][2] + dcm[1][1]) + phi);
jdawkins 0:bb2cacd02294 77
jdawkins 0:bb2cacd02294 78 } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) {
jdawkins 0:bb2cacd02294 79 phi = 0.0f;
jdawkins 0:bb2cacd02294 80 psi = atan2f(dcm[1][2] - dcm[0][1],
jdawkins 0:bb2cacd02294 81 dcm[0][2] + dcm[1][1] - phi);
jdawkins 0:bb2cacd02294 82
jdawkins 0:bb2cacd02294 83 } else {
jdawkins 0:bb2cacd02294 84 phi = atan2f(dcm[2][1], dcm[2][2]);
jdawkins 0:bb2cacd02294 85 psi = atan2f(dcm[1][0], dcm[0][0]);
jdawkins 0:bb2cacd02294 86 }
jdawkins 0:bb2cacd02294 87
jdawkins 0:bb2cacd02294 88 *roll = phi;
jdawkins 0:bb2cacd02294 89 *pitch = theta;
jdawkins 0:bb2cacd02294 90 *yaw = psi;
jdawkins 0:bb2cacd02294 91 }
jdawkins 0:bb2cacd02294 92
jdawkins 0:bb2cacd02294 93
jdawkins 0:bb2cacd02294 94 /**
jdawkins 0:bb2cacd02294 95 * Converts a quaternion to euler angles
jdawkins 0:bb2cacd02294 96 *
jdawkins 0:bb2cacd02294 97 * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
jdawkins 0:bb2cacd02294 98 * @param roll the roll angle in radians
jdawkins 0:bb2cacd02294 99 * @param pitch the pitch angle in radians
jdawkins 0:bb2cacd02294 100 * @param yaw the yaw angle in radians
jdawkins 0:bb2cacd02294 101 */
jdawkins 0:bb2cacd02294 102 MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw)
jdawkins 0:bb2cacd02294 103 {
jdawkins 0:bb2cacd02294 104 float dcm[3][3];
jdawkins 0:bb2cacd02294 105 mavlink_quaternion_to_dcm(quaternion, dcm);
jdawkins 0:bb2cacd02294 106 mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw);
jdawkins 0:bb2cacd02294 107 }
jdawkins 0:bb2cacd02294 108
jdawkins 0:bb2cacd02294 109
jdawkins 0:bb2cacd02294 110 /**
jdawkins 0:bb2cacd02294 111 * Converts euler angles to a quaternion
jdawkins 0:bb2cacd02294 112 *
jdawkins 0:bb2cacd02294 113 * @param roll the roll angle in radians
jdawkins 0:bb2cacd02294 114 * @param pitch the pitch angle in radians
jdawkins 0:bb2cacd02294 115 * @param yaw the yaw angle in radians
jdawkins 0:bb2cacd02294 116 * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
jdawkins 0:bb2cacd02294 117 */
jdawkins 0:bb2cacd02294 118 MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4])
jdawkins 0:bb2cacd02294 119 {
jdawkins 0:bb2cacd02294 120 float cosPhi_2 = cosf(roll / 2);
jdawkins 0:bb2cacd02294 121 float sinPhi_2 = sinf(roll / 2);
jdawkins 0:bb2cacd02294 122 float cosTheta_2 = cosf(pitch / 2);
jdawkins 0:bb2cacd02294 123 float sinTheta_2 = sinf(pitch / 2);
jdawkins 0:bb2cacd02294 124 float cosPsi_2 = cosf(yaw / 2);
jdawkins 0:bb2cacd02294 125 float sinPsi_2 = sinf(yaw / 2);
jdawkins 0:bb2cacd02294 126 quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
jdawkins 0:bb2cacd02294 127 sinPhi_2 * sinTheta_2 * sinPsi_2);
jdawkins 0:bb2cacd02294 128 quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
jdawkins 0:bb2cacd02294 129 cosPhi_2 * sinTheta_2 * sinPsi_2);
jdawkins 0:bb2cacd02294 130 quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 +
jdawkins 0:bb2cacd02294 131 sinPhi_2 * cosTheta_2 * sinPsi_2);
jdawkins 0:bb2cacd02294 132 quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 -
jdawkins 0:bb2cacd02294 133 sinPhi_2 * sinTheta_2 * cosPsi_2);
jdawkins 0:bb2cacd02294 134 }
jdawkins 0:bb2cacd02294 135
jdawkins 0:bb2cacd02294 136
jdawkins 0:bb2cacd02294 137 /**
jdawkins 0:bb2cacd02294 138 * Converts a rotation matrix to a quaternion
jdawkins 0:bb2cacd02294 139 * Reference:
jdawkins 0:bb2cacd02294 140 * - Shoemake, Quaternions,
jdawkins 0:bb2cacd02294 141 * http://www.cs.ucr.edu/~vbz/resources/quatut.pdf
jdawkins 0:bb2cacd02294 142 *
jdawkins 0:bb2cacd02294 143 * @param dcm a 3x3 rotation matrix
jdawkins 0:bb2cacd02294 144 * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
jdawkins 0:bb2cacd02294 145 */
jdawkins 0:bb2cacd02294 146 MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4])
jdawkins 0:bb2cacd02294 147 {
jdawkins 0:bb2cacd02294 148 float tr = dcm[0][0] + dcm[1][1] + dcm[2][2];
jdawkins 0:bb2cacd02294 149 if (tr > 0.0f) {
jdawkins 0:bb2cacd02294 150 float s = sqrtf(tr + 1.0f);
jdawkins 0:bb2cacd02294 151 quaternion[0] = s * 0.5f;
jdawkins 0:bb2cacd02294 152 s = 0.5f / s;
jdawkins 0:bb2cacd02294 153 quaternion[1] = (dcm[2][1] - dcm[1][2]) * s;
jdawkins 0:bb2cacd02294 154 quaternion[2] = (dcm[0][2] - dcm[2][0]) * s;
jdawkins 0:bb2cacd02294 155 quaternion[3] = (dcm[1][0] - dcm[0][1]) * s;
jdawkins 0:bb2cacd02294 156 } else {
jdawkins 0:bb2cacd02294 157 /* Find maximum diagonal element in dcm
jdawkins 0:bb2cacd02294 158 * store index in dcm_i */
jdawkins 0:bb2cacd02294 159 int dcm_i = 0;
jdawkins 0:bb2cacd02294 160 int i;
jdawkins 0:bb2cacd02294 161 for (i = 1; i < 3; i++) {
jdawkins 0:bb2cacd02294 162 if (dcm[i][i] > dcm[dcm_i][dcm_i]) {
jdawkins 0:bb2cacd02294 163 dcm_i = i;
jdawkins 0:bb2cacd02294 164 }
jdawkins 0:bb2cacd02294 165 }
jdawkins 0:bb2cacd02294 166
jdawkins 0:bb2cacd02294 167 int dcm_j = (dcm_i + 1) % 3;
jdawkins 0:bb2cacd02294 168 int dcm_k = (dcm_i + 2) % 3;
jdawkins 0:bb2cacd02294 169
jdawkins 0:bb2cacd02294 170 float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] -
jdawkins 0:bb2cacd02294 171 dcm[dcm_k][dcm_k]) + 1.0f);
jdawkins 0:bb2cacd02294 172 quaternion[dcm_i + 1] = s * 0.5f;
jdawkins 0:bb2cacd02294 173 s = 0.5f / s;
jdawkins 0:bb2cacd02294 174 quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s;
jdawkins 0:bb2cacd02294 175 quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s;
jdawkins 0:bb2cacd02294 176 quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s;
jdawkins 0:bb2cacd02294 177 }
jdawkins 0:bb2cacd02294 178 }
jdawkins 0:bb2cacd02294 179
jdawkins 0:bb2cacd02294 180
jdawkins 0:bb2cacd02294 181 /**
jdawkins 0:bb2cacd02294 182 * Converts euler angles to a rotation matrix
jdawkins 0:bb2cacd02294 183 *
jdawkins 0:bb2cacd02294 184 * @param roll the roll angle in radians
jdawkins 0:bb2cacd02294 185 * @param pitch the pitch angle in radians
jdawkins 0:bb2cacd02294 186 * @param yaw the yaw angle in radians
jdawkins 0:bb2cacd02294 187 * @param dcm a 3x3 rotation matrix
jdawkins 0:bb2cacd02294 188 */
jdawkins 0:bb2cacd02294 189 MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3])
jdawkins 0:bb2cacd02294 190 {
jdawkins 0:bb2cacd02294 191 float cosPhi = cosf(roll);
jdawkins 0:bb2cacd02294 192 float sinPhi = sinf(roll);
jdawkins 0:bb2cacd02294 193 float cosThe = cosf(pitch);
jdawkins 0:bb2cacd02294 194 float sinThe = sinf(pitch);
jdawkins 0:bb2cacd02294 195 float cosPsi = cosf(yaw);
jdawkins 0:bb2cacd02294 196 float sinPsi = sinf(yaw);
jdawkins 0:bb2cacd02294 197
jdawkins 0:bb2cacd02294 198 dcm[0][0] = cosThe * cosPsi;
jdawkins 0:bb2cacd02294 199 dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi;
jdawkins 0:bb2cacd02294 200 dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi;
jdawkins 0:bb2cacd02294 201
jdawkins 0:bb2cacd02294 202 dcm[1][0] = cosThe * sinPsi;
jdawkins 0:bb2cacd02294 203 dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi;
jdawkins 0:bb2cacd02294 204 dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi;
jdawkins 0:bb2cacd02294 205
jdawkins 0:bb2cacd02294 206 dcm[2][0] = -sinThe;
jdawkins 0:bb2cacd02294 207 dcm[2][1] = sinPhi * cosThe;
jdawkins 0:bb2cacd02294 208 dcm[2][2] = cosPhi * cosThe;
jdawkins 0:bb2cacd02294 209 }
jdawkins 0:bb2cacd02294 210
jdawkins 0:bb2cacd02294 211 #endif
jdawkins 0:bb2cacd02294 212