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_full_state.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 FULL_STATE PACKING |
shimniok | 0:826c6171fc1b | 2 | |
shimniok | 0:826c6171fc1b | 3 | #define MAVLINK_MSG_ID_FULL_STATE 67 |
shimniok | 0:826c6171fc1b | 4 | |
shimniok | 0:826c6171fc1b | 5 | typedef struct __mavlink_full_state_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 | float roll; ///< Roll angle (rad) |
shimniok | 0:826c6171fc1b | 9 | float pitch; ///< Pitch angle (rad) |
shimniok | 0:826c6171fc1b | 10 | float yaw; ///< Yaw angle (rad) |
shimniok | 0:826c6171fc1b | 11 | float rollspeed; ///< Roll angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 12 | float pitchspeed; ///< Pitch angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 13 | float yawspeed; ///< Yaw angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 14 | int32_t lat; ///< Latitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 15 | int32_t lon; ///< Longitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 16 | int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters) |
shimniok | 0:826c6171fc1b | 17 | int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 18 | int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 19 | int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 20 | int16_t xacc; ///< X acceleration (mg) |
shimniok | 0:826c6171fc1b | 21 | int16_t yacc; ///< Y acceleration (mg) |
shimniok | 0:826c6171fc1b | 22 | int16_t zacc; ///< Z acceleration (mg) |
shimniok | 0:826c6171fc1b | 23 | |
shimniok | 0:826c6171fc1b | 24 | } mavlink_full_state_t; |
shimniok | 0:826c6171fc1b | 25 | |
shimniok | 0:826c6171fc1b | 26 | |
shimniok | 0:826c6171fc1b | 27 | |
shimniok | 0:826c6171fc1b | 28 | /** |
shimniok | 0:826c6171fc1b | 29 | * @brief Pack a full_state message |
shimniok | 0:826c6171fc1b | 30 | * @param system_id ID of this system |
shimniok | 0:826c6171fc1b | 31 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:826c6171fc1b | 32 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:826c6171fc1b | 33 | * |
shimniok | 0:826c6171fc1b | 34 | * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:826c6171fc1b | 35 | * @param roll Roll angle (rad) |
shimniok | 0:826c6171fc1b | 36 | * @param pitch Pitch angle (rad) |
shimniok | 0:826c6171fc1b | 37 | * @param yaw Yaw angle (rad) |
shimniok | 0:826c6171fc1b | 38 | * @param rollspeed Roll angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 39 | * @param pitchspeed Pitch angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 40 | * @param yawspeed Yaw angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 41 | * @param lat Latitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 42 | * @param lon Longitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 43 | * @param alt Altitude in meters, expressed as * 1000 (millimeters) |
shimniok | 0:826c6171fc1b | 44 | * @param vx Ground X Speed (Latitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 45 | * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 46 | * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 47 | * @param xacc X acceleration (mg) |
shimniok | 0:826c6171fc1b | 48 | * @param yacc Y acceleration (mg) |
shimniok | 0:826c6171fc1b | 49 | * @param zacc Z acceleration (mg) |
shimniok | 0:826c6171fc1b | 50 | * @return length of the message in bytes (excluding serial stream start sign) |
shimniok | 0:826c6171fc1b | 51 | */ |
shimniok | 0:826c6171fc1b | 52 | static inline uint16_t mavlink_msg_full_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) |
shimniok | 0:826c6171fc1b | 53 | { |
shimniok | 0:826c6171fc1b | 54 | uint16_t i = 0; |
shimniok | 0:826c6171fc1b | 55 | msg->msgid = MAVLINK_MSG_ID_FULL_STATE; |
shimniok | 0:826c6171fc1b | 56 | |
shimniok | 0:826c6171fc1b | 57 | i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:826c6171fc1b | 58 | i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad) |
shimniok | 0:826c6171fc1b | 59 | i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad) |
shimniok | 0:826c6171fc1b | 60 | i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad) |
shimniok | 0:826c6171fc1b | 61 | i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 62 | i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 63 | i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 64 | i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 65 | i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 66 | i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters) |
shimniok | 0:826c6171fc1b | 67 | i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 68 | i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 69 | i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 70 | i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg) |
shimniok | 0:826c6171fc1b | 71 | i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg) |
shimniok | 0:826c6171fc1b | 72 | i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg) |
shimniok | 0:826c6171fc1b | 73 | |
shimniok | 0:826c6171fc1b | 74 | return mavlink_finalize_message(msg, system_id, component_id, i); |
shimniok | 0:826c6171fc1b | 75 | } |
shimniok | 0:826c6171fc1b | 76 | |
shimniok | 0:826c6171fc1b | 77 | /** |
shimniok | 0:826c6171fc1b | 78 | * @brief Pack a full_state message |
shimniok | 0:826c6171fc1b | 79 | * @param system_id ID of this system |
shimniok | 0:826c6171fc1b | 80 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:826c6171fc1b | 81 | * @param chan The MAVLink channel this message was sent over |
shimniok | 0:826c6171fc1b | 82 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:826c6171fc1b | 83 | * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:826c6171fc1b | 84 | * @param roll Roll angle (rad) |
shimniok | 0:826c6171fc1b | 85 | * @param pitch Pitch angle (rad) |
shimniok | 0:826c6171fc1b | 86 | * @param yaw Yaw angle (rad) |
shimniok | 0:826c6171fc1b | 87 | * @param rollspeed Roll angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 88 | * @param pitchspeed Pitch angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 89 | * @param yawspeed Yaw angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 90 | * @param lat Latitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 91 | * @param lon Longitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 92 | * @param alt Altitude in meters, expressed as * 1000 (millimeters) |
shimniok | 0:826c6171fc1b | 93 | * @param vx Ground X Speed (Latitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 94 | * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 95 | * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 96 | * @param xacc X acceleration (mg) |
shimniok | 0:826c6171fc1b | 97 | * @param yacc Y acceleration (mg) |
shimniok | 0:826c6171fc1b | 98 | * @param zacc Z acceleration (mg) |
shimniok | 0:826c6171fc1b | 99 | * @return length of the message in bytes (excluding serial stream start sign) |
shimniok | 0:826c6171fc1b | 100 | */ |
shimniok | 0:826c6171fc1b | 101 | static inline uint16_t mavlink_msg_full_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) |
shimniok | 0:826c6171fc1b | 102 | { |
shimniok | 0:826c6171fc1b | 103 | uint16_t i = 0; |
shimniok | 0:826c6171fc1b | 104 | msg->msgid = MAVLINK_MSG_ID_FULL_STATE; |
shimniok | 0:826c6171fc1b | 105 | |
shimniok | 0:826c6171fc1b | 106 | i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:826c6171fc1b | 107 | i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad) |
shimniok | 0:826c6171fc1b | 108 | i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad) |
shimniok | 0:826c6171fc1b | 109 | i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad) |
shimniok | 0:826c6171fc1b | 110 | i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 111 | i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 112 | i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 113 | i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 114 | i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 115 | i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters) |
shimniok | 0:826c6171fc1b | 116 | i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 117 | i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 118 | i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 119 | i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg) |
shimniok | 0:826c6171fc1b | 120 | i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg) |
shimniok | 0:826c6171fc1b | 121 | i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg) |
shimniok | 0:826c6171fc1b | 122 | |
shimniok | 0:826c6171fc1b | 123 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); |
shimniok | 0:826c6171fc1b | 124 | } |
shimniok | 0:826c6171fc1b | 125 | |
shimniok | 0:826c6171fc1b | 126 | /** |
shimniok | 0:826c6171fc1b | 127 | * @brief Encode a full_state struct into a message |
shimniok | 0:826c6171fc1b | 128 | * |
shimniok | 0:826c6171fc1b | 129 | * @param system_id ID of this system |
shimniok | 0:826c6171fc1b | 130 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:826c6171fc1b | 131 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:826c6171fc1b | 132 | * @param full_state C-struct to read the message contents from |
shimniok | 0:826c6171fc1b | 133 | */ |
shimniok | 0:826c6171fc1b | 134 | static inline uint16_t mavlink_msg_full_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_full_state_t* full_state) |
shimniok | 0:826c6171fc1b | 135 | { |
shimniok | 0:826c6171fc1b | 136 | return mavlink_msg_full_state_pack(system_id, component_id, msg, full_state->usec, full_state->roll, full_state->pitch, full_state->yaw, full_state->rollspeed, full_state->pitchspeed, full_state->yawspeed, full_state->lat, full_state->lon, full_state->alt, full_state->vx, full_state->vy, full_state->vz, full_state->xacc, full_state->yacc, full_state->zacc); |
shimniok | 0:826c6171fc1b | 137 | } |
shimniok | 0:826c6171fc1b | 138 | |
shimniok | 0:826c6171fc1b | 139 | /** |
shimniok | 0:826c6171fc1b | 140 | * @brief Send a full_state message |
shimniok | 0:826c6171fc1b | 141 | * @param chan MAVLink channel to send the message |
shimniok | 0:826c6171fc1b | 142 | * |
shimniok | 0:826c6171fc1b | 143 | * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:826c6171fc1b | 144 | * @param roll Roll angle (rad) |
shimniok | 0:826c6171fc1b | 145 | * @param pitch Pitch angle (rad) |
shimniok | 0:826c6171fc1b | 146 | * @param yaw Yaw angle (rad) |
shimniok | 0:826c6171fc1b | 147 | * @param rollspeed Roll angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 148 | * @param pitchspeed Pitch angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 149 | * @param yawspeed Yaw angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 150 | * @param lat Latitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 151 | * @param lon Longitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 152 | * @param alt Altitude in meters, expressed as * 1000 (millimeters) |
shimniok | 0:826c6171fc1b | 153 | * @param vx Ground X Speed (Latitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 154 | * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 155 | * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 156 | * @param xacc X acceleration (mg) |
shimniok | 0:826c6171fc1b | 157 | * @param yacc Y acceleration (mg) |
shimniok | 0:826c6171fc1b | 158 | * @param zacc Z acceleration (mg) |
shimniok | 0:826c6171fc1b | 159 | */ |
shimniok | 0:826c6171fc1b | 160 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
shimniok | 0:826c6171fc1b | 161 | |
shimniok | 0:826c6171fc1b | 162 | static inline void mavlink_msg_full_state_send(mavlink_channel_t chan, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) |
shimniok | 0:826c6171fc1b | 163 | { |
shimniok | 0:826c6171fc1b | 164 | mavlink_message_t msg; |
shimniok | 0:826c6171fc1b | 165 | mavlink_msg_full_state_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc); |
shimniok | 0:826c6171fc1b | 166 | mavlink_send_uart(chan, &msg); |
shimniok | 0:826c6171fc1b | 167 | } |
shimniok | 0:826c6171fc1b | 168 | |
shimniok | 0:826c6171fc1b | 169 | #endif |
shimniok | 0:826c6171fc1b | 170 | // MESSAGE FULL_STATE UNPACKING |
shimniok | 0:826c6171fc1b | 171 | |
shimniok | 0:826c6171fc1b | 172 | /** |
shimniok | 0:826c6171fc1b | 173 | * @brief Get field usec from full_state message |
shimniok | 0:826c6171fc1b | 174 | * |
shimniok | 0:826c6171fc1b | 175 | * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
shimniok | 0:826c6171fc1b | 176 | */ |
shimniok | 0:826c6171fc1b | 177 | static inline uint64_t mavlink_msg_full_state_get_usec(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 178 | { |
shimniok | 0:826c6171fc1b | 179 | generic_64bit r; |
shimniok | 0:826c6171fc1b | 180 | r.b[7] = (msg->payload)[0]; |
shimniok | 0:826c6171fc1b | 181 | r.b[6] = (msg->payload)[1]; |
shimniok | 0:826c6171fc1b | 182 | r.b[5] = (msg->payload)[2]; |
shimniok | 0:826c6171fc1b | 183 | r.b[4] = (msg->payload)[3]; |
shimniok | 0:826c6171fc1b | 184 | r.b[3] = (msg->payload)[4]; |
shimniok | 0:826c6171fc1b | 185 | r.b[2] = (msg->payload)[5]; |
shimniok | 0:826c6171fc1b | 186 | r.b[1] = (msg->payload)[6]; |
shimniok | 0:826c6171fc1b | 187 | r.b[0] = (msg->payload)[7]; |
shimniok | 0:826c6171fc1b | 188 | return (uint64_t)r.ll; |
shimniok | 0:826c6171fc1b | 189 | } |
shimniok | 0:826c6171fc1b | 190 | |
shimniok | 0:826c6171fc1b | 191 | /** |
shimniok | 0:826c6171fc1b | 192 | * @brief Get field roll from full_state message |
shimniok | 0:826c6171fc1b | 193 | * |
shimniok | 0:826c6171fc1b | 194 | * @return Roll angle (rad) |
shimniok | 0:826c6171fc1b | 195 | */ |
shimniok | 0:826c6171fc1b | 196 | static inline float mavlink_msg_full_state_get_roll(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 197 | { |
shimniok | 0:826c6171fc1b | 198 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 199 | r.b[3] = (msg->payload+sizeof(uint64_t))[0]; |
shimniok | 0:826c6171fc1b | 200 | r.b[2] = (msg->payload+sizeof(uint64_t))[1]; |
shimniok | 0:826c6171fc1b | 201 | r.b[1] = (msg->payload+sizeof(uint64_t))[2]; |
shimniok | 0:826c6171fc1b | 202 | r.b[0] = (msg->payload+sizeof(uint64_t))[3]; |
shimniok | 0:826c6171fc1b | 203 | return (float)r.f; |
shimniok | 0:826c6171fc1b | 204 | } |
shimniok | 0:826c6171fc1b | 205 | |
shimniok | 0:826c6171fc1b | 206 | /** |
shimniok | 0:826c6171fc1b | 207 | * @brief Get field pitch from full_state message |
shimniok | 0:826c6171fc1b | 208 | * |
shimniok | 0:826c6171fc1b | 209 | * @return Pitch angle (rad) |
shimniok | 0:826c6171fc1b | 210 | */ |
shimniok | 0:826c6171fc1b | 211 | static inline float mavlink_msg_full_state_get_pitch(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 212 | { |
shimniok | 0:826c6171fc1b | 213 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 214 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0]; |
shimniok | 0:826c6171fc1b | 215 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1]; |
shimniok | 0:826c6171fc1b | 216 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2]; |
shimniok | 0:826c6171fc1b | 217 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3]; |
shimniok | 0:826c6171fc1b | 218 | return (float)r.f; |
shimniok | 0:826c6171fc1b | 219 | } |
shimniok | 0:826c6171fc1b | 220 | |
shimniok | 0:826c6171fc1b | 221 | /** |
shimniok | 0:826c6171fc1b | 222 | * @brief Get field yaw from full_state message |
shimniok | 0:826c6171fc1b | 223 | * |
shimniok | 0:826c6171fc1b | 224 | * @return Yaw angle (rad) |
shimniok | 0:826c6171fc1b | 225 | */ |
shimniok | 0:826c6171fc1b | 226 | static inline float mavlink_msg_full_state_get_yaw(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 227 | { |
shimniok | 0:826c6171fc1b | 228 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 229 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; |
shimniok | 0:826c6171fc1b | 230 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; |
shimniok | 0:826c6171fc1b | 231 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; |
shimniok | 0:826c6171fc1b | 232 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; |
shimniok | 0:826c6171fc1b | 233 | return (float)r.f; |
shimniok | 0:826c6171fc1b | 234 | } |
shimniok | 0:826c6171fc1b | 235 | |
shimniok | 0:826c6171fc1b | 236 | /** |
shimniok | 0:826c6171fc1b | 237 | * @brief Get field rollspeed from full_state message |
shimniok | 0:826c6171fc1b | 238 | * |
shimniok | 0:826c6171fc1b | 239 | * @return Roll angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 240 | */ |
shimniok | 0:826c6171fc1b | 241 | static inline float mavlink_msg_full_state_get_rollspeed(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 242 | { |
shimniok | 0:826c6171fc1b | 243 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 244 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; |
shimniok | 0:826c6171fc1b | 245 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; |
shimniok | 0:826c6171fc1b | 246 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; |
shimniok | 0:826c6171fc1b | 247 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; |
shimniok | 0:826c6171fc1b | 248 | return (float)r.f; |
shimniok | 0:826c6171fc1b | 249 | } |
shimniok | 0:826c6171fc1b | 250 | |
shimniok | 0:826c6171fc1b | 251 | /** |
shimniok | 0:826c6171fc1b | 252 | * @brief Get field pitchspeed from full_state message |
shimniok | 0:826c6171fc1b | 253 | * |
shimniok | 0:826c6171fc1b | 254 | * @return Pitch angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 255 | */ |
shimniok | 0:826c6171fc1b | 256 | static inline float mavlink_msg_full_state_get_pitchspeed(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 257 | { |
shimniok | 0:826c6171fc1b | 258 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 259 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; |
shimniok | 0:826c6171fc1b | 260 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; |
shimniok | 0:826c6171fc1b | 261 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; |
shimniok | 0:826c6171fc1b | 262 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; |
shimniok | 0:826c6171fc1b | 263 | return (float)r.f; |
shimniok | 0:826c6171fc1b | 264 | } |
shimniok | 0:826c6171fc1b | 265 | |
shimniok | 0:826c6171fc1b | 266 | /** |
shimniok | 0:826c6171fc1b | 267 | * @brief Get field yawspeed from full_state message |
shimniok | 0:826c6171fc1b | 268 | * |
shimniok | 0:826c6171fc1b | 269 | * @return Yaw angular speed (rad/s) |
shimniok | 0:826c6171fc1b | 270 | */ |
shimniok | 0:826c6171fc1b | 271 | static inline float mavlink_msg_full_state_get_yawspeed(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 272 | { |
shimniok | 0:826c6171fc1b | 273 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 274 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; |
shimniok | 0:826c6171fc1b | 275 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; |
shimniok | 0:826c6171fc1b | 276 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; |
shimniok | 0:826c6171fc1b | 277 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; |
shimniok | 0:826c6171fc1b | 278 | return (float)r.f; |
shimniok | 0:826c6171fc1b | 279 | } |
shimniok | 0:826c6171fc1b | 280 | |
shimniok | 0:826c6171fc1b | 281 | /** |
shimniok | 0:826c6171fc1b | 282 | * @brief Get field lat from full_state message |
shimniok | 0:826c6171fc1b | 283 | * |
shimniok | 0:826c6171fc1b | 284 | * @return Latitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 285 | */ |
shimniok | 0:826c6171fc1b | 286 | static inline int32_t mavlink_msg_full_state_get_lat(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 287 | { |
shimniok | 0:826c6171fc1b | 288 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 289 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; |
shimniok | 0:826c6171fc1b | 290 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; |
shimniok | 0:826c6171fc1b | 291 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; |
shimniok | 0:826c6171fc1b | 292 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; |
shimniok | 0:826c6171fc1b | 293 | return (int32_t)r.i; |
shimniok | 0:826c6171fc1b | 294 | } |
shimniok | 0:826c6171fc1b | 295 | |
shimniok | 0:826c6171fc1b | 296 | /** |
shimniok | 0:826c6171fc1b | 297 | * @brief Get field lon from full_state message |
shimniok | 0:826c6171fc1b | 298 | * |
shimniok | 0:826c6171fc1b | 299 | * @return Longitude, expressed as * 1E7 |
shimniok | 0:826c6171fc1b | 300 | */ |
shimniok | 0:826c6171fc1b | 301 | static inline int32_t mavlink_msg_full_state_get_lon(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 302 | { |
shimniok | 0:826c6171fc1b | 303 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 304 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[0]; |
shimniok | 0:826c6171fc1b | 305 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[1]; |
shimniok | 0:826c6171fc1b | 306 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[2]; |
shimniok | 0:826c6171fc1b | 307 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[3]; |
shimniok | 0:826c6171fc1b | 308 | return (int32_t)r.i; |
shimniok | 0:826c6171fc1b | 309 | } |
shimniok | 0:826c6171fc1b | 310 | |
shimniok | 0:826c6171fc1b | 311 | /** |
shimniok | 0:826c6171fc1b | 312 | * @brief Get field alt from full_state message |
shimniok | 0:826c6171fc1b | 313 | * |
shimniok | 0:826c6171fc1b | 314 | * @return Altitude in meters, expressed as * 1000 (millimeters) |
shimniok | 0:826c6171fc1b | 315 | */ |
shimniok | 0:826c6171fc1b | 316 | static inline int32_t mavlink_msg_full_state_get_alt(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 317 | { |
shimniok | 0:826c6171fc1b | 318 | generic_32bit r; |
shimniok | 0:826c6171fc1b | 319 | r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[0]; |
shimniok | 0:826c6171fc1b | 320 | r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[1]; |
shimniok | 0:826c6171fc1b | 321 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[2]; |
shimniok | 0:826c6171fc1b | 322 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[3]; |
shimniok | 0:826c6171fc1b | 323 | return (int32_t)r.i; |
shimniok | 0:826c6171fc1b | 324 | } |
shimniok | 0:826c6171fc1b | 325 | |
shimniok | 0:826c6171fc1b | 326 | /** |
shimniok | 0:826c6171fc1b | 327 | * @brief Get field vx from full_state message |
shimniok | 0:826c6171fc1b | 328 | * |
shimniok | 0:826c6171fc1b | 329 | * @return Ground X Speed (Latitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 330 | */ |
shimniok | 0:826c6171fc1b | 331 | static inline int16_t mavlink_msg_full_state_get_vx(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 332 | { |
shimniok | 0:826c6171fc1b | 333 | generic_16bit r; |
shimniok | 0:826c6171fc1b | 334 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[0]; |
shimniok | 0:826c6171fc1b | 335 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[1]; |
shimniok | 0:826c6171fc1b | 336 | return (int16_t)r.s; |
shimniok | 0:826c6171fc1b | 337 | } |
shimniok | 0:826c6171fc1b | 338 | |
shimniok | 0:826c6171fc1b | 339 | /** |
shimniok | 0:826c6171fc1b | 340 | * @brief Get field vy from full_state message |
shimniok | 0:826c6171fc1b | 341 | * |
shimniok | 0:826c6171fc1b | 342 | * @return Ground Y Speed (Longitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 343 | */ |
shimniok | 0:826c6171fc1b | 344 | static inline int16_t mavlink_msg_full_state_get_vy(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 345 | { |
shimniok | 0:826c6171fc1b | 346 | generic_16bit r; |
shimniok | 0:826c6171fc1b | 347 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[0]; |
shimniok | 0:826c6171fc1b | 348 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[1]; |
shimniok | 0:826c6171fc1b | 349 | return (int16_t)r.s; |
shimniok | 0:826c6171fc1b | 350 | } |
shimniok | 0:826c6171fc1b | 351 | |
shimniok | 0:826c6171fc1b | 352 | /** |
shimniok | 0:826c6171fc1b | 353 | * @brief Get field vz from full_state message |
shimniok | 0:826c6171fc1b | 354 | * |
shimniok | 0:826c6171fc1b | 355 | * @return Ground Z Speed (Altitude), expressed as m/s * 100 |
shimniok | 0:826c6171fc1b | 356 | */ |
shimniok | 0:826c6171fc1b | 357 | static inline int16_t mavlink_msg_full_state_get_vz(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 358 | { |
shimniok | 0:826c6171fc1b | 359 | generic_16bit r; |
shimniok | 0:826c6171fc1b | 360 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[0]; |
shimniok | 0:826c6171fc1b | 361 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[1]; |
shimniok | 0:826c6171fc1b | 362 | return (int16_t)r.s; |
shimniok | 0:826c6171fc1b | 363 | } |
shimniok | 0:826c6171fc1b | 364 | |
shimniok | 0:826c6171fc1b | 365 | /** |
shimniok | 0:826c6171fc1b | 366 | * @brief Get field xacc from full_state message |
shimniok | 0:826c6171fc1b | 367 | * |
shimniok | 0:826c6171fc1b | 368 | * @return X acceleration (mg) |
shimniok | 0:826c6171fc1b | 369 | */ |
shimniok | 0:826c6171fc1b | 370 | static inline int16_t mavlink_msg_full_state_get_xacc(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 371 | { |
shimniok | 0:826c6171fc1b | 372 | generic_16bit r; |
shimniok | 0:826c6171fc1b | 373 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; |
shimniok | 0:826c6171fc1b | 374 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; |
shimniok | 0:826c6171fc1b | 375 | return (int16_t)r.s; |
shimniok | 0:826c6171fc1b | 376 | } |
shimniok | 0:826c6171fc1b | 377 | |
shimniok | 0:826c6171fc1b | 378 | /** |
shimniok | 0:826c6171fc1b | 379 | * @brief Get field yacc from full_state message |
shimniok | 0:826c6171fc1b | 380 | * |
shimniok | 0:826c6171fc1b | 381 | * @return Y acceleration (mg) |
shimniok | 0:826c6171fc1b | 382 | */ |
shimniok | 0:826c6171fc1b | 383 | static inline int16_t mavlink_msg_full_state_get_yacc(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 384 | { |
shimniok | 0:826c6171fc1b | 385 | generic_16bit r; |
shimniok | 0:826c6171fc1b | 386 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; |
shimniok | 0:826c6171fc1b | 387 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; |
shimniok | 0:826c6171fc1b | 388 | return (int16_t)r.s; |
shimniok | 0:826c6171fc1b | 389 | } |
shimniok | 0:826c6171fc1b | 390 | |
shimniok | 0:826c6171fc1b | 391 | /** |
shimniok | 0:826c6171fc1b | 392 | * @brief Get field zacc from full_state message |
shimniok | 0:826c6171fc1b | 393 | * |
shimniok | 0:826c6171fc1b | 394 | * @return Z acceleration (mg) |
shimniok | 0:826c6171fc1b | 395 | */ |
shimniok | 0:826c6171fc1b | 396 | static inline int16_t mavlink_msg_full_state_get_zacc(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 397 | { |
shimniok | 0:826c6171fc1b | 398 | generic_16bit r; |
shimniok | 0:826c6171fc1b | 399 | r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; |
shimniok | 0:826c6171fc1b | 400 | r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; |
shimniok | 0:826c6171fc1b | 401 | return (int16_t)r.s; |
shimniok | 0:826c6171fc1b | 402 | } |
shimniok | 0:826c6171fc1b | 403 | |
shimniok | 0:826c6171fc1b | 404 | /** |
shimniok | 0:826c6171fc1b | 405 | * @brief Decode a full_state message into a struct |
shimniok | 0:826c6171fc1b | 406 | * |
shimniok | 0:826c6171fc1b | 407 | * @param msg The message to decode |
shimniok | 0:826c6171fc1b | 408 | * @param full_state C-struct to decode the message contents into |
shimniok | 0:826c6171fc1b | 409 | */ |
shimniok | 0:826c6171fc1b | 410 | static inline void mavlink_msg_full_state_decode(const mavlink_message_t* msg, mavlink_full_state_t* full_state) |
shimniok | 0:826c6171fc1b | 411 | { |
shimniok | 0:826c6171fc1b | 412 | full_state->usec = mavlink_msg_full_state_get_usec(msg); |
shimniok | 0:826c6171fc1b | 413 | full_state->roll = mavlink_msg_full_state_get_roll(msg); |
shimniok | 0:826c6171fc1b | 414 | full_state->pitch = mavlink_msg_full_state_get_pitch(msg); |
shimniok | 0:826c6171fc1b | 415 | full_state->yaw = mavlink_msg_full_state_get_yaw(msg); |
shimniok | 0:826c6171fc1b | 416 | full_state->rollspeed = mavlink_msg_full_state_get_rollspeed(msg); |
shimniok | 0:826c6171fc1b | 417 | full_state->pitchspeed = mavlink_msg_full_state_get_pitchspeed(msg); |
shimniok | 0:826c6171fc1b | 418 | full_state->yawspeed = mavlink_msg_full_state_get_yawspeed(msg); |
shimniok | 0:826c6171fc1b | 419 | full_state->lat = mavlink_msg_full_state_get_lat(msg); |
shimniok | 0:826c6171fc1b | 420 | full_state->lon = mavlink_msg_full_state_get_lon(msg); |
shimniok | 0:826c6171fc1b | 421 | full_state->alt = mavlink_msg_full_state_get_alt(msg); |
shimniok | 0:826c6171fc1b | 422 | full_state->vx = mavlink_msg_full_state_get_vx(msg); |
shimniok | 0:826c6171fc1b | 423 | full_state->vy = mavlink_msg_full_state_get_vy(msg); |
shimniok | 0:826c6171fc1b | 424 | full_state->vz = mavlink_msg_full_state_get_vz(msg); |
shimniok | 0:826c6171fc1b | 425 | full_state->xacc = mavlink_msg_full_state_get_xacc(msg); |
shimniok | 0:826c6171fc1b | 426 | full_state->yacc = mavlink_msg_full_state_get_yacc(msg); |
shimniok | 0:826c6171fc1b | 427 | full_state->zacc = mavlink_msg_full_state_get_zacc(msg); |
shimniok | 0:826c6171fc1b | 428 | } |