Code for autonomous rover for Sparkfun AVC. DataBus won 3rd in 2012 and the same code was used on Troubled Child, a 1986 Jeep Grand Wagoneer to win 1st in 2014.
Dependencies: mbed Watchdog SDFileSystem DigoleSerialDisp
MAVlink/include/common/mavlink_msg_gps_raw_ugv.h@25:bb5356402687, 2018-11-30 (annotated)
- Committer:
- shimniok
- Date:
- Fri Nov 30 16:11:53 2018 +0000
- Revision:
- 25:bb5356402687
- Parent:
- 0:a6a169de725f
Initial publish of revised version.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
shimniok | 0:a6a169de725f | 1 | // MESSAGE GPS_RAW_UGV PACKING |
shimniok | 0:a6a169de725f | 2 | |
shimniok | 0:a6a169de725f | 3 | #define MAVLINK_MSG_ID_GPS_RAW_UGV 86 |
shimniok | 0:a6a169de725f | 4 | |
shimniok | 0:a6a169de725f | 5 | typedef struct __mavlink_gps_raw_ugv_t |
shimniok | 0:a6a169de725f | 6 | { |
shimniok | 0:a6a169de725f | 7 | uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 9 | double lat; ///< Latitude in 1E15 degrees |
shimniok | 0:a6a169de725f | 10 | double lon; ///< Longitude in 1E15 degrees |
shimniok | 0:a6a169de725f | 11 | float eph; ///< GPS HDOP |
shimniok | 0:a6a169de725f | 12 | float epv; ///< GPS VDOP |
shimniok | 0:a6a169de725f | 13 | float v; ///< GPS ground speed |
shimniok | 0:a6a169de725f | 14 | float hdg; ///< Compass heading in degrees, 0..360 degrees |
shimniok | 0:a6a169de725f | 15 | |
shimniok | 0:a6a169de725f | 16 | } mavlink_gps_raw_ugv_t; |
shimniok | 0:a6a169de725f | 17 | |
shimniok | 0:a6a169de725f | 18 | |
shimniok | 0:a6a169de725f | 19 | /** |
shimniok | 0:a6a169de725f | 20 | * @brief Pack a gps_raw message |
shimniok | 0:a6a169de725f | 21 | * @param system_id ID of this system |
shimniok | 0:a6a169de725f | 22 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:a6a169de725f | 23 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:a6a169de725f | 24 | * |
shimniok | 0:a6a169de725f | 25 | * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 27 | * @param lat Latitude in degrees |
shimniok | 0:a6a169de725f | 28 | * @param lon Longitude in degrees |
shimniok | 0:a6a169de725f | 29 | * @param eph GPS HDOP |
shimniok | 0:a6a169de725f | 30 | * @param epv GPS VDOP |
shimniok | 0:a6a169de725f | 31 | * @param v GPS ground speed |
shimniok | 0:a6a169de725f | 32 | * @param hdg Compass heading in degrees, 0..360 degrees |
shimniok | 0:a6a169de725f | 33 | * @return length of the message in bytes (excluding serial stream start sign) |
shimniok | 0:a6a169de725f | 34 | */ |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 36 | { |
shimniok | 0:a6a169de725f | 37 | uint16_t i = 0; |
shimniok | 0:a6a169de725f | 38 | msg->msgid = MAVLINK_MSG_ID_GPS_RAW_UGV; |
shimniok | 0:a6a169de725f | 39 | |
shimniok | 0:a6a169de725f | 40 | i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 42 | i += put_double_by_index(lat, i, msg->payload); // Latitude in degrees |
shimniok | 0:a6a169de725f | 43 | i += put_double_by_index(lon, i, msg->payload); // Longitude in degrees |
shimniok | 0:a6a169de725f | 44 | i += put_float_by_index(eph, i, msg->payload); // GPS HDOP |
shimniok | 0:a6a169de725f | 45 | i += put_float_by_index(epv, i, msg->payload); // GPS VDOP |
shimniok | 0:a6a169de725f | 46 | i += put_float_by_index(v, i, msg->payload); // GPS ground speed |
shimniok | 0:a6a169de725f | 47 | i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees |
shimniok | 0:a6a169de725f | 48 | |
shimniok | 0:a6a169de725f | 49 | return mavlink_finalize_message(msg, system_id, component_id, i); |
shimniok | 0:a6a169de725f | 50 | } |
shimniok | 0:a6a169de725f | 51 | |
shimniok | 0:a6a169de725f | 52 | /** |
shimniok | 0:a6a169de725f | 53 | * @brief Pack a gps_raw message |
shimniok | 0:a6a169de725f | 54 | * @param system_id ID of this system |
shimniok | 0:a6a169de725f | 55 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:a6a169de725f | 56 | * @param chan The MAVLink channel this message was sent over |
shimniok | 0:a6a169de725f | 57 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:a6a169de725f | 58 | * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 60 | * @param lat Latitude in degrees |
shimniok | 0:a6a169de725f | 61 | * @param lon Longitude in degrees |
shimniok | 0:a6a169de725f | 62 | * @param eph GPS HDOP |
shimniok | 0:a6a169de725f | 63 | * @param epv GPS VDOP |
shimniok | 0:a6a169de725f | 64 | * @param v GPS ground speed |
shimniok | 0:a6a169de725f | 65 | * @param hdg Compass heading in degrees, 0..360 degrees |
shimniok | 0:a6a169de725f | 66 | * @return length of the message in bytes (excluding serial stream start sign) |
shimniok | 0:a6a169de725f | 67 | */ |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 69 | { |
shimniok | 0:a6a169de725f | 70 | uint16_t i = 0; |
shimniok | 0:a6a169de725f | 71 | msg->msgid = MAVLINK_MSG_ID_GPS_RAW_UGV; |
shimniok | 0:a6a169de725f | 72 | |
shimniok | 0:a6a169de725f | 73 | i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 75 | i += put_double_by_index(lat, i, msg->payload); // Latitude in degrees |
shimniok | 0:a6a169de725f | 76 | i += put_double_by_index(lon, i, msg->payload); // Longitude in degrees |
shimniok | 0:a6a169de725f | 77 | i += put_float_by_index(eph, i, msg->payload); // GPS HDOP |
shimniok | 0:a6a169de725f | 78 | i += put_float_by_index(epv, i, msg->payload); // GPS VDOP |
shimniok | 0:a6a169de725f | 79 | i += put_float_by_index(v, i, msg->payload); // GPS ground speed |
shimniok | 0:a6a169de725f | 80 | i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees |
shimniok | 0:a6a169de725f | 81 | |
shimniok | 0:a6a169de725f | 82 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); |
shimniok | 0:a6a169de725f | 83 | } |
shimniok | 0:a6a169de725f | 84 | |
shimniok | 0:a6a169de725f | 85 | /** |
shimniok | 0:a6a169de725f | 86 | * @brief Encode a gps_raw struct into a message |
shimniok | 0:a6a169de725f | 87 | * |
shimniok | 0:a6a169de725f | 88 | * @param system_id ID of this system |
shimniok | 0:a6a169de725f | 89 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:a6a169de725f | 90 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:a6a169de725f | 91 | * @param gps_raw C-struct to read the message contents from |
shimniok | 0:a6a169de725f | 92 | */ |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 94 | { |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 96 | } |
shimniok | 0:a6a169de725f | 97 | |
shimniok | 0:a6a169de725f | 98 | /** |
shimniok | 0:a6a169de725f | 99 | * @brief Send a gps_raw message |
shimniok | 0:a6a169de725f | 100 | * @param chan MAVLink channel to send the message |
shimniok | 0:a6a169de725f | 101 | * |
shimniok | 0:a6a169de725f | 102 | * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 104 | * @param lat Latitude in degrees |
shimniok | 0:a6a169de725f | 105 | * @param lon Longitude in degrees |
shimniok | 0:a6a169de725f | 106 | * @param eph GPS HDOP |
shimniok | 0:a6a169de725f | 107 | * @param epv GPS VDOP |
shimniok | 0:a6a169de725f | 108 | * @param v GPS ground speed |
shimniok | 0:a6a169de725f | 109 | * @param hdg Compass heading in degrees, 0..360 degrees |
shimniok | 0:a6a169de725f | 110 | */ |
shimniok | 0:a6a169de725f | 111 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
shimniok | 0:a6a169de725f | 112 | |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 114 | { |
shimniok | 0:a6a169de725f | 115 | mavlink_message_t msg; |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 117 | mavlink_send_uart(chan, &msg); |
shimniok | 0:a6a169de725f | 118 | } |
shimniok | 0:a6a169de725f | 119 | |
shimniok | 0:a6a169de725f | 120 | #endif |
shimniok | 0:a6a169de725f | 121 | // MESSAGE GPS_RAW UNPACKING |
shimniok | 0:a6a169de725f | 122 | |
shimniok | 0:a6a169de725f | 123 | /** |
shimniok | 0:a6a169de725f | 124 | * @brief Get field usec from gps_raw message |
shimniok | 0:a6a169de725f | 125 | * |
shimniok | 0:a6a169de725f | 126 | * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:a6a169de725f | 127 | */ |
shimniok | 0:a6a169de725f | 128 | static inline uint64_t mavlink_msg_gps_raw_ugv_get_usec(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 129 | { |
shimniok | 0:a6a169de725f | 130 | generic_64bit r; |
shimniok | 0:a6a169de725f | 131 | r.b[7] = (msg->payload)[0]; |
shimniok | 0:a6a169de725f | 132 | r.b[6] = (msg->payload)[1]; |
shimniok | 0:a6a169de725f | 133 | r.b[5] = (msg->payload)[2]; |
shimniok | 0:a6a169de725f | 134 | r.b[4] = (msg->payload)[3]; |
shimniok | 0:a6a169de725f | 135 | r.b[3] = (msg->payload)[4]; |
shimniok | 0:a6a169de725f | 136 | r.b[2] = (msg->payload)[5]; |
shimniok | 0:a6a169de725f | 137 | r.b[1] = (msg->payload)[6]; |
shimniok | 0:a6a169de725f | 138 | r.b[0] = (msg->payload)[7]; |
shimniok | 0:a6a169de725f | 139 | return (uint64_t)r.ll; |
shimniok | 0:a6a169de725f | 140 | } |
shimniok | 0:a6a169de725f | 141 | |
shimniok | 0:a6a169de725f | 142 | /** |
shimniok | 0:a6a169de725f | 143 | * @brief Get field fix_type from gps_raw message |
shimniok | 0:a6a169de725f | 144 | * |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 146 | */ |
shimniok | 0:a6a169de725f | 147 | static inline uint8_t mavlink_msg_gps_raw_ugv_get_fix_type(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 148 | { |
shimniok | 0:a6a169de725f | 149 | return (uint8_t)(msg->payload+sizeof(uint64_t))[0]; |
shimniok | 0:a6a169de725f | 150 | } |
shimniok | 0:a6a169de725f | 151 | |
shimniok | 0:a6a169de725f | 152 | /** |
shimniok | 0:a6a169de725f | 153 | * @brief Get field lat from gps_raw message |
shimniok | 0:a6a169de725f | 154 | * |
shimniok | 0:a6a169de725f | 155 | * @return Latitude in degrees |
shimniok | 0:a6a169de725f | 156 | */ |
shimniok | 0:a6a169de725f | 157 | static inline double mavlink_msg_gps_raw_ugv_get_lat(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 158 | { |
shimniok | 0:a6a169de725f | 159 | generic_64bit r; |
shimniok | 0:a6a169de725f | 160 | r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0]; |
shimniok | 0:a6a169de725f | 161 | r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1]; |
shimniok | 0:a6a169de725f | 162 | r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2]; |
shimniok | 0:a6a169de725f | 163 | r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3]; |
shimniok | 0:a6a169de725f | 164 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[4]; |
shimniok | 0:a6a169de725f | 165 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[5]; |
shimniok | 0:a6a169de725f | 166 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[6]; |
shimniok | 0:a6a169de725f | 167 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[7]; |
shimniok | 0:a6a169de725f | 168 | return (double)r.d; |
shimniok | 0:a6a169de725f | 169 | } |
shimniok | 0:a6a169de725f | 170 | |
shimniok | 0:a6a169de725f | 171 | /** |
shimniok | 0:a6a169de725f | 172 | * @brief Get field lon from gps_raw message |
shimniok | 0:a6a169de725f | 173 | * |
shimniok | 0:a6a169de725f | 174 | * @return Longitude in degrees |
shimniok | 0:a6a169de725f | 175 | */ |
shimniok | 0:a6a169de725f | 176 | static inline double mavlink_msg_gps_raw_ugv_get_lon(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 177 | { |
shimniok | 0:a6a169de725f | 178 | generic_64bit r; |
shimniok | 0:a6a169de725f | 179 | r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[0]; |
shimniok | 0:a6a169de725f | 180 | r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[1]; |
shimniok | 0:a6a169de725f | 181 | r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[2]; |
shimniok | 0:a6a169de725f | 182 | r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[3]; |
shimniok | 0:a6a169de725f | 183 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[4]; |
shimniok | 0:a6a169de725f | 184 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[5]; |
shimniok | 0:a6a169de725f | 185 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[6]; |
shimniok | 0:a6a169de725f | 186 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[7]; |
shimniok | 0:a6a169de725f | 187 | return (double)r.d; |
shimniok | 0:a6a169de725f | 188 | } |
shimniok | 0:a6a169de725f | 189 | |
shimniok | 0:a6a169de725f | 190 | /** |
shimniok | 0:a6a169de725f | 191 | * @brief Get field eph from gps_raw message |
shimniok | 0:a6a169de725f | 192 | * |
shimniok | 0:a6a169de725f | 193 | * @return GPS HDOP |
shimniok | 0:a6a169de725f | 194 | */ |
shimniok | 0:a6a169de725f | 195 | static inline float mavlink_msg_gps_raw_ugv_get_eph(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 196 | { |
shimniok | 0:a6a169de725f | 197 | generic_32bit r; |
shimniok | 0:a6a169de725f | 198 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[0]; |
shimniok | 0:a6a169de725f | 199 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[1]; |
shimniok | 0:a6a169de725f | 200 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[2]; |
shimniok | 0:a6a169de725f | 201 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[3]; |
shimniok | 0:a6a169de725f | 202 | return (float)r.f; |
shimniok | 0:a6a169de725f | 203 | } |
shimniok | 0:a6a169de725f | 204 | |
shimniok | 0:a6a169de725f | 205 | /** |
shimniok | 0:a6a169de725f | 206 | * @brief Get field epv from gps_raw message |
shimniok | 0:a6a169de725f | 207 | * |
shimniok | 0:a6a169de725f | 208 | * @return GPS VDOP |
shimniok | 0:a6a169de725f | 209 | */ |
shimniok | 0:a6a169de725f | 210 | static inline float mavlink_msg_gps_raw_ugv_get_epv(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 211 | { |
shimniok | 0:a6a169de725f | 212 | generic_32bit r; |
shimniok | 0:a6a169de725f | 213 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[0]; |
shimniok | 0:a6a169de725f | 214 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[1]; |
shimniok | 0:a6a169de725f | 215 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[2]; |
shimniok | 0:a6a169de725f | 216 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[3]; |
shimniok | 0:a6a169de725f | 217 | return (float)r.f; |
shimniok | 0:a6a169de725f | 218 | } |
shimniok | 0:a6a169de725f | 219 | |
shimniok | 0:a6a169de725f | 220 | /** |
shimniok | 0:a6a169de725f | 221 | * @brief Get field v from gps_raw message |
shimniok | 0:a6a169de725f | 222 | * |
shimniok | 0:a6a169de725f | 223 | * @return GPS ground speed |
shimniok | 0:a6a169de725f | 224 | */ |
shimniok | 0:a6a169de725f | 225 | static inline float mavlink_msg_gps_raw_ugv_get_v(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 226 | { |
shimniok | 0:a6a169de725f | 227 | generic_32bit r; |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 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:a6a169de725f | 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:a6a169de725f | 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:a6a169de725f | 232 | return (float)r.f; |
shimniok | 0:a6a169de725f | 233 | } |
shimniok | 0:a6a169de725f | 234 | |
shimniok | 0:a6a169de725f | 235 | /** |
shimniok | 0:a6a169de725f | 236 | * @brief Get field hdg from gps_raw message |
shimniok | 0:a6a169de725f | 237 | * |
shimniok | 0:a6a169de725f | 238 | * @return Compass heading in degrees, 0..360 degrees |
shimniok | 0:a6a169de725f | 239 | */ |
shimniok | 0:a6a169de725f | 240 | static inline float mavlink_msg_gps_raw_ugv_get_hdg(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 241 | { |
shimniok | 0:a6a169de725f | 242 | generic_32bit r; |
shimniok | 0:a6a169de725f | 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:a6a169de725f | 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:a6a169de725f | 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:a6a169de725f | 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:a6a169de725f | 247 | return (float)r.f; |
shimniok | 0:a6a169de725f | 248 | } |
shimniok | 0:a6a169de725f | 249 | |
shimniok | 0:a6a169de725f | 250 | /** |
shimniok | 0:a6a169de725f | 251 | * @brief Decode a gps_raw message into a struct |
shimniok | 0:a6a169de725f | 252 | * |
shimniok | 0:a6a169de725f | 253 | * @param msg The message to decode |
shimniok | 0:a6a169de725f | 254 | * @param gps_raw C-struct to decode the message contents into |
shimniok | 0:a6a169de725f | 255 | */ |
shimniok | 0:a6a169de725f | 256 | static inline void mavlink_msg_gps_raw_ugv_decode(const mavlink_message_t* msg, mavlink_gps_raw_ugv_t* gps_raw) |
shimniok | 0:a6a169de725f | 257 | { |
shimniok | 0:a6a169de725f | 258 | gps_raw->usec = mavlink_msg_gps_raw_ugv_get_usec(msg); |
shimniok | 0:a6a169de725f | 259 | gps_raw->fix_type = mavlink_msg_gps_raw_ugv_get_fix_type(msg); |
shimniok | 0:a6a169de725f | 260 | gps_raw->lat = mavlink_msg_gps_raw_ugv_get_lat(msg); |
shimniok | 0:a6a169de725f | 261 | gps_raw->lon = mavlink_msg_gps_raw_ugv_get_lon(msg); |
shimniok | 0:a6a169de725f | 262 | gps_raw->eph = mavlink_msg_gps_raw_ugv_get_eph(msg); |
shimniok | 0:a6a169de725f | 263 | gps_raw->epv = mavlink_msg_gps_raw_ugv_get_epv(msg); |
shimniok | 0:a6a169de725f | 264 | gps_raw->v = mavlink_msg_gps_raw_ugv_get_v(msg); |
shimniok | 0:a6a169de725f | 265 | gps_raw->hdg = mavlink_msg_gps_raw_ugv_get_hdg(msg); |
shimniok | 0:a6a169de725f | 266 | } |