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

mavlink_msg_brief_feature.h

00001 // MESSAGE BRIEF_FEATURE PACKING
00002 
00003 #define MAVLINK_MSG_ID_BRIEF_FEATURE 172
00004 
00005 typedef struct __mavlink_brief_feature_t 
00006 {
00007     float x; ///< x position in m
00008     float y; ///< y position in m
00009     float z; ///< z position in m
00010     uint8_t orientation_assignment; ///< Orientation assignment 0: false, 1:true
00011     uint16_t size; ///< Size in pixels
00012     uint16_t orientation; ///< Orientation
00013     uint8_t descriptor[32]; ///< Descriptor
00014     float response; ///< Harris operator response at this location
00015 
00016 } mavlink_brief_feature_t;
00017 
00018 #define MAVLINK_MSG_BRIEF_FEATURE_FIELD_DESCRIPTOR_LEN 32
00019 
00020 
00021 /**
00022  * @brief Pack a brief_feature 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 x x position in m
00028  * @param y y position in m
00029  * @param z z position in m
00030  * @param orientation_assignment Orientation assignment 0: false, 1:true
00031  * @param size Size in pixels
00032  * @param orientation Orientation
00033  * @param descriptor Descriptor
00034  * @param response Harris operator response at this location
00035  * @return length of the message in bytes (excluding serial stream start sign)
00036  */
00037 static inline uint16_t mavlink_msg_brief_feature_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t* descriptor, float response)
00038 {
00039     uint16_t i = 0;
00040     msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE;
00041 
00042     i += put_float_by_index(x, i, msg->payload); // x position in m
00043     i += put_float_by_index(y, i, msg->payload); // y position in m
00044     i += put_float_by_index(z, i, msg->payload); // z position in m
00045     i += put_uint8_t_by_index(orientation_assignment, i, msg->payload); // Orientation assignment 0: false, 1:true
00046     i += put_uint16_t_by_index(size, i, msg->payload); // Size in pixels
00047     i += put_uint16_t_by_index(orientation, i, msg->payload); // Orientation
00048     i += put_array_by_index((const int8_t*)descriptor, sizeof(uint8_t)*32, i, msg->payload); // Descriptor
00049     i += put_float_by_index(response, i, msg->payload); // Harris operator response at this location
00050 
00051     return mavlink_finalize_message(msg, system_id, component_id, i);
00052 }
00053 
00054 /**
00055  * @brief Pack a brief_feature 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 x x position in m
00061  * @param y y position in m
00062  * @param z z position in m
00063  * @param orientation_assignment Orientation assignment 0: false, 1:true
00064  * @param size Size in pixels
00065  * @param orientation Orientation
00066  * @param descriptor Descriptor
00067  * @param response Harris operator response at this location
00068  * @return length of the message in bytes (excluding serial stream start sign)
00069  */
00070 static inline uint16_t mavlink_msg_brief_feature_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t* descriptor, float response)
00071 {
00072     uint16_t i = 0;
00073     msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE;
00074 
00075     i += put_float_by_index(x, i, msg->payload); // x position in m
00076     i += put_float_by_index(y, i, msg->payload); // y position in m
00077     i += put_float_by_index(z, i, msg->payload); // z position in m
00078     i += put_uint8_t_by_index(orientation_assignment, i, msg->payload); // Orientation assignment 0: false, 1:true
00079     i += put_uint16_t_by_index(size, i, msg->payload); // Size in pixels
00080     i += put_uint16_t_by_index(orientation, i, msg->payload); // Orientation
00081     i += put_array_by_index((const int8_t*)descriptor, sizeof(uint8_t)*32, i, msg->payload); // Descriptor
00082     i += put_float_by_index(response, i, msg->payload); // Harris operator response at this location
00083 
00084     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00085 }
00086 
00087 /**
00088  * @brief Encode a brief_feature 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 brief_feature C-struct to read the message contents from
00094  */
00095 static inline uint16_t mavlink_msg_brief_feature_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_brief_feature_t* brief_feature)
00096 {
00097     return mavlink_msg_brief_feature_pack(system_id, component_id, msg, brief_feature->x, brief_feature->y, brief_feature->z, brief_feature->orientation_assignment, brief_feature->size, brief_feature->orientation, brief_feature->descriptor, brief_feature->response);
00098 }
00099 
00100 /**
00101  * @brief Send a brief_feature message
00102  * @param chan MAVLink channel to send the message
00103  *
00104  * @param x x position in m
00105  * @param y y position in m
00106  * @param z z position in m
00107  * @param orientation_assignment Orientation assignment 0: false, 1:true
00108  * @param size Size in pixels
00109  * @param orientation Orientation
00110  * @param descriptor Descriptor
00111  * @param response Harris operator response at this location
00112  */
00113 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00114 
00115 static inline void mavlink_msg_brief_feature_send(mavlink_channel_t chan, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t* descriptor, float response)
00116 {
00117     mavlink_message_t msg;
00118     mavlink_msg_brief_feature_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, x, y, z, orientation_assignment, size, orientation, descriptor, response);
00119     mavlink_send_uart(chan, &msg);
00120 }
00121 
00122 #endif
00123 // MESSAGE BRIEF_FEATURE UNPACKING
00124 
00125 /**
00126  * @brief Get field x from brief_feature message
00127  *
00128  * @return x position in m
00129  */
00130 static inline float mavlink_msg_brief_feature_get_x(const mavlink_message_t* msg)
00131 {
00132     generic_32bit r;
00133     r.b[3] = (msg->payload)[0];
00134     r.b[2] = (msg->payload)[1];
00135     r.b[1] = (msg->payload)[2];
00136     r.b[0] = (msg->payload)[3];
00137     return (float)r.f;
00138 }
00139 
00140 /**
00141  * @brief Get field y from brief_feature message
00142  *
00143  * @return y position in m
00144  */
00145 static inline float mavlink_msg_brief_feature_get_y(const mavlink_message_t* msg)
00146 {
00147     generic_32bit r;
00148     r.b[3] = (msg->payload+sizeof(float))[0];
00149     r.b[2] = (msg->payload+sizeof(float))[1];
00150     r.b[1] = (msg->payload+sizeof(float))[2];
00151     r.b[0] = (msg->payload+sizeof(float))[3];
00152     return (float)r.f;
00153 }
00154 
00155 /**
00156  * @brief Get field z from brief_feature message
00157  *
00158  * @return z position in m
00159  */
00160 static inline float mavlink_msg_brief_feature_get_z(const mavlink_message_t* msg)
00161 {
00162     generic_32bit r;
00163     r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
00164     r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
00165     r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
00166     r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
00167     return (float)r.f;
00168 }
00169 
00170 /**
00171  * @brief Get field orientation_assignment from brief_feature message
00172  *
00173  * @return Orientation assignment 0: false, 1:true
00174  */
00175 static inline uint8_t mavlink_msg_brief_feature_get_orientation_assignment(const mavlink_message_t* msg)
00176 {
00177     return (uint8_t)(msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
00178 }
00179 
00180 /**
00181  * @brief Get field size from brief_feature message
00182  *
00183  * @return Size in pixels
00184  */
00185 static inline uint16_t mavlink_msg_brief_feature_get_size(const mavlink_message_t* msg)
00186 {
00187     generic_16bit r;
00188     r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0];
00189     r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[1];
00190     return (uint16_t)r.s;
00191 }
00192 
00193 /**
00194  * @brief Get field orientation from brief_feature message
00195  *
00196  * @return Orientation
00197  */
00198 static inline uint16_t mavlink_msg_brief_feature_get_orientation(const mavlink_message_t* msg)
00199 {
00200     generic_16bit r;
00201     r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t))[0];
00202     r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t))[1];
00203     return (uint16_t)r.s;
00204 }
00205 
00206 /**
00207  * @brief Get field descriptor from brief_feature message
00208  *
00209  * @return Descriptor
00210  */
00211 static inline uint16_t mavlink_msg_brief_feature_get_descriptor(const mavlink_message_t* msg, uint8_t* r_data)
00212 {
00213 
00214     memcpy(r_data, msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t), sizeof(uint8_t)*32);
00215     return sizeof(uint8_t)*32;
00216 }
00217 
00218 /**
00219  * @brief Get field response from brief_feature message
00220  *
00221  * @return Harris operator response at this location
00222  */
00223 static inline float mavlink_msg_brief_feature_get_response(const mavlink_message_t* msg)
00224 {
00225     generic_32bit r;
00226     r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)*32)[0];
00227     r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)*32)[1];
00228     r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)*32)[2];
00229     r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)*32)[3];
00230     return (float)r.f;
00231 }
00232 
00233 /**
00234  * @brief Decode a brief_feature message into a struct
00235  *
00236  * @param msg The message to decode
00237  * @param brief_feature C-struct to decode the message contents into
00238  */
00239 static inline void mavlink_msg_brief_feature_decode(const mavlink_message_t* msg, mavlink_brief_feature_t* brief_feature)
00240 {
00241     brief_feature->x = mavlink_msg_brief_feature_get_x(msg);
00242     brief_feature->y = mavlink_msg_brief_feature_get_y(msg);
00243     brief_feature->z = mavlink_msg_brief_feature_get_z(msg);
00244     brief_feature->orientation_assignment = mavlink_msg_brief_feature_get_orientation_assignment(msg);
00245     brief_feature->size = mavlink_msg_brief_feature_get_size(msg);
00246     brief_feature->orientation = mavlink_msg_brief_feature_get_orientation(msg);
00247     mavlink_msg_brief_feature_get_descriptor(msg, brief_feature->descriptor);
00248     brief_feature->response = mavlink_msg_brief_feature_get_response(msg);
00249 }