Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.
Dependencies: Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo
MAVlink/include/common/mavlink_msg_gps_raw.h@0:826c6171fc1b, 2012-06-20 (annotated)
- Committer:
- shimniok
- Date:
- Wed Jun 20 14:57:48 2012 +0000
- Revision:
- 0:826c6171fc1b
Updated documentation
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
shimniok | 0:826c6171fc1b | 1 | // MESSAGE GPS_RAW PACKING |
shimniok | 0:826c6171fc1b | 2 | |
shimniok | 0:826c6171fc1b | 3 | #define MAVLINK_MSG_ID_GPS_RAW 32 |
shimniok | 0:826c6171fc1b | 4 | |
shimniok | 0:826c6171fc1b | 5 | typedef struct __mavlink_gps_raw_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 | float lat; ///< Latitude in degrees |
shimniok | 0:826c6171fc1b | 10 | float lon; ///< Longitude in degrees |
shimniok | 0:826c6171fc1b | 11 | float alt; ///< Altitude in meters |
shimniok | 0:826c6171fc1b | 12 | float eph; ///< GPS HDOP |
shimniok | 0:826c6171fc1b | 13 | float epv; ///< GPS VDOP |
shimniok | 0:826c6171fc1b | 14 | float v; ///< GPS ground speed |
shimniok | 0:826c6171fc1b | 15 | float hdg; ///< Compass heading in degrees, 0..360 degrees |
shimniok | 0:826c6171fc1b | 16 | |
shimniok | 0:826c6171fc1b | 17 | } mavlink_gps_raw_t; |
shimniok | 0:826c6171fc1b | 18 | |
shimniok | 0:826c6171fc1b | 19 | |
shimniok | 0:826c6171fc1b | 20 | |
shimniok | 0:826c6171fc1b | 21 | /** |
shimniok | 0:826c6171fc1b | 22 | * @brief Pack a gps_raw message |
shimniok | 0:826c6171fc1b | 23 | * @param system_id ID of this system |
shimniok | 0:826c6171fc1b | 24 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:826c6171fc1b | 25 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:826c6171fc1b | 26 | * |
shimniok | 0:826c6171fc1b | 27 | * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:826c6171fc1b | 28 | * @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 | 29 | * @param lat Latitude in degrees |
shimniok | 0:826c6171fc1b | 30 | * @param lon Longitude in degrees |
shimniok | 0:826c6171fc1b | 31 | * @param alt Altitude in meters |
shimniok | 0:826c6171fc1b | 32 | * @param eph GPS HDOP |
shimniok | 0:826c6171fc1b | 33 | * @param epv GPS VDOP |
shimniok | 0:826c6171fc1b | 34 | * @param v GPS ground speed |
shimniok | 0:826c6171fc1b | 35 | * @param hdg Compass heading in degrees, 0..360 degrees |
shimniok | 0:826c6171fc1b | 36 | * @return length of the message in bytes (excluding serial stream start sign) |
shimniok | 0:826c6171fc1b | 37 | */ |
shimniok | 0:826c6171fc1b | 38 | static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg) |
shimniok | 0:826c6171fc1b | 39 | { |
shimniok | 0:826c6171fc1b | 40 | uint16_t i = 0; |
shimniok | 0:826c6171fc1b | 41 | msg->msgid = MAVLINK_MSG_ID_GPS_RAW; |
shimniok | 0:826c6171fc1b | 42 | |
shimniok | 0:826c6171fc1b | 43 | i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:826c6171fc1b | 44 | 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 | 45 | i += put_float_by_index(lat, i, msg->payload); // Latitude in degrees |
shimniok | 0:826c6171fc1b | 46 | i += put_float_by_index(lon, i, msg->payload); // Longitude in degrees |
shimniok | 0:826c6171fc1b | 47 | i += put_float_by_index(alt, i, msg->payload); // Altitude in meters |
shimniok | 0:826c6171fc1b | 48 | i += put_float_by_index(eph, i, msg->payload); // GPS HDOP |
shimniok | 0:826c6171fc1b | 49 | i += put_float_by_index(epv, i, msg->payload); // GPS VDOP |
shimniok | 0:826c6171fc1b | 50 | i += put_float_by_index(v, i, msg->payload); // GPS ground speed |
shimniok | 0:826c6171fc1b | 51 | i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees |
shimniok | 0:826c6171fc1b | 52 | |
shimniok | 0:826c6171fc1b | 53 | return mavlink_finalize_message(msg, system_id, component_id, i); |
shimniok | 0:826c6171fc1b | 54 | } |
shimniok | 0:826c6171fc1b | 55 | |
shimniok | 0:826c6171fc1b | 56 | /** |
shimniok | 0:826c6171fc1b | 57 | * @brief Pack a gps_raw message |
shimniok | 0:826c6171fc1b | 58 | * @param system_id ID of this system |
shimniok | 0:826c6171fc1b | 59 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:826c6171fc1b | 60 | * @param chan The MAVLink channel this message was sent over |
shimniok | 0:826c6171fc1b | 61 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:826c6171fc1b | 62 | * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:826c6171fc1b | 63 | * @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 | 64 | * @param lat Latitude in degrees |
shimniok | 0:826c6171fc1b | 65 | * @param lon Longitude in degrees |
shimniok | 0:826c6171fc1b | 66 | * @param alt Altitude in meters |
shimniok | 0:826c6171fc1b | 67 | * @param eph GPS HDOP |
shimniok | 0:826c6171fc1b | 68 | * @param epv GPS VDOP |
shimniok | 0:826c6171fc1b | 69 | * @param v GPS ground speed |
shimniok | 0:826c6171fc1b | 70 | * @param hdg Compass heading in degrees, 0..360 degrees |
shimniok | 0:826c6171fc1b | 71 | * @return length of the message in bytes (excluding serial stream start sign) |
shimniok | 0:826c6171fc1b | 72 | */ |
shimniok | 0:826c6171fc1b | 73 | static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg) |
shimniok | 0:826c6171fc1b | 74 | { |
shimniok | 0:826c6171fc1b | 75 | uint16_t i = 0; |
shimniok | 0:826c6171fc1b | 76 | msg->msgid = MAVLINK_MSG_ID_GPS_RAW; |
shimniok | 0:826c6171fc1b | 77 | |
shimniok | 0:826c6171fc1b | 78 | i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:826c6171fc1b | 79 | 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 | 80 | i += put_float_by_index(lat, i, msg->payload); // Latitude in degrees |
shimniok | 0:826c6171fc1b | 81 | i += put_float_by_index(lon, i, msg->payload); // Longitude in degrees |
shimniok | 0:826c6171fc1b | 82 | i += put_float_by_index(alt, i, msg->payload); // Altitude in meters |
shimniok | 0:826c6171fc1b | 83 | i += put_float_by_index(eph, i, msg->payload); // GPS HDOP |
shimniok | 0:826c6171fc1b | 84 | i += put_float_by_index(epv, i, msg->payload); // GPS VDOP |
shimniok | 0:826c6171fc1b | 85 | i += put_float_by_index(v, i, msg->payload); // GPS ground speed |
shimniok | 0:826c6171fc1b | 86 | i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees |
shimniok | 0:826c6171fc1b | 87 | |
shimniok | 0:826c6171fc1b | 88 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); |
shimniok | 0:826c6171fc1b | 89 | } |
shimniok | 0:826c6171fc1b | 90 | |
shimniok | 0:826c6171fc1b | 91 | /** |
shimniok | 0:826c6171fc1b | 92 | * @brief Encode a gps_raw struct into a message |
shimniok | 0:826c6171fc1b | 93 | * |
shimniok | 0:826c6171fc1b | 94 | * @param system_id ID of this system |
shimniok | 0:826c6171fc1b | 95 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:826c6171fc1b | 96 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:826c6171fc1b | 97 | * @param gps_raw C-struct to read the message contents from |
shimniok | 0:826c6171fc1b | 98 | */ |
shimniok | 0:826c6171fc1b | 99 | static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_t* gps_raw) |
shimniok | 0:826c6171fc1b | 100 | { |
shimniok | 0:826c6171fc1b | 101 | return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg); |
shimniok | 0:826c6171fc1b | 102 | } |
shimniok | 0:826c6171fc1b | 103 | |
shimniok | 0:826c6171fc1b | 104 | /** |
shimniok | 0:826c6171fc1b | 105 | * @brief Send a gps_raw message |
shimniok | 0:826c6171fc1b | 106 | * @param chan MAVLink channel to send the message |
shimniok | 0:826c6171fc1b | 107 | * |
shimniok | 0:826c6171fc1b | 108 | * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:826c6171fc1b | 109 | * @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 | 110 | * @param lat Latitude in degrees |
shimniok | 0:826c6171fc1b | 111 | * @param lon Longitude in degrees |
shimniok | 0:826c6171fc1b | 112 | * @param alt Altitude in meters |
shimniok | 0:826c6171fc1b | 113 | * @param eph GPS HDOP |
shimniok | 0:826c6171fc1b | 114 | * @param epv GPS VDOP |
shimniok | 0:826c6171fc1b | 115 | * @param v GPS ground speed |
shimniok | 0:826c6171fc1b | 116 | * @param hdg Compass heading in degrees, 0..360 degrees |
shimniok | 0:826c6171fc1b | 117 | */ |
shimniok | 0:826c6171fc1b | 118 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
shimniok | 0:826c6171fc1b | 119 | |
shimniok | 0:826c6171fc1b | 120 | static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg) |
shimniok | 0:826c6171fc1b | 121 | { |
shimniok | 0:826c6171fc1b | 122 | mavlink_message_t msg; |
shimniok | 0:826c6171fc1b | 123 | mavlink_msg_gps_raw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, fix_type, lat, lon, alt, eph, epv, v, hdg); |
shimniok | 0:826c6171fc1b | 124 | mavlink_send_uart(chan, &msg); |
shimniok | 0:826c6171fc1b | 125 | } |
shimniok | 0:826c6171fc1b | 126 | |
shimniok | 0:826c6171fc1b | 127 | #endif |
shimniok | 0:826c6171fc1b | 128 | // MESSAGE GPS_RAW UNPACKING |
shimniok | 0:826c6171fc1b | 129 | |
shimniok | 0:826c6171fc1b | 130 | /** |
shimniok | 0:826c6171fc1b | 131 | * @brief Get field usec from gps_raw message |
shimniok | 0:826c6171fc1b | 132 | * |
shimniok | 0:826c6171fc1b | 133 | * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:826c6171fc1b | 134 | */ |
shimniok | 0:826c6171fc1b | 135 | static inline uint64_t mavlink_msg_gps_raw_get_usec(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 136 | { |
shimniok | 0:826c6171fc1b | 137 | generic_64bit r; |
shimniok | 0:826c6171fc1b | 138 | r.b[7] = (msg->payload)[0]; |
shimniok | 0:826c6171fc1b | 139 | r.b[6] = (msg->payload)[1]; |
shimniok | 0:826c6171fc1b | 140 | r.b[5] = (msg->payload)[2]; |
shimniok | 0:826c6171fc1b | 141 | r.b[4] = (msg->payload)[3]; |
shimniok | 0:826c6171fc1b | 142 | r.b[3] = (msg->payload)[4]; |
shimniok | 0:826c6171fc1b | 143 | r.b[2] = (msg->payload)[5]; |
shimniok | 0:826c6171fc1b | 144 | r.b[1] = (msg->payload)[6]; |
shimniok | 0:826c6171fc1b | 145 | r.b[0] = (msg->payload)[7]; |
shimniok | 0:826c6171fc1b | 146 | return (uint64_t)r.ll; |
shimniok | 0:826c6171fc1b | 147 | } |
shimniok | 0:826c6171fc1b | 148 | |
shimniok | 0:826c6171fc1b | 149 | /** |
shimniok | 0:826c6171fc1b | 150 | * @brief Get field fix_type from gps_raw message |
shimniok | 0:826c6171fc1b | 151 | * |
shimniok | 0:826c6171fc1b | 152 | * @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 | 153 | */ |
shimniok | 0:826c6171fc1b | 154 | static inline uint8_t mavlink_msg_gps_raw_get_fix_type(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 155 | { |
shimniok | 0:826c6171fc1b | 156 | return (uint8_t)(msg->payload+sizeof(uint64_t))[0]; |
shimniok | 0:826c6171fc1b | 157 | } |
shimniok | 0:826c6171fc1b | 158 | |
shimniok | 0:826c6171fc1b | 159 | /** |
shimniok | 0:826c6171fc1b | 160 | * @brief Get field lat from gps_raw message |
shimniok | 0:826c6171fc1b | 161 | * |
shimniok | 0:826c6171fc1b | 162 | * @return Latitude in degrees |
shimniok | 0:826c6171fc1b | 163 | */ |
shimniok | 0:826c6171fc1b | 164 | static inline float mavlink_msg_gps_raw_get_lat(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 165 | { |
shimniok | 0:826c6171fc1b | 166 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 167 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0]; |
shimniok | 0:826c6171fc1b | 168 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1]; |
shimniok | 0:826c6171fc1b | 169 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2]; |
shimniok | 0:826c6171fc1b | 170 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3]; |
shimniok | 0:826c6171fc1b | 171 | return (float)r.f; |
shimniok | 0:826c6171fc1b | 172 | } |
shimniok | 0:826c6171fc1b | 173 | |
shimniok | 0:826c6171fc1b | 174 | /** |
shimniok | 0:826c6171fc1b | 175 | * @brief Get field lon from gps_raw message |
shimniok | 0:826c6171fc1b | 176 | * |
shimniok | 0:826c6171fc1b | 177 | * @return Longitude in degrees |
shimniok | 0:826c6171fc1b | 178 | */ |
shimniok | 0:826c6171fc1b | 179 | static inline float mavlink_msg_gps_raw_get_lon(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 180 | { |
shimniok | 0:826c6171fc1b | 181 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 182 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[0]; |
shimniok | 0:826c6171fc1b | 183 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[1]; |
shimniok | 0:826c6171fc1b | 184 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[2]; |
shimniok | 0:826c6171fc1b | 185 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[3]; |
shimniok | 0:826c6171fc1b | 186 | return (float)r.f; |
shimniok | 0:826c6171fc1b | 187 | } |
shimniok | 0:826c6171fc1b | 188 | |
shimniok | 0:826c6171fc1b | 189 | /** |
shimniok | 0:826c6171fc1b | 190 | * @brief Get field alt from gps_raw message |
shimniok | 0:826c6171fc1b | 191 | * |
shimniok | 0:826c6171fc1b | 192 | * @return Altitude in meters |
shimniok | 0:826c6171fc1b | 193 | */ |
shimniok | 0:826c6171fc1b | 194 | static inline float mavlink_msg_gps_raw_get_alt(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 195 | { |
shimniok | 0:826c6171fc1b | 196 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 197 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; |
shimniok | 0:826c6171fc1b | 198 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; |
shimniok | 0:826c6171fc1b | 199 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; |
shimniok | 0:826c6171fc1b | 200 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; |
shimniok | 0:826c6171fc1b | 201 | return (float)r.f; |
shimniok | 0:826c6171fc1b | 202 | } |
shimniok | 0:826c6171fc1b | 203 | |
shimniok | 0:826c6171fc1b | 204 | /** |
shimniok | 0:826c6171fc1b | 205 | * @brief Get field eph from gps_raw message |
shimniok | 0:826c6171fc1b | 206 | * |
shimniok | 0:826c6171fc1b | 207 | * @return GPS HDOP |
shimniok | 0:826c6171fc1b | 208 | */ |
shimniok | 0:826c6171fc1b | 209 | static inline float mavlink_msg_gps_raw_get_eph(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 210 | { |
shimniok | 0:826c6171fc1b | 211 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 212 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; |
shimniok | 0:826c6171fc1b | 213 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; |
shimniok | 0:826c6171fc1b | 214 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; |
shimniok | 0:826c6171fc1b | 215 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; |
shimniok | 0:826c6171fc1b | 216 | return (float)r.f; |
shimniok | 0:826c6171fc1b | 217 | } |
shimniok | 0:826c6171fc1b | 218 | |
shimniok | 0:826c6171fc1b | 219 | /** |
shimniok | 0:826c6171fc1b | 220 | * @brief Get field epv from gps_raw message |
shimniok | 0:826c6171fc1b | 221 | * |
shimniok | 0:826c6171fc1b | 222 | * @return GPS VDOP |
shimniok | 0:826c6171fc1b | 223 | */ |
shimniok | 0:826c6171fc1b | 224 | static inline float mavlink_msg_gps_raw_get_epv(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 225 | { |
shimniok | 0:826c6171fc1b | 226 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 227 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; |
shimniok | 0:826c6171fc1b | 228 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; |
shimniok | 0:826c6171fc1b | 229 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; |
shimniok | 0:826c6171fc1b | 230 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; |
shimniok | 0:826c6171fc1b | 231 | return (float)r.f; |
shimniok | 0:826c6171fc1b | 232 | } |
shimniok | 0:826c6171fc1b | 233 | |
shimniok | 0:826c6171fc1b | 234 | /** |
shimniok | 0:826c6171fc1b | 235 | * @brief Get field v from gps_raw message |
shimniok | 0:826c6171fc1b | 236 | * |
shimniok | 0:826c6171fc1b | 237 | * @return GPS ground speed |
shimniok | 0:826c6171fc1b | 238 | */ |
shimniok | 0:826c6171fc1b | 239 | static inline float mavlink_msg_gps_raw_get_v(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 240 | { |
shimniok | 0:826c6171fc1b | 241 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 242 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; |
shimniok | 0:826c6171fc1b | 243 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; |
shimniok | 0:826c6171fc1b | 244 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; |
shimniok | 0:826c6171fc1b | 245 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; |
shimniok | 0:826c6171fc1b | 246 | return (float)r.f; |
shimniok | 0:826c6171fc1b | 247 | } |
shimniok | 0:826c6171fc1b | 248 | |
shimniok | 0:826c6171fc1b | 249 | /** |
shimniok | 0:826c6171fc1b | 250 | * @brief Get field hdg from gps_raw message |
shimniok | 0:826c6171fc1b | 251 | * |
shimniok | 0:826c6171fc1b | 252 | * @return Compass heading in degrees, 0..360 degrees |
shimniok | 0:826c6171fc1b | 253 | */ |
shimniok | 0:826c6171fc1b | 254 | static inline float mavlink_msg_gps_raw_get_hdg(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 255 | { |
shimniok | 0:826c6171fc1b | 256 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 257 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; |
shimniok | 0:826c6171fc1b | 258 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; |
shimniok | 0:826c6171fc1b | 259 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; |
shimniok | 0:826c6171fc1b | 260 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; |
shimniok | 0:826c6171fc1b | 261 | return (float)r.f; |
shimniok | 0:826c6171fc1b | 262 | } |
shimniok | 0:826c6171fc1b | 263 | |
shimniok | 0:826c6171fc1b | 264 | /** |
shimniok | 0:826c6171fc1b | 265 | * @brief Decode a gps_raw message into a struct |
shimniok | 0:826c6171fc1b | 266 | * |
shimniok | 0:826c6171fc1b | 267 | * @param msg The message to decode |
shimniok | 0:826c6171fc1b | 268 | * @param gps_raw C-struct to decode the message contents into |
shimniok | 0:826c6171fc1b | 269 | */ |
shimniok | 0:826c6171fc1b | 270 | static inline void mavlink_msg_gps_raw_decode(const mavlink_message_t* msg, mavlink_gps_raw_t* gps_raw) |
shimniok | 0:826c6171fc1b | 271 | { |
shimniok | 0:826c6171fc1b | 272 | gps_raw->usec = mavlink_msg_gps_raw_get_usec(msg); |
shimniok | 0:826c6171fc1b | 273 | gps_raw->fix_type = mavlink_msg_gps_raw_get_fix_type(msg); |
shimniok | 0:826c6171fc1b | 274 | gps_raw->lat = mavlink_msg_gps_raw_get_lat(msg); |
shimniok | 0:826c6171fc1b | 275 | gps_raw->lon = mavlink_msg_gps_raw_get_lon(msg); |
shimniok | 0:826c6171fc1b | 276 | gps_raw->alt = mavlink_msg_gps_raw_get_alt(msg); |
shimniok | 0:826c6171fc1b | 277 | gps_raw->eph = mavlink_msg_gps_raw_get_eph(msg); |
shimniok | 0:826c6171fc1b | 278 | gps_raw->epv = mavlink_msg_gps_raw_get_epv(msg); |
shimniok | 0:826c6171fc1b | 279 | gps_raw->v = mavlink_msg_gps_raw_get_v(msg); |
shimniok | 0:826c6171fc1b | 280 | gps_raw->hdg = mavlink_msg_gps_raw_get_hdg(msg); |
shimniok | 0:826c6171fc1b | 281 | } |