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

mavlink_msg_point_of_interest.h

00001 // MESSAGE POINT_OF_INTEREST PACKING
00002 
00003 #define MAVLINK_MSG_ID_POINT_OF_INTEREST 161
00004 
00005 typedef struct __mavlink_point_of_interest_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 x; ///< X Position
00012     float y; ///< Y Position
00013     float z; ///< Z Position
00014     int8_t name[25]; ///< POI name
00015 
00016 } mavlink_point_of_interest_t;
00017 
00018 #define MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN 25
00019 
00020 
00021 /**
00022  * @brief Pack a point_of_interest message
00023  * @param system_id ID of this system
00024  * @param component_id ID of this component (e.g. 200 for IMU)
00025  * @param msg The MAVLink message to compress the data into
00026  *
00027  * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
00028  * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
00029  * @param coordinate_system 0: global, 1:local
00030  * @param timeout 0: no timeout, >1: timeout in seconds
00031  * @param x X Position
00032  * @param y Y Position
00033  * @param z Z Position
00034  * @param name POI name
00035  * @return length of the message in bytes (excluding serial stream start sign)
00036  */
00037 static inline uint16_t mavlink_msg_point_of_interest_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 x, float y, float z, const int8_t* name)
00038 {
00039     uint16_t i = 0;
00040     msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST;
00041 
00042     i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
00043     i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
00044     i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local
00045     i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds
00046     i += put_float_by_index(x, i, msg->payload); // X Position
00047     i += put_float_by_index(y, i, msg->payload); // Y Position
00048     i += put_float_by_index(z, i, msg->payload); // Z Position
00049     i += put_array_by_index(name, 25, i, msg->payload); // POI name
00050 
00051     return mavlink_finalize_message(msg, system_id, component_id, i);
00052 }
00053 
00054 /**
00055  * @brief Pack a point_of_interest message
00056  * @param system_id ID of this system
00057  * @param component_id ID of this component (e.g. 200 for IMU)
00058  * @param chan The MAVLink channel this message was sent over
00059  * @param msg The MAVLink message to compress the data into
00060  * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
00061  * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
00062  * @param coordinate_system 0: global, 1:local
00063  * @param timeout 0: no timeout, >1: timeout in seconds
00064  * @param x X Position
00065  * @param y Y Position
00066  * @param z Z Position
00067  * @param name POI name
00068  * @return length of the message in bytes (excluding serial stream start sign)
00069  */
00070 static inline uint16_t mavlink_msg_point_of_interest_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 x, float y, float z, const int8_t* name)
00071 {
00072     uint16_t i = 0;
00073     msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST;
00074 
00075     i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
00076     i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
00077     i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local
00078     i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds
00079     i += put_float_by_index(x, i, msg->payload); // X Position
00080     i += put_float_by_index(y, i, msg->payload); // Y Position
00081     i += put_float_by_index(z, i, msg->payload); // Z Position
00082     i += put_array_by_index(name, 25, i, msg->payload); // POI name
00083 
00084     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00085 }
00086 
00087 /**
00088  * @brief Encode a point_of_interest struct into a message
00089  *
00090  * @param system_id ID of this system
00091  * @param component_id ID of this component (e.g. 200 for IMU)
00092  * @param msg The MAVLink message to compress the data into
00093  * @param point_of_interest C-struct to read the message contents from
00094  */
00095 static inline uint16_t mavlink_msg_point_of_interest_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_t* point_of_interest)
00096 {
00097     return mavlink_msg_point_of_interest_pack(system_id, component_id, msg, point_of_interest->type, point_of_interest->color, point_of_interest->coordinate_system, point_of_interest->timeout, point_of_interest->x, point_of_interest->y, point_of_interest->z, point_of_interest->name);
00098 }
00099 
00100 /**
00101  * @brief Send a point_of_interest message
00102  * @param chan MAVLink channel to send the message
00103  *
00104  * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
00105  * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
00106  * @param coordinate_system 0: global, 1:local
00107  * @param timeout 0: no timeout, >1: timeout in seconds
00108  * @param x X Position
00109  * @param y Y Position
00110  * @param z Z Position
00111  * @param name POI name
00112  */
00113 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00114 
00115 static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const int8_t* name)
00116 {
00117     mavlink_message_t msg;
00118     mavlink_msg_point_of_interest_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, color, coordinate_system, timeout, x, y, z, name);
00119     mavlink_send_uart(chan, &msg);
00120 }
00121 
00122 #endif
00123 // MESSAGE POINT_OF_INTEREST UNPACKING
00124 
00125 /**
00126  * @brief Get field type from point_of_interest message
00127  *
00128  * @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
00129  */
00130 static inline uint8_t mavlink_msg_point_of_interest_get_type(const mavlink_message_t* msg)
00131 {
00132     return (uint8_t)(msg->payload)[0];
00133 }
00134 
00135 /**
00136  * @brief Get field color from point_of_interest message
00137  *
00138  * @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
00139  */
00140 static inline uint8_t mavlink_msg_point_of_interest_get_color(const mavlink_message_t* msg)
00141 {
00142     return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
00143 }
00144 
00145 /**
00146  * @brief Get field coordinate_system from point_of_interest message
00147  *
00148  * @return 0: global, 1:local
00149  */
00150 static inline uint8_t mavlink_msg_point_of_interest_get_coordinate_system(const mavlink_message_t* msg)
00151 {
00152     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
00153 }
00154 
00155 /**
00156  * @brief Get field timeout from point_of_interest message
00157  *
00158  * @return 0: no timeout, >1: timeout in seconds
00159  */
00160 static inline uint16_t mavlink_msg_point_of_interest_get_timeout(const mavlink_message_t* msg)
00161 {
00162     generic_16bit r;
00163     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
00164     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
00165     return (uint16_t)r.s;
00166 }
00167 
00168 /**
00169  * @brief Get field x from point_of_interest message
00170  *
00171  * @return X Position
00172  */
00173 static inline float mavlink_msg_point_of_interest_get_x(const mavlink_message_t* msg)
00174 {
00175     generic_32bit r;
00176     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
00177     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1];
00178     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[2];
00179     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[3];
00180     return (float)r.f;
00181 }
00182 
00183 /**
00184  * @brief Get field y from point_of_interest message
00185  *
00186  * @return Y Position
00187  */
00188 static inline float mavlink_msg_point_of_interest_get_y(const mavlink_message_t* msg)
00189 {
00190     generic_32bit r;
00191     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[0];
00192     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[1];
00193     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[2];
00194     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[3];
00195     return (float)r.f;
00196 }
00197 
00198 /**
00199  * @brief Get field z from point_of_interest message
00200  *
00201  * @return Z Position
00202  */
00203 static inline float mavlink_msg_point_of_interest_get_z(const mavlink_message_t* msg)
00204 {
00205     generic_32bit r;
00206     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0];
00207     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1];
00208     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2];
00209     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3];
00210     return (float)r.f;
00211 }
00212 
00213 /**
00214  * @brief Get field name from point_of_interest message
00215  *
00216  * @return POI name
00217  */
00218 static inline uint16_t mavlink_msg_point_of_interest_get_name(const mavlink_message_t* msg, int8_t* r_data)
00219 {
00220 
00221     memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float), 25);
00222     return 25;
00223 }
00224 
00225 /**
00226  * @brief Decode a point_of_interest message into a struct
00227  *
00228  * @param msg The message to decode
00229  * @param point_of_interest C-struct to decode the message contents into
00230  */
00231 static inline void mavlink_msg_point_of_interest_decode(const mavlink_message_t* msg, mavlink_point_of_interest_t* point_of_interest)
00232 {
00233     point_of_interest->type = mavlink_msg_point_of_interest_get_type(msg);
00234     point_of_interest->color = mavlink_msg_point_of_interest_get_color(msg);
00235     point_of_interest->coordinate_system = mavlink_msg_point_of_interest_get_coordinate_system(msg);
00236     point_of_interest->timeout = mavlink_msg_point_of_interest_get_timeout(msg);
00237     point_of_interest->x = mavlink_msg_point_of_interest_get_x(msg);
00238     point_of_interest->y = mavlink_msg_point_of_interest_get_y(msg);
00239     point_of_interest->z = mavlink_msg_point_of_interest_get_z(msg);
00240     mavlink_msg_point_of_interest_get_name(msg, point_of_interest->name);
00241 }