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

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers mavlink_msg_hil_state.h Source File

mavlink_msg_hil_state.h

00001 // MESSAGE HIL_STATE PACKING
00002 
00003 #define MAVLINK_MSG_ID_HIL_STATE 67
00004 
00005 typedef struct __mavlink_hil_state_t 
00006 {
00007     uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
00008     float roll; ///< Roll angle (rad)
00009     float pitch; ///< Pitch angle (rad)
00010     float yaw; ///< Yaw angle (rad)
00011     float rollspeed; ///< Roll angular speed (rad/s)
00012     float pitchspeed; ///< Pitch angular speed (rad/s)
00013     float yawspeed; ///< Yaw angular speed (rad/s)
00014     int32_t lat; ///< Latitude, expressed as * 1E7
00015     int32_t lon; ///< Longitude, expressed as * 1E7
00016     int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters)
00017     int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
00018     int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
00019     int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
00020     int16_t xacc; ///< X acceleration (mg)
00021     int16_t yacc; ///< Y acceleration (mg)
00022     int16_t zacc; ///< Z acceleration (mg)
00023 
00024 } mavlink_hil_state_t;
00025 
00026 
00027 
00028 /**
00029  * @brief Pack a hil_state message
00030  * @param system_id ID of this system
00031  * @param component_id ID of this component (e.g. 200 for IMU)
00032  * @param msg The MAVLink message to compress the data into
00033  *
00034  * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
00035  * @param roll Roll angle (rad)
00036  * @param pitch Pitch angle (rad)
00037  * @param yaw Yaw angle (rad)
00038  * @param rollspeed Roll angular speed (rad/s)
00039  * @param pitchspeed Pitch angular speed (rad/s)
00040  * @param yawspeed Yaw angular speed (rad/s)
00041  * @param lat Latitude, expressed as * 1E7
00042  * @param lon Longitude, expressed as * 1E7
00043  * @param alt Altitude in meters, expressed as * 1000 (millimeters)
00044  * @param vx Ground X Speed (Latitude), expressed as m/s * 100
00045  * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
00046  * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
00047  * @param xacc X acceleration (mg)
00048  * @param yacc Y acceleration (mg)
00049  * @param zacc Z acceleration (mg)
00050  * @return length of the message in bytes (excluding serial stream start sign)
00051  */
00052 static inline uint16_t mavlink_msg_hil_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)
00053 {
00054     uint16_t i = 0;
00055     msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
00056 
00057     i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
00058     i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
00059     i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
00060     i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
00061     i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s)
00062     i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s)
00063     i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s)
00064     i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7
00065     i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7
00066     i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
00067     i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
00068     i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
00069     i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
00070     i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg)
00071     i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg)
00072     i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg)
00073 
00074     return mavlink_finalize_message(msg, system_id, component_id, i);
00075 }
00076 
00077 /**
00078  * @brief Pack a hil_state message
00079  * @param system_id ID of this system
00080  * @param component_id ID of this component (e.g. 200 for IMU)
00081  * @param chan The MAVLink channel this message was sent over
00082  * @param msg The MAVLink message to compress the data into
00083  * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
00084  * @param roll Roll angle (rad)
00085  * @param pitch Pitch angle (rad)
00086  * @param yaw Yaw angle (rad)
00087  * @param rollspeed Roll angular speed (rad/s)
00088  * @param pitchspeed Pitch angular speed (rad/s)
00089  * @param yawspeed Yaw angular speed (rad/s)
00090  * @param lat Latitude, expressed as * 1E7
00091  * @param lon Longitude, expressed as * 1E7
00092  * @param alt Altitude in meters, expressed as * 1000 (millimeters)
00093  * @param vx Ground X Speed (Latitude), expressed as m/s * 100
00094  * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
00095  * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
00096  * @param xacc X acceleration (mg)
00097  * @param yacc Y acceleration (mg)
00098  * @param zacc Z acceleration (mg)
00099  * @return length of the message in bytes (excluding serial stream start sign)
00100  */
00101 static inline uint16_t mavlink_msg_hil_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)
00102 {
00103     uint16_t i = 0;
00104     msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
00105 
00106     i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
00107     i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
00108     i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
00109     i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
00110     i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s)
00111     i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s)
00112     i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s)
00113     i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7
00114     i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7
00115     i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
00116     i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
00117     i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
00118     i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
00119     i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg)
00120     i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg)
00121     i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg)
00122 
00123     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00124 }
00125 
00126 /**
00127  * @brief Encode a hil_state struct into a message
00128  *
00129  * @param system_id ID of this system
00130  * @param component_id ID of this component (e.g. 200 for IMU)
00131  * @param msg The MAVLink message to compress the data into
00132  * @param hil_state C-struct to read the message contents from
00133  */
00134 static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state)
00135 {
00136     return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc);
00137 }
00138 
00139 /**
00140  * @brief Send a hil_state message
00141  * @param chan MAVLink channel to send the message
00142  *
00143  * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
00144  * @param roll Roll angle (rad)
00145  * @param pitch Pitch angle (rad)
00146  * @param yaw Yaw angle (rad)
00147  * @param rollspeed Roll angular speed (rad/s)
00148  * @param pitchspeed Pitch angular speed (rad/s)
00149  * @param yawspeed Yaw angular speed (rad/s)
00150  * @param lat Latitude, expressed as * 1E7
00151  * @param lon Longitude, expressed as * 1E7
00152  * @param alt Altitude in meters, expressed as * 1000 (millimeters)
00153  * @param vx Ground X Speed (Latitude), expressed as m/s * 100
00154  * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
00155  * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
00156  * @param xacc X acceleration (mg)
00157  * @param yacc Y acceleration (mg)
00158  * @param zacc Z acceleration (mg)
00159  */
00160 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00161 
00162 static inline void mavlink_msg_hil_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)
00163 {
00164     mavlink_message_t msg;
00165     mavlink_msg_hil_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);
00166     mavlink_send_uart(chan, &msg);
00167 }
00168 
00169 #endif
00170 // MESSAGE HIL_STATE UNPACKING
00171 
00172 /**
00173  * @brief Get field usec from hil_state message
00174  *
00175  * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
00176  */
00177 static inline uint64_t mavlink_msg_hil_state_get_usec(const mavlink_message_t* msg)
00178 {
00179     generic_64bit r;
00180     r.b[7] = (msg->payload)[0];
00181     r.b[6] = (msg->payload)[1];
00182     r.b[5] = (msg->payload)[2];
00183     r.b[4] = (msg->payload)[3];
00184     r.b[3] = (msg->payload)[4];
00185     r.b[2] = (msg->payload)[5];
00186     r.b[1] = (msg->payload)[6];
00187     r.b[0] = (msg->payload)[7];
00188     return (uint64_t)r.ll;
00189 }
00190 
00191 /**
00192  * @brief Get field roll from hil_state message
00193  *
00194  * @return Roll angle (rad)
00195  */
00196 static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg)
00197 {
00198     generic_32bit r;
00199     r.b[3] = (msg->payload+sizeof(uint64_t))[0];
00200     r.b[2] = (msg->payload+sizeof(uint64_t))[1];
00201     r.b[1] = (msg->payload+sizeof(uint64_t))[2];
00202     r.b[0] = (msg->payload+sizeof(uint64_t))[3];
00203     return (float)r.f;
00204 }
00205 
00206 /**
00207  * @brief Get field pitch from hil_state message
00208  *
00209  * @return Pitch angle (rad)
00210  */
00211 static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg)
00212 {
00213     generic_32bit r;
00214     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
00215     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
00216     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
00217     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
00218     return (float)r.f;
00219 }
00220 
00221 /**
00222  * @brief Get field yaw from hil_state message
00223  *
00224  * @return Yaw angle (rad)
00225  */
00226 static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg)
00227 {
00228     generic_32bit r;
00229     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
00230     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
00231     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
00232     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
00233     return (float)r.f;
00234 }
00235 
00236 /**
00237  * @brief Get field rollspeed from hil_state message
00238  *
00239  * @return Roll angular speed (rad/s)
00240  */
00241 static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg)
00242 {
00243     generic_32bit r;
00244     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00245     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00246     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00247     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00248     return (float)r.f;
00249 }
00250 
00251 /**
00252  * @brief Get field pitchspeed from hil_state message
00253  *
00254  * @return Pitch angular speed (rad/s)
00255  */
00256 static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg)
00257 {
00258     generic_32bit r;
00259     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00260     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00261     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00262     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00263     return (float)r.f;
00264 }
00265 
00266 /**
00267  * @brief Get field yawspeed from hil_state message
00268  *
00269  * @return Yaw angular speed (rad/s)
00270  */
00271 static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg)
00272 {
00273     generic_32bit r;
00274     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00275     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00276     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00277     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00278     return (float)r.f;
00279 }
00280 
00281 /**
00282  * @brief Get field lat from hil_state message
00283  *
00284  * @return Latitude, expressed as * 1E7
00285  */
00286 static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg)
00287 {
00288     generic_32bit r;
00289     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00290     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00291     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00292     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00293     return (int32_t)r.i;
00294 }
00295 
00296 /**
00297  * @brief Get field lon from hil_state message
00298  *
00299  * @return Longitude, expressed as * 1E7
00300  */
00301 static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg)
00302 {
00303     generic_32bit r;
00304     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[0];
00305     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[1];
00306     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[2];
00307     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int32_t))[3];
00308     return (int32_t)r.i;
00309 }
00310 
00311 /**
00312  * @brief Get field alt from hil_state message
00313  *
00314  * @return Altitude in meters, expressed as * 1000 (millimeters)
00315  */
00316 static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg)
00317 {
00318     generic_32bit r;
00319     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];
00320     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];
00321     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];
00322     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];
00323     return (int32_t)r.i;
00324 }
00325 
00326 /**
00327  * @brief Get field vx from hil_state message
00328  *
00329  * @return Ground X Speed (Latitude), expressed as m/s * 100
00330  */
00331 static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg)
00332 {
00333     generic_16bit r;
00334     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];
00335     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];
00336     return (int16_t)r.s;
00337 }
00338 
00339 /**
00340  * @brief Get field vy from hil_state message
00341  *
00342  * @return Ground Y Speed (Longitude), expressed as m/s * 100
00343  */
00344 static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg)
00345 {
00346     generic_16bit r;
00347     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];
00348     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];
00349     return (int16_t)r.s;
00350 }
00351 
00352 /**
00353  * @brief Get field vz from hil_state message
00354  *
00355  * @return Ground Z Speed (Altitude), expressed as m/s * 100
00356  */
00357 static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg)
00358 {
00359     generic_16bit r;
00360     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];
00361     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];
00362     return (int16_t)r.s;
00363 }
00364 
00365 /**
00366  * @brief Get field xacc from hil_state message
00367  *
00368  * @return X acceleration (mg)
00369  */
00370 static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg)
00371 {
00372     generic_16bit r;
00373     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];
00374     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];
00375     return (int16_t)r.s;
00376 }
00377 
00378 /**
00379  * @brief Get field yacc from hil_state message
00380  *
00381  * @return Y acceleration (mg)
00382  */
00383 static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg)
00384 {
00385     generic_16bit r;
00386     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];
00387     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];
00388     return (int16_t)r.s;
00389 }
00390 
00391 /**
00392  * @brief Get field zacc from hil_state message
00393  *
00394  * @return Z acceleration (mg)
00395  */
00396 static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg)
00397 {
00398     generic_16bit r;
00399     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];
00400     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];
00401     return (int16_t)r.s;
00402 }
00403 
00404 /**
00405  * @brief Decode a hil_state message into a struct
00406  *
00407  * @param msg The message to decode
00408  * @param hil_state C-struct to decode the message contents into
00409  */
00410 static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state)
00411 {
00412     hil_state->usec = mavlink_msg_hil_state_get_usec(msg);
00413     hil_state->roll = mavlink_msg_hil_state_get_roll(msg);
00414     hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg);
00415     hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg);
00416     hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg);
00417     hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg);
00418     hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg);
00419     hil_state->lat = mavlink_msg_hil_state_get_lat(msg);
00420     hil_state->lon = mavlink_msg_hil_state_get_lon(msg);
00421     hil_state->alt = mavlink_msg_hil_state_get_alt(msg);
00422     hil_state->vx = mavlink_msg_hil_state_get_vx(msg);
00423     hil_state->vy = mavlink_msg_hil_state_get_vy(msg);
00424     hil_state->vz = mavlink_msg_hil_state_get_vz(msg);
00425     hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg);
00426     hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg);
00427     hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg);
00428 }