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_waypoint.h Source File

mavlink_msg_waypoint.h

00001 // MESSAGE WAYPOINT PACKING
00002 
00003 #define MAVLINK_MSG_ID_WAYPOINT 39
00004 
00005 typedef struct __mavlink_waypoint_t 
00006 {
00007     uint8_t target_system; ///< System ID
00008     uint8_t target_component; ///< Component ID
00009     uint16_t seq; ///< Sequence
00010     uint8_t frame; ///< The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
00011     uint8_t command; ///< The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
00012     uint8_t current; ///< false:0, true:1
00013     uint8_t autocontinue; ///< autocontinue to next wp
00014     float param1; ///< PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
00015     float param2; ///< PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
00016     float param3; ///< PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
00017     float param4; ///< PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
00018     float x; ///< PARAM5 / local: x position, global: latitude
00019     float y; ///< PARAM6 / y position: global: longitude
00020     float z; ///< PARAM7 / z position: global: altitude
00021 
00022 } mavlink_waypoint_t;
00023 
00024 
00025 
00026 /**
00027  * @brief Pack a waypoint message
00028  * @param system_id ID of this system
00029  * @param component_id ID of this component (e.g. 200 for IMU)
00030  * @param msg The MAVLink message to compress the data into
00031  *
00032  * @param target_system System ID
00033  * @param target_component Component ID
00034  * @param seq Sequence
00035  * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
00036  * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
00037  * @param current false:0, true:1
00038  * @param autocontinue autocontinue to next wp
00039  * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
00040  * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
00041  * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
00042  * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
00043  * @param x PARAM5 / local: x position, global: latitude
00044  * @param y PARAM6 / y position: global: longitude
00045  * @param z PARAM7 / z position: global: altitude
00046  * @return length of the message in bytes (excluding serial stream start sign)
00047  */
00048 static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
00049 {
00050     uint16_t i = 0;
00051     msg->msgid = MAVLINK_MSG_ID_WAYPOINT;
00052 
00053     i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
00054     i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
00055     i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
00056     i += put_uint8_t_by_index(frame, i, msg->payload); // The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
00057     i += put_uint8_t_by_index(command, i, msg->payload); // The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
00058     i += put_uint8_t_by_index(current, i, msg->payload); // false:0, true:1
00059     i += put_uint8_t_by_index(autocontinue, i, msg->payload); // autocontinue to next wp
00060     i += put_float_by_index(param1, i, msg->payload); // PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
00061     i += put_float_by_index(param2, i, msg->payload); // PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
00062     i += put_float_by_index(param3, i, msg->payload); // PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
00063     i += put_float_by_index(param4, i, msg->payload); // PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
00064     i += put_float_by_index(x, i, msg->payload); // PARAM5 / local: x position, global: latitude
00065     i += put_float_by_index(y, i, msg->payload); // PARAM6 / y position: global: longitude
00066     i += put_float_by_index(z, i, msg->payload); // PARAM7 / z position: global: altitude
00067 
00068     return mavlink_finalize_message(msg, system_id, component_id, i);
00069 }
00070 
00071 /**
00072  * @brief Pack a waypoint message
00073  * @param system_id ID of this system
00074  * @param component_id ID of this component (e.g. 200 for IMU)
00075  * @param chan The MAVLink channel this message was sent over
00076  * @param msg The MAVLink message to compress the data into
00077  * @param target_system System ID
00078  * @param target_component Component ID
00079  * @param seq Sequence
00080  * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
00081  * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
00082  * @param current false:0, true:1
00083  * @param autocontinue autocontinue to next wp
00084  * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
00085  * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
00086  * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
00087  * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
00088  * @param x PARAM5 / local: x position, global: latitude
00089  * @param y PARAM6 / y position: global: longitude
00090  * @param z PARAM7 / z position: global: altitude
00091  * @return length of the message in bytes (excluding serial stream start sign)
00092  */
00093 static inline uint16_t mavlink_msg_waypoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
00094 {
00095     uint16_t i = 0;
00096     msg->msgid = MAVLINK_MSG_ID_WAYPOINT;
00097 
00098     i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
00099     i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
00100     i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
00101     i += put_uint8_t_by_index(frame, i, msg->payload); // The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
00102     i += put_uint8_t_by_index(command, i, msg->payload); // The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
00103     i += put_uint8_t_by_index(current, i, msg->payload); // false:0, true:1
00104     i += put_uint8_t_by_index(autocontinue, i, msg->payload); // autocontinue to next wp
00105     i += put_float_by_index(param1, i, msg->payload); // PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
00106     i += put_float_by_index(param2, i, msg->payload); // PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
00107     i += put_float_by_index(param3, i, msg->payload); // PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
00108     i += put_float_by_index(param4, i, msg->payload); // PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
00109     i += put_float_by_index(x, i, msg->payload); // PARAM5 / local: x position, global: latitude
00110     i += put_float_by_index(y, i, msg->payload); // PARAM6 / y position: global: longitude
00111     i += put_float_by_index(z, i, msg->payload); // PARAM7 / z position: global: altitude
00112 
00113     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00114 }
00115 
00116 /**
00117  * @brief Encode a waypoint struct into a message
00118  *
00119  * @param system_id ID of this system
00120  * @param component_id ID of this component (e.g. 200 for IMU)
00121  * @param msg The MAVLink message to compress the data into
00122  * @param waypoint C-struct to read the message contents from
00123  */
00124 static inline uint16_t mavlink_msg_waypoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_t* waypoint)
00125 {
00126     return mavlink_msg_waypoint_pack(system_id, component_id, msg, waypoint->target_system, waypoint->target_component, waypoint->seq, waypoint->frame, waypoint->command, waypoint->current, waypoint->autocontinue, waypoint->param1, waypoint->param2, waypoint->param3, waypoint->param4, waypoint->x, waypoint->y, waypoint->z);
00127 }
00128 
00129 /**
00130  * @brief Send a waypoint message
00131  * @param chan MAVLink channel to send the message
00132  *
00133  * @param target_system System ID
00134  * @param target_component Component ID
00135  * @param seq Sequence
00136  * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
00137  * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
00138  * @param current false:0, true:1
00139  * @param autocontinue autocontinue to next wp
00140  * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
00141  * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
00142  * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
00143  * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
00144  * @param x PARAM5 / local: x position, global: latitude
00145  * @param y PARAM6 / y position: global: longitude
00146  * @param z PARAM7 / z position: global: altitude
00147  */
00148 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00149 
00150 static inline void mavlink_msg_waypoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
00151 {
00152     mavlink_message_t msg;
00153     mavlink_msg_waypoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z);
00154     mavlink_send_uart(chan, &msg);
00155 }
00156 
00157 #endif
00158 // MESSAGE WAYPOINT UNPACKING
00159 
00160 /**
00161  * @brief Get field target_system from waypoint message
00162  *
00163  * @return System ID
00164  */
00165 static inline uint8_t mavlink_msg_waypoint_get_target_system(const mavlink_message_t* msg)
00166 {
00167     return (uint8_t)(msg->payload)[0];
00168 }
00169 
00170 /**
00171  * @brief Get field target_component from waypoint message
00172  *
00173  * @return Component ID
00174  */
00175 static inline uint8_t mavlink_msg_waypoint_get_target_component(const mavlink_message_t* msg)
00176 {
00177     return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
00178 }
00179 
00180 /**
00181  * @brief Get field seq from waypoint message
00182  *
00183  * @return Sequence
00184  */
00185 static inline uint16_t mavlink_msg_waypoint_get_seq(const mavlink_message_t* msg)
00186 {
00187     generic_16bit r;
00188     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
00189     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
00190     return (uint16_t)r.s;
00191 }
00192 
00193 /**
00194  * @brief Get field frame from waypoint message
00195  *
00196  * @return The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
00197  */
00198 static inline uint8_t mavlink_msg_waypoint_get_frame(const mavlink_message_t* msg)
00199 {
00200     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
00201 }
00202 
00203 /**
00204  * @brief Get field command from waypoint message
00205  *
00206  * @return The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
00207  */
00208 static inline uint8_t mavlink_msg_waypoint_get_command(const mavlink_message_t* msg)
00209 {
00210     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t))[0];
00211 }
00212 
00213 /**
00214  * @brief Get field current from waypoint message
00215  *
00216  * @return false:0, true:1
00217  */
00218 static inline uint8_t mavlink_msg_waypoint_get_current(const mavlink_message_t* msg)
00219 {
00220     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
00221 }
00222 
00223 /**
00224  * @brief Get field autocontinue from waypoint message
00225  *
00226  * @return autocontinue to next wp
00227  */
00228 static inline uint8_t mavlink_msg_waypoint_get_autocontinue(const mavlink_message_t* msg)
00229 {
00230     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
00231 }
00232 
00233 /**
00234  * @brief Get field param1 from waypoint message
00235  *
00236  * @return PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
00237  */
00238 static inline float mavlink_msg_waypoint_get_param1(const mavlink_message_t* msg)
00239 {
00240     generic_32bit r;
00241     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
00242     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
00243     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[2];
00244     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[3];
00245     return (float)r.f;
00246 }
00247 
00248 /**
00249  * @brief Get field param2 from waypoint message
00250  *
00251  * @return PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
00252  */
00253 static inline float mavlink_msg_waypoint_get_param2(const mavlink_message_t* msg)
00254 {
00255     generic_32bit r;
00256     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
00257     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
00258     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
00259     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
00260     return (float)r.f;
00261 }
00262 
00263 /**
00264  * @brief Get field param3 from waypoint message
00265  *
00266  * @return PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
00267  */
00268 static inline float mavlink_msg_waypoint_get_param3(const mavlink_message_t* msg)
00269 {
00270     generic_32bit r;
00271     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
00272     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
00273     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
00274     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
00275     return (float)r.f;
00276 }
00277 
00278 /**
00279  * @brief Get field param4 from waypoint message
00280  *
00281  * @return PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
00282  */
00283 static inline float mavlink_msg_waypoint_get_param4(const mavlink_message_t* msg)
00284 {
00285     generic_32bit r;
00286     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00287     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00288     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00289     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00290     return (float)r.f;
00291 }
00292 
00293 /**
00294  * @brief Get field x from waypoint message
00295  *
00296  * @return PARAM5 / local: x position, global: latitude
00297  */
00298 static inline float mavlink_msg_waypoint_get_x(const mavlink_message_t* msg)
00299 {
00300     generic_32bit r;
00301     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00302     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00303     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00304     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00305     return (float)r.f;
00306 }
00307 
00308 /**
00309  * @brief Get field y from waypoint message
00310  *
00311  * @return PARAM6 / y position: global: longitude
00312  */
00313 static inline float mavlink_msg_waypoint_get_y(const mavlink_message_t* msg)
00314 {
00315     generic_32bit r;
00316     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00317     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00318     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00319     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00320     return (float)r.f;
00321 }
00322 
00323 /**
00324  * @brief Get field z from waypoint message
00325  *
00326  * @return PARAM7 / z position: global: altitude
00327  */
00328 static inline float mavlink_msg_waypoint_get_z(const mavlink_message_t* msg)
00329 {
00330     generic_32bit r;
00331     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00332     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00333     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00334     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00335     return (float)r.f;
00336 }
00337 
00338 /**
00339  * @brief Decode a waypoint message into a struct
00340  *
00341  * @param msg The message to decode
00342  * @param waypoint C-struct to decode the message contents into
00343  */
00344 static inline void mavlink_msg_waypoint_decode(const mavlink_message_t* msg, mavlink_waypoint_t* waypoint)
00345 {
00346     waypoint->target_system = mavlink_msg_waypoint_get_target_system(msg);
00347     waypoint->target_component = mavlink_msg_waypoint_get_target_component(msg);
00348     waypoint->seq = mavlink_msg_waypoint_get_seq(msg);
00349     waypoint->frame = mavlink_msg_waypoint_get_frame(msg);
00350     waypoint->command = mavlink_msg_waypoint_get_command(msg);
00351     waypoint->current = mavlink_msg_waypoint_get_current(msg);
00352     waypoint->autocontinue = mavlink_msg_waypoint_get_autocontinue(msg);
00353     waypoint->param1 = mavlink_msg_waypoint_get_param1(msg);
00354     waypoint->param2 = mavlink_msg_waypoint_get_param2(msg);
00355     waypoint->param3 = mavlink_msg_waypoint_get_param3(msg);
00356     waypoint->param4 = mavlink_msg_waypoint_get_param4(msg);
00357     waypoint->x = mavlink_msg_waypoint_get_x(msg);
00358     waypoint->y = mavlink_msg_waypoint_get_y(msg);
00359     waypoint->z = mavlink_msg_waypoint_get_z(msg);
00360 }