Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Committer:
shimniok
Date:
Wed Jun 20 14:57:48 2012 +0000
Revision:
0:826c6171fc1b
Updated documentation

Who changed what in which revision?

UserRevisionLine numberNew contents of line
shimniok 0:826c6171fc1b 1 // MESSAGE GPS_RAW_UGV PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_GPS_RAW_UGV 86
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_gps_raw_ugv_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 8 uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
shimniok 0:826c6171fc1b 9 double lat; ///< Latitude in 1E15 degrees
shimniok 0:826c6171fc1b 10 double lon; ///< Longitude in 1E15 degrees
shimniok 0:826c6171fc1b 11 float eph; ///< GPS HDOP
shimniok 0:826c6171fc1b 12 float epv; ///< GPS VDOP
shimniok 0:826c6171fc1b 13 float v; ///< GPS ground speed
shimniok 0:826c6171fc1b 14 float hdg; ///< Compass heading in degrees, 0..360 degrees
shimniok 0:826c6171fc1b 15
shimniok 0:826c6171fc1b 16 } mavlink_gps_raw_ugv_t;
shimniok 0:826c6171fc1b 17
shimniok 0:826c6171fc1b 18
shimniok 0:826c6171fc1b 19 /**
shimniok 0:826c6171fc1b 20 * @brief Pack a gps_raw message
shimniok 0:826c6171fc1b 21 * @param system_id ID of this system
shimniok 0:826c6171fc1b 22 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 23 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 24 *
shimniok 0:826c6171fc1b 25 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 26 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
shimniok 0:826c6171fc1b 27 * @param lat Latitude in degrees
shimniok 0:826c6171fc1b 28 * @param lon Longitude in degrees
shimniok 0:826c6171fc1b 29 * @param eph GPS HDOP
shimniok 0:826c6171fc1b 30 * @param epv GPS VDOP
shimniok 0:826c6171fc1b 31 * @param v GPS ground speed
shimniok 0:826c6171fc1b 32 * @param hdg Compass heading in degrees, 0..360 degrees
shimniok 0:826c6171fc1b 33 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 34 */
shimniok 0:826c6171fc1b 35 static inline uint16_t mavlink_msg_gps_raw_ugv_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, double lat, double lon, float eph, float epv, float v, float hdg)
shimniok 0:826c6171fc1b 36 {
shimniok 0:826c6171fc1b 37 uint16_t i = 0;
shimniok 0:826c6171fc1b 38 msg->msgid = MAVLINK_MSG_ID_GPS_RAW_UGV;
shimniok 0:826c6171fc1b 39
shimniok 0:826c6171fc1b 40 i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 41 i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
shimniok 0:826c6171fc1b 42 i += put_double_by_index(lat, i, msg->payload); // Latitude in degrees
shimniok 0:826c6171fc1b 43 i += put_double_by_index(lon, i, msg->payload); // Longitude in degrees
shimniok 0:826c6171fc1b 44 i += put_float_by_index(eph, i, msg->payload); // GPS HDOP
shimniok 0:826c6171fc1b 45 i += put_float_by_index(epv, i, msg->payload); // GPS VDOP
shimniok 0:826c6171fc1b 46 i += put_float_by_index(v, i, msg->payload); // GPS ground speed
shimniok 0:826c6171fc1b 47 i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees
shimniok 0:826c6171fc1b 48
shimniok 0:826c6171fc1b 49 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:826c6171fc1b 50 }
shimniok 0:826c6171fc1b 51
shimniok 0:826c6171fc1b 52 /**
shimniok 0:826c6171fc1b 53 * @brief Pack a gps_raw message
shimniok 0:826c6171fc1b 54 * @param system_id ID of this system
shimniok 0:826c6171fc1b 55 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 56 * @param chan The MAVLink channel this message was sent over
shimniok 0:826c6171fc1b 57 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 58 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 59 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
shimniok 0:826c6171fc1b 60 * @param lat Latitude in degrees
shimniok 0:826c6171fc1b 61 * @param lon Longitude in degrees
shimniok 0:826c6171fc1b 62 * @param eph GPS HDOP
shimniok 0:826c6171fc1b 63 * @param epv GPS VDOP
shimniok 0:826c6171fc1b 64 * @param v GPS ground speed
shimniok 0:826c6171fc1b 65 * @param hdg Compass heading in degrees, 0..360 degrees
shimniok 0:826c6171fc1b 66 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 67 */
shimniok 0:826c6171fc1b 68 static inline uint16_t mavlink_msg_gps_raw_ugv_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, double lat, double lon, float eph, float epv, float v, float hdg)
shimniok 0:826c6171fc1b 69 {
shimniok 0:826c6171fc1b 70 uint16_t i = 0;
shimniok 0:826c6171fc1b 71 msg->msgid = MAVLINK_MSG_ID_GPS_RAW_UGV;
shimniok 0:826c6171fc1b 72
shimniok 0:826c6171fc1b 73 i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 74 i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
shimniok 0:826c6171fc1b 75 i += put_double_by_index(lat, i, msg->payload); // Latitude in degrees
shimniok 0:826c6171fc1b 76 i += put_double_by_index(lon, i, msg->payload); // Longitude in degrees
shimniok 0:826c6171fc1b 77 i += put_float_by_index(eph, i, msg->payload); // GPS HDOP
shimniok 0:826c6171fc1b 78 i += put_float_by_index(epv, i, msg->payload); // GPS VDOP
shimniok 0:826c6171fc1b 79 i += put_float_by_index(v, i, msg->payload); // GPS ground speed
shimniok 0:826c6171fc1b 80 i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees
shimniok 0:826c6171fc1b 81
shimniok 0:826c6171fc1b 82 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:826c6171fc1b 83 }
shimniok 0:826c6171fc1b 84
shimniok 0:826c6171fc1b 85 /**
shimniok 0:826c6171fc1b 86 * @brief Encode a gps_raw struct into a message
shimniok 0:826c6171fc1b 87 *
shimniok 0:826c6171fc1b 88 * @param system_id ID of this system
shimniok 0:826c6171fc1b 89 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 90 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 91 * @param gps_raw C-struct to read the message contents from
shimniok 0:826c6171fc1b 92 */
shimniok 0:826c6171fc1b 93 static inline uint16_t mavlink_msg_gps_raw_ugv_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_ugv_t* gps_raw)
shimniok 0:826c6171fc1b 94 {
shimniok 0:826c6171fc1b 95 return mavlink_msg_gps_raw_ugv_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg);
shimniok 0:826c6171fc1b 96 }
shimniok 0:826c6171fc1b 97
shimniok 0:826c6171fc1b 98 /**
shimniok 0:826c6171fc1b 99 * @brief Send a gps_raw message
shimniok 0:826c6171fc1b 100 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 101 *
shimniok 0:826c6171fc1b 102 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 103 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
shimniok 0:826c6171fc1b 104 * @param lat Latitude in degrees
shimniok 0:826c6171fc1b 105 * @param lon Longitude in degrees
shimniok 0:826c6171fc1b 106 * @param eph GPS HDOP
shimniok 0:826c6171fc1b 107 * @param epv GPS VDOP
shimniok 0:826c6171fc1b 108 * @param v GPS ground speed
shimniok 0:826c6171fc1b 109 * @param hdg Compass heading in degrees, 0..360 degrees
shimniok 0:826c6171fc1b 110 */
shimniok 0:826c6171fc1b 111 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:826c6171fc1b 112
shimniok 0:826c6171fc1b 113 static inline void mavlink_msg_gps_raw_ugv_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, double lat, double lon, float eph, float epv, float v, float hdg)
shimniok 0:826c6171fc1b 114 {
shimniok 0:826c6171fc1b 115 mavlink_message_t msg;
shimniok 0:826c6171fc1b 116 mavlink_msg_gps_raw_ugv_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, fix_type, lat, lon, eph, epv, v, hdg);
shimniok 0:826c6171fc1b 117 mavlink_send_uart(chan, &msg);
shimniok 0:826c6171fc1b 118 }
shimniok 0:826c6171fc1b 119
shimniok 0:826c6171fc1b 120 #endif
shimniok 0:826c6171fc1b 121 // MESSAGE GPS_RAW UNPACKING
shimniok 0:826c6171fc1b 122
shimniok 0:826c6171fc1b 123 /**
shimniok 0:826c6171fc1b 124 * @brief Get field usec from gps_raw message
shimniok 0:826c6171fc1b 125 *
shimniok 0:826c6171fc1b 126 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 127 */
shimniok 0:826c6171fc1b 128 static inline uint64_t mavlink_msg_gps_raw_ugv_get_usec(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 129 {
shimniok 0:826c6171fc1b 130 generic_64bit r;
shimniok 0:826c6171fc1b 131 r.b[7] = (msg->payload)[0];
shimniok 0:826c6171fc1b 132 r.b[6] = (msg->payload)[1];
shimniok 0:826c6171fc1b 133 r.b[5] = (msg->payload)[2];
shimniok 0:826c6171fc1b 134 r.b[4] = (msg->payload)[3];
shimniok 0:826c6171fc1b 135 r.b[3] = (msg->payload)[4];
shimniok 0:826c6171fc1b 136 r.b[2] = (msg->payload)[5];
shimniok 0:826c6171fc1b 137 r.b[1] = (msg->payload)[6];
shimniok 0:826c6171fc1b 138 r.b[0] = (msg->payload)[7];
shimniok 0:826c6171fc1b 139 return (uint64_t)r.ll;
shimniok 0:826c6171fc1b 140 }
shimniok 0:826c6171fc1b 141
shimniok 0:826c6171fc1b 142 /**
shimniok 0:826c6171fc1b 143 * @brief Get field fix_type from gps_raw message
shimniok 0:826c6171fc1b 144 *
shimniok 0:826c6171fc1b 145 * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
shimniok 0:826c6171fc1b 146 */
shimniok 0:826c6171fc1b 147 static inline uint8_t mavlink_msg_gps_raw_ugv_get_fix_type(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 148 {
shimniok 0:826c6171fc1b 149 return (uint8_t)(msg->payload+sizeof(uint64_t))[0];
shimniok 0:826c6171fc1b 150 }
shimniok 0:826c6171fc1b 151
shimniok 0:826c6171fc1b 152 /**
shimniok 0:826c6171fc1b 153 * @brief Get field lat from gps_raw message
shimniok 0:826c6171fc1b 154 *
shimniok 0:826c6171fc1b 155 * @return Latitude in degrees
shimniok 0:826c6171fc1b 156 */
shimniok 0:826c6171fc1b 157 static inline double mavlink_msg_gps_raw_ugv_get_lat(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 158 {
shimniok 0:826c6171fc1b 159 generic_64bit r;
shimniok 0:826c6171fc1b 160 r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0];
shimniok 0:826c6171fc1b 161 r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1];
shimniok 0:826c6171fc1b 162 r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2];
shimniok 0:826c6171fc1b 163 r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3];
shimniok 0:826c6171fc1b 164 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[4];
shimniok 0:826c6171fc1b 165 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[5];
shimniok 0:826c6171fc1b 166 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[6];
shimniok 0:826c6171fc1b 167 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[7];
shimniok 0:826c6171fc1b 168 return (double)r.d;
shimniok 0:826c6171fc1b 169 }
shimniok 0:826c6171fc1b 170
shimniok 0:826c6171fc1b 171 /**
shimniok 0:826c6171fc1b 172 * @brief Get field lon from gps_raw message
shimniok 0:826c6171fc1b 173 *
shimniok 0:826c6171fc1b 174 * @return Longitude in degrees
shimniok 0:826c6171fc1b 175 */
shimniok 0:826c6171fc1b 176 static inline double mavlink_msg_gps_raw_ugv_get_lon(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 177 {
shimniok 0:826c6171fc1b 178 generic_64bit r;
shimniok 0:826c6171fc1b 179 r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[0];
shimniok 0:826c6171fc1b 180 r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[1];
shimniok 0:826c6171fc1b 181 r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[2];
shimniok 0:826c6171fc1b 182 r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[3];
shimniok 0:826c6171fc1b 183 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[4];
shimniok 0:826c6171fc1b 184 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[5];
shimniok 0:826c6171fc1b 185 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[6];
shimniok 0:826c6171fc1b 186 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[7];
shimniok 0:826c6171fc1b 187 return (double)r.d;
shimniok 0:826c6171fc1b 188 }
shimniok 0:826c6171fc1b 189
shimniok 0:826c6171fc1b 190 /**
shimniok 0:826c6171fc1b 191 * @brief Get field eph from gps_raw message
shimniok 0:826c6171fc1b 192 *
shimniok 0:826c6171fc1b 193 * @return GPS HDOP
shimniok 0:826c6171fc1b 194 */
shimniok 0:826c6171fc1b 195 static inline float mavlink_msg_gps_raw_ugv_get_eph(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 196 {
shimniok 0:826c6171fc1b 197 generic_32bit r;
shimniok 0:826c6171fc1b 198 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[0];
shimniok 0:826c6171fc1b 199 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[1];
shimniok 0:826c6171fc1b 200 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[2];
shimniok 0:826c6171fc1b 201 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[3];
shimniok 0:826c6171fc1b 202 return (float)r.f;
shimniok 0:826c6171fc1b 203 }
shimniok 0:826c6171fc1b 204
shimniok 0:826c6171fc1b 205 /**
shimniok 0:826c6171fc1b 206 * @brief Get field epv from gps_raw message
shimniok 0:826c6171fc1b 207 *
shimniok 0:826c6171fc1b 208 * @return GPS VDOP
shimniok 0:826c6171fc1b 209 */
shimniok 0:826c6171fc1b 210 static inline float mavlink_msg_gps_raw_ugv_get_epv(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 211 {
shimniok 0:826c6171fc1b 212 generic_32bit r;
shimniok 0:826c6171fc1b 213 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 214 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 215 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 216 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 217 return (float)r.f;
shimniok 0:826c6171fc1b 218 }
shimniok 0:826c6171fc1b 219
shimniok 0:826c6171fc1b 220 /**
shimniok 0:826c6171fc1b 221 * @brief Get field v from gps_raw message
shimniok 0:826c6171fc1b 222 *
shimniok 0:826c6171fc1b 223 * @return GPS ground speed
shimniok 0:826c6171fc1b 224 */
shimniok 0:826c6171fc1b 225 static inline float mavlink_msg_gps_raw_ugv_get_v(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 226 {
shimniok 0:826c6171fc1b 227 generic_32bit r;
shimniok 0:826c6171fc1b 228 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 229 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 230 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 231 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 232 return (float)r.f;
shimniok 0:826c6171fc1b 233 }
shimniok 0:826c6171fc1b 234
shimniok 0:826c6171fc1b 235 /**
shimniok 0:826c6171fc1b 236 * @brief Get field hdg from gps_raw message
shimniok 0:826c6171fc1b 237 *
shimniok 0:826c6171fc1b 238 * @return Compass heading in degrees, 0..360 degrees
shimniok 0:826c6171fc1b 239 */
shimniok 0:826c6171fc1b 240 static inline float mavlink_msg_gps_raw_ugv_get_hdg(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 241 {
shimniok 0:826c6171fc1b 242 generic_32bit r;
shimniok 0:826c6171fc1b 243 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 244 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 245 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 246 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 247 return (float)r.f;
shimniok 0:826c6171fc1b 248 }
shimniok 0:826c6171fc1b 249
shimniok 0:826c6171fc1b 250 /**
shimniok 0:826c6171fc1b 251 * @brief Decode a gps_raw message into a struct
shimniok 0:826c6171fc1b 252 *
shimniok 0:826c6171fc1b 253 * @param msg The message to decode
shimniok 0:826c6171fc1b 254 * @param gps_raw C-struct to decode the message contents into
shimniok 0:826c6171fc1b 255 */
shimniok 0:826c6171fc1b 256 static inline void mavlink_msg_gps_raw_ugv_decode(const mavlink_message_t* msg, mavlink_gps_raw_ugv_t* gps_raw)
shimniok 0:826c6171fc1b 257 {
shimniok 0:826c6171fc1b 258 gps_raw->usec = mavlink_msg_gps_raw_ugv_get_usec(msg);
shimniok 0:826c6171fc1b 259 gps_raw->fix_type = mavlink_msg_gps_raw_ugv_get_fix_type(msg);
shimniok 0:826c6171fc1b 260 gps_raw->lat = mavlink_msg_gps_raw_ugv_get_lat(msg);
shimniok 0:826c6171fc1b 261 gps_raw->lon = mavlink_msg_gps_raw_ugv_get_lon(msg);
shimniok 0:826c6171fc1b 262 gps_raw->eph = mavlink_msg_gps_raw_ugv_get_eph(msg);
shimniok 0:826c6171fc1b 263 gps_raw->epv = mavlink_msg_gps_raw_ugv_get_epv(msg);
shimniok 0:826c6171fc1b 264 gps_raw->v = mavlink_msg_gps_raw_ugv_get_v(msg);
shimniok 0:826c6171fc1b 265 gps_raw->hdg = mavlink_msg_gps_raw_ugv_get_hdg(msg);
shimniok 0:826c6171fc1b 266 }