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

mavlink_msg_point_of_interest_connection.h

00001 // MESSAGE POINT_OF_INTEREST_CONNECTION PACKING
00002 
00003 #define MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION 162
00004 
00005 typedef struct __mavlink_point_of_interest_connection_t 
00006 {
00007     uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
00008     uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
00009     uint8_t coordinate_system; ///< 0: global, 1:local
00010     uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds
00011     float xp1; ///< X1 Position
00012     float yp1; ///< Y1 Position
00013     float zp1; ///< Z1 Position
00014     float xp2; ///< X2 Position
00015     float yp2; ///< Y2 Position
00016     float zp2; ///< Z2 Position
00017     int8_t name[25]; ///< POI connection name
00018 
00019 } mavlink_point_of_interest_connection_t;
00020 
00021 #define MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN 25
00022 
00023 
00024 /**
00025  * @brief Pack a point_of_interest_connection message
00026  * @param system_id ID of this system
00027  * @param component_id ID of this component (e.g. 200 for IMU)
00028  * @param msg The MAVLink message to compress the data into
00029  *
00030  * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
00031  * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
00032  * @param coordinate_system 0: global, 1:local
00033  * @param timeout 0: no timeout, >1: timeout in seconds
00034  * @param xp1 X1 Position
00035  * @param yp1 Y1 Position
00036  * @param zp1 Z1 Position
00037  * @param xp2 X2 Position
00038  * @param yp2 Y2 Position
00039  * @param zp2 Z2 Position
00040  * @param name POI connection name
00041  * @return length of the message in bytes (excluding serial stream start sign)
00042  */
00043 static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const int8_t* name)
00044 {
00045     uint16_t i = 0;
00046     msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION;
00047 
00048     i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
00049     i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
00050     i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local
00051     i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds
00052     i += put_float_by_index(xp1, i, msg->payload); // X1 Position
00053     i += put_float_by_index(yp1, i, msg->payload); // Y1 Position
00054     i += put_float_by_index(zp1, i, msg->payload); // Z1 Position
00055     i += put_float_by_index(xp2, i, msg->payload); // X2 Position
00056     i += put_float_by_index(yp2, i, msg->payload); // Y2 Position
00057     i += put_float_by_index(zp2, i, msg->payload); // Z2 Position
00058     i += put_array_by_index(name, 25, i, msg->payload); // POI connection name
00059 
00060     return mavlink_finalize_message(msg, system_id, component_id, i);
00061 }
00062 
00063 /**
00064  * @brief Pack a point_of_interest_connection message
00065  * @param system_id ID of this system
00066  * @param component_id ID of this component (e.g. 200 for IMU)
00067  * @param chan The MAVLink channel this message was sent over
00068  * @param msg The MAVLink message to compress the data into
00069  * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
00070  * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
00071  * @param coordinate_system 0: global, 1:local
00072  * @param timeout 0: no timeout, >1: timeout in seconds
00073  * @param xp1 X1 Position
00074  * @param yp1 Y1 Position
00075  * @param zp1 Z1 Position
00076  * @param xp2 X2 Position
00077  * @param yp2 Y2 Position
00078  * @param zp2 Z2 Position
00079  * @param name POI connection name
00080  * @return length of the message in bytes (excluding serial stream start sign)
00081  */
00082 static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const int8_t* name)
00083 {
00084     uint16_t i = 0;
00085     msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION;
00086 
00087     i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
00088     i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
00089     i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local
00090     i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds
00091     i += put_float_by_index(xp1, i, msg->payload); // X1 Position
00092     i += put_float_by_index(yp1, i, msg->payload); // Y1 Position
00093     i += put_float_by_index(zp1, i, msg->payload); // Z1 Position
00094     i += put_float_by_index(xp2, i, msg->payload); // X2 Position
00095     i += put_float_by_index(yp2, i, msg->payload); // Y2 Position
00096     i += put_float_by_index(zp2, i, msg->payload); // Z2 Position
00097     i += put_array_by_index(name, 25, i, msg->payload); // POI connection name
00098 
00099     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00100 }
00101 
00102 /**
00103  * @brief Encode a point_of_interest_connection struct into a message
00104  *
00105  * @param system_id ID of this system
00106  * @param component_id ID of this component (e.g. 200 for IMU)
00107  * @param msg The MAVLink message to compress the data into
00108  * @param point_of_interest_connection C-struct to read the message contents from
00109  */
00110 static inline uint16_t mavlink_msg_point_of_interest_connection_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_connection_t* point_of_interest_connection)
00111 {
00112     return mavlink_msg_point_of_interest_connection_pack(system_id, component_id, msg, point_of_interest_connection->type, point_of_interest_connection->color, point_of_interest_connection->coordinate_system, point_of_interest_connection->timeout, point_of_interest_connection->xp1, point_of_interest_connection->yp1, point_of_interest_connection->zp1, point_of_interest_connection->xp2, point_of_interest_connection->yp2, point_of_interest_connection->zp2, point_of_interest_connection->name);
00113 }
00114 
00115 /**
00116  * @brief Send a point_of_interest_connection message
00117  * @param chan MAVLink channel to send the message
00118  *
00119  * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
00120  * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
00121  * @param coordinate_system 0: global, 1:local
00122  * @param timeout 0: no timeout, >1: timeout in seconds
00123  * @param xp1 X1 Position
00124  * @param yp1 Y1 Position
00125  * @param zp1 Z1 Position
00126  * @param xp2 X2 Position
00127  * @param yp2 Y2 Position
00128  * @param zp2 Z2 Position
00129  * @param name POI connection name
00130  */
00131 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00132 
00133 static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const int8_t* name)
00134 {
00135     mavlink_message_t msg;
00136     mavlink_msg_point_of_interest_connection_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, color, coordinate_system, timeout, xp1, yp1, zp1, xp2, yp2, zp2, name);
00137     mavlink_send_uart(chan, &msg);
00138 }
00139 
00140 #endif
00141 // MESSAGE POINT_OF_INTEREST_CONNECTION UNPACKING
00142 
00143 /**
00144  * @brief Get field type from point_of_interest_connection message
00145  *
00146  * @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
00147  */
00148 static inline uint8_t mavlink_msg_point_of_interest_connection_get_type(const mavlink_message_t* msg)
00149 {
00150     return (uint8_t)(msg->payload)[0];
00151 }
00152 
00153 /**
00154  * @brief Get field color from point_of_interest_connection message
00155  *
00156  * @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
00157  */
00158 static inline uint8_t mavlink_msg_point_of_interest_connection_get_color(const mavlink_message_t* msg)
00159 {
00160     return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
00161 }
00162 
00163 /**
00164  * @brief Get field coordinate_system from point_of_interest_connection message
00165  *
00166  * @return 0: global, 1:local
00167  */
00168 static inline uint8_t mavlink_msg_point_of_interest_connection_get_coordinate_system(const mavlink_message_t* msg)
00169 {
00170     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
00171 }
00172 
00173 /**
00174  * @brief Get field timeout from point_of_interest_connection message
00175  *
00176  * @return 0: no timeout, >1: timeout in seconds
00177  */
00178 static inline uint16_t mavlink_msg_point_of_interest_connection_get_timeout(const mavlink_message_t* msg)
00179 {
00180     generic_16bit r;
00181     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
00182     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
00183     return (uint16_t)r.s;
00184 }
00185 
00186 /**
00187  * @brief Get field xp1 from point_of_interest_connection message
00188  *
00189  * @return X1 Position
00190  */
00191 static inline float mavlink_msg_point_of_interest_connection_get_xp1(const mavlink_message_t* msg)
00192 {
00193     generic_32bit r;
00194     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
00195     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1];
00196     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[2];
00197     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[3];
00198     return (float)r.f;
00199 }
00200 
00201 /**
00202  * @brief Get field yp1 from point_of_interest_connection message
00203  *
00204  * @return Y1 Position
00205  */
00206 static inline float mavlink_msg_point_of_interest_connection_get_yp1(const mavlink_message_t* msg)
00207 {
00208     generic_32bit r;
00209     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[0];
00210     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[1];
00211     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[2];
00212     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[3];
00213     return (float)r.f;
00214 }
00215 
00216 /**
00217  * @brief Get field zp1 from point_of_interest_connection message
00218  *
00219  * @return Z1 Position
00220  */
00221 static inline float mavlink_msg_point_of_interest_connection_get_zp1(const mavlink_message_t* msg)
00222 {
00223     generic_32bit r;
00224     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0];
00225     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1];
00226     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2];
00227     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3];
00228     return (float)r.f;
00229 }
00230 
00231 /**
00232  * @brief Get field xp2 from point_of_interest_connection message
00233  *
00234  * @return X2 Position
00235  */
00236 static inline float mavlink_msg_point_of_interest_connection_get_xp2(const mavlink_message_t* msg)
00237 {
00238     generic_32bit r;
00239     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00240     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00241     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00242     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00243     return (float)r.f;
00244 }
00245 
00246 /**
00247  * @brief Get field yp2 from point_of_interest_connection message
00248  *
00249  * @return Y2 Position
00250  */
00251 static inline float mavlink_msg_point_of_interest_connection_get_yp2(const mavlink_message_t* msg)
00252 {
00253     generic_32bit r;
00254     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00255     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00256     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00257     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00258     return (float)r.f;
00259 }
00260 
00261 /**
00262  * @brief Get field zp2 from point_of_interest_connection message
00263  *
00264  * @return Z2 Position
00265  */
00266 static inline float mavlink_msg_point_of_interest_connection_get_zp2(const mavlink_message_t* msg)
00267 {
00268     generic_32bit r;
00269     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00270     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00271     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00272     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00273     return (float)r.f;
00274 }
00275 
00276 /**
00277  * @brief Get field name from point_of_interest_connection message
00278  *
00279  * @return POI connection name
00280  */
00281 static inline uint16_t mavlink_msg_point_of_interest_connection_get_name(const mavlink_message_t* msg, int8_t* r_data)
00282 {
00283 
00284     memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float), 25);
00285     return 25;
00286 }
00287 
00288 /**
00289  * @brief Decode a point_of_interest_connection message into a struct
00290  *
00291  * @param msg The message to decode
00292  * @param point_of_interest_connection C-struct to decode the message contents into
00293  */
00294 static inline void mavlink_msg_point_of_interest_connection_decode(const mavlink_message_t* msg, mavlink_point_of_interest_connection_t* point_of_interest_connection)
00295 {
00296     point_of_interest_connection->type = mavlink_msg_point_of_interest_connection_get_type(msg);
00297     point_of_interest_connection->color = mavlink_msg_point_of_interest_connection_get_color(msg);
00298     point_of_interest_connection->coordinate_system = mavlink_msg_point_of_interest_connection_get_coordinate_system(msg);
00299     point_of_interest_connection->timeout = mavlink_msg_point_of_interest_connection_get_timeout(msg);
00300     point_of_interest_connection->xp1 = mavlink_msg_point_of_interest_connection_get_xp1(msg);
00301     point_of_interest_connection->yp1 = mavlink_msg_point_of_interest_connection_get_yp1(msg);
00302     point_of_interest_connection->zp1 = mavlink_msg_point_of_interest_connection_get_zp1(msg);
00303     point_of_interest_connection->xp2 = mavlink_msg_point_of_interest_connection_get_xp2(msg);
00304     point_of_interest_connection->yp2 = mavlink_msg_point_of_interest_connection_get_yp2(msg);
00305     point_of_interest_connection->zp2 = mavlink_msg_point_of_interest_connection_get_zp2(msg);
00306     mavlink_msg_point_of_interest_connection_get_name(msg, point_of_interest_connection->name);
00307 }