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

mavlink_msg_global_position_int.h

00001 // MESSAGE GLOBAL_POSITION_INT PACKING
00002 
00003 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 73
00004 
00005 typedef struct __mavlink_global_position_int_t 
00006 {
00007     int32_t lat; ///< Latitude, expressed as * 1E7
00008     int32_t lon; ///< Longitude, expressed as * 1E7
00009     int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters)
00010     int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
00011     int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
00012     int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
00013 
00014 } mavlink_global_position_int_t;
00015 
00016 
00017 
00018 /**
00019  * @brief Pack a global_position_int message
00020  * @param system_id ID of this system
00021  * @param component_id ID of this component (e.g. 200 for IMU)
00022  * @param msg The MAVLink message to compress the data into
00023  *
00024  * @param lat Latitude, expressed as * 1E7
00025  * @param lon Longitude, expressed as * 1E7
00026  * @param alt Altitude in meters, expressed as * 1000 (millimeters)
00027  * @param vx Ground X Speed (Latitude), expressed as m/s * 100
00028  * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
00029  * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
00030  * @return length of the message in bytes (excluding serial stream start sign)
00031  */
00032 static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
00033 {
00034     uint16_t i = 0;
00035     msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
00036 
00037     i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7
00038     i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7
00039     i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
00040     i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
00041     i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
00042     i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
00043 
00044     return mavlink_finalize_message(msg, system_id, component_id, i);
00045 }
00046 
00047 /**
00048  * @brief Pack a global_position_int message
00049  * @param system_id ID of this system
00050  * @param component_id ID of this component (e.g. 200 for IMU)
00051  * @param chan The MAVLink channel this message was sent over
00052  * @param msg The MAVLink message to compress the data into
00053  * @param lat Latitude, expressed as * 1E7
00054  * @param lon Longitude, expressed as * 1E7
00055  * @param alt Altitude in meters, expressed as * 1000 (millimeters)
00056  * @param vx Ground X Speed (Latitude), expressed as m/s * 100
00057  * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
00058  * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
00059  * @return length of the message in bytes (excluding serial stream start sign)
00060  */
00061 static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
00062 {
00063     uint16_t i = 0;
00064     msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
00065 
00066     i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7
00067     i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7
00068     i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
00069     i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
00070     i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
00071     i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
00072 
00073     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00074 }
00075 
00076 /**
00077  * @brief Encode a global_position_int struct into a message
00078  *
00079  * @param system_id ID of this system
00080  * @param component_id ID of this component (e.g. 200 for IMU)
00081  * @param msg The MAVLink message to compress the data into
00082  * @param global_position_int C-struct to read the message contents from
00083  */
00084 static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
00085 {
00086     return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->vx, global_position_int->vy, global_position_int->vz);
00087 }
00088 
00089 /**
00090  * @brief Send a global_position_int message
00091  * @param chan MAVLink channel to send the message
00092  *
00093  * @param lat Latitude, expressed as * 1E7
00094  * @param lon Longitude, expressed as * 1E7
00095  * @param alt Altitude in meters, expressed as * 1000 (millimeters)
00096  * @param vx Ground X Speed (Latitude), expressed as m/s * 100
00097  * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
00098  * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
00099  */
00100 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00101 
00102 static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
00103 {
00104     mavlink_message_t msg;
00105     mavlink_msg_global_position_int_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, lat, lon, alt, vx, vy, vz);
00106     mavlink_send_uart(chan, &msg);
00107 }
00108 
00109 #endif
00110 // MESSAGE GLOBAL_POSITION_INT UNPACKING
00111 
00112 /**
00113  * @brief Get field lat from global_position_int message
00114  *
00115  * @return Latitude, expressed as * 1E7
00116  */
00117 static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
00118 {
00119     generic_32bit r;
00120     r.b[3] = (msg->payload)[0];
00121     r.b[2] = (msg->payload)[1];
00122     r.b[1] = (msg->payload)[2];
00123     r.b[0] = (msg->payload)[3];
00124     return (int32_t)r.i;
00125 }
00126 
00127 /**
00128  * @brief Get field lon from global_position_int message
00129  *
00130  * @return Longitude, expressed as * 1E7
00131  */
00132 static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
00133 {
00134     generic_32bit r;
00135     r.b[3] = (msg->payload+sizeof(int32_t))[0];
00136     r.b[2] = (msg->payload+sizeof(int32_t))[1];
00137     r.b[1] = (msg->payload+sizeof(int32_t))[2];
00138     r.b[0] = (msg->payload+sizeof(int32_t))[3];
00139     return (int32_t)r.i;
00140 }
00141 
00142 /**
00143  * @brief Get field alt from global_position_int message
00144  *
00145  * @return Altitude in meters, expressed as * 1000 (millimeters)
00146  */
00147 static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
00148 {
00149     generic_32bit r;
00150     r.b[3] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[0];
00151     r.b[2] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[1];
00152     r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[2];
00153     r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[3];
00154     return (int32_t)r.i;
00155 }
00156 
00157 /**
00158  * @brief Get field vx from global_position_int message
00159  *
00160  * @return Ground X Speed (Latitude), expressed as m/s * 100
00161  */
00162 static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
00163 {
00164     generic_16bit r;
00165     r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[0];
00166     r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[1];
00167     return (int16_t)r.s;
00168 }
00169 
00170 /**
00171  * @brief Get field vy from global_position_int message
00172  *
00173  * @return Ground Y Speed (Longitude), expressed as m/s * 100
00174  */
00175 static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
00176 {
00177     generic_16bit r;
00178     r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[0];
00179     r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[1];
00180     return (int16_t)r.s;
00181 }
00182 
00183 /**
00184  * @brief Get field vz from global_position_int message
00185  *
00186  * @return Ground Z Speed (Altitude), expressed as m/s * 100
00187  */
00188 static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
00189 {
00190     generic_16bit r;
00191     r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[0];
00192     r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[1];
00193     return (int16_t)r.s;
00194 }
00195 
00196 /**
00197  * @brief Decode a global_position_int message into a struct
00198  *
00199  * @param msg The message to decode
00200  * @param global_position_int C-struct to decode the message contents into
00201  */
00202 static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int)
00203 {
00204     global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg);
00205     global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg);
00206     global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg);
00207     global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg);
00208     global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg);
00209     global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg);
00210 }