00001
00002
00003 #define MAVLINK_MSG_ID_DEBUG_VECT 250
00004
00005 typedef struct __mavlink_debug_vect_t
00006 {
00007 uint64_t time_usec;
00008 float x;
00009 float y;
00010 float z;
00011 char name[10];
00012 } mavlink_debug_vect_t;
00013
00014 #define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
00015 #define MAVLINK_MSG_ID_250_LEN 30
00016
00017 #define MAVLINK_MSG_ID_DEBUG_VECT_CRC 49
00018 #define MAVLINK_MSG_ID_250_CRC 49
00019
00020 #define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10
00021
00022 #define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
00023 "DEBUG_VECT", \
00024 5, \
00025 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \
00026 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \
00027 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \
00028 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \
00029 { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \
00030 } \
00031 }
00032
00033
00047 static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00048 const char *name, uint64_t time_usec, float x, float y, float z)
00049 {
00050 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00051 char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN];
00052 _mav_put_uint64_t(buf, 0, time_usec);
00053 _mav_put_float(buf, 8, x);
00054 _mav_put_float(buf, 12, y);
00055 _mav_put_float(buf, 16, z);
00056 _mav_put_char_array(buf, 20, name, 10);
00057 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
00058 #else
00059 mavlink_debug_vect_t packet;
00060 packet.time_usec = time_usec;
00061 packet.x = x;
00062 packet.y = y;
00063 packet.z = z;
00064 mav_array_memcpy(packet.name, name, sizeof(char)*10);
00065 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
00066 #endif
00067
00068 msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
00069 #if MAVLINK_CRC_EXTRA
00070 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
00071 #else
00072 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
00073 #endif
00074 }
00075
00089 static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00090 mavlink_message_t* msg,
00091 const char *name,uint64_t time_usec,float x,float y,float z)
00092 {
00093 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00094 char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN];
00095 _mav_put_uint64_t(buf, 0, time_usec);
00096 _mav_put_float(buf, 8, x);
00097 _mav_put_float(buf, 12, y);
00098 _mav_put_float(buf, 16, z);
00099 _mav_put_char_array(buf, 20, name, 10);
00100 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
00101 #else
00102 mavlink_debug_vect_t packet;
00103 packet.time_usec = time_usec;
00104 packet.x = x;
00105 packet.y = y;
00106 packet.z = z;
00107 mav_array_memcpy(packet.name, name, sizeof(char)*10);
00108 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
00109 #endif
00110
00111 msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
00112 #if MAVLINK_CRC_EXTRA
00113 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
00114 #else
00115 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
00116 #endif
00117 }
00118
00127 static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
00128 {
00129 return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z);
00130 }
00131
00141 static inline uint16_t mavlink_msg_debug_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
00142 {
00143 return mavlink_msg_debug_vect_pack_chan(system_id, component_id, chan, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z);
00144 }
00145
00156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00157
00158 static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z)
00159 {
00160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00161 char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN];
00162 _mav_put_uint64_t(buf, 0, time_usec);
00163 _mav_put_float(buf, 8, x);
00164 _mav_put_float(buf, 12, y);
00165 _mav_put_float(buf, 16, z);
00166 _mav_put_char_array(buf, 20, name, 10);
00167 #if MAVLINK_CRC_EXTRA
00168 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
00169 #else
00170 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
00171 #endif
00172 #else
00173 mavlink_debug_vect_t packet;
00174 packet.time_usec = time_usec;
00175 packet.x = x;
00176 packet.y = y;
00177 packet.z = z;
00178 mav_array_memcpy(packet.name, name, sizeof(char)*10);
00179 #if MAVLINK_CRC_EXTRA
00180 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
00181 #else
00182 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
00183 #endif
00184 #endif
00185 }
00186
00187 #if MAVLINK_MSG_ID_DEBUG_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00188
00189
00190
00191
00192
00193
00194
00195 static inline void mavlink_msg_debug_vect_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z)
00196 {
00197 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00198 char *buf = (char *)msgbuf;
00199 _mav_put_uint64_t(buf, 0, time_usec);
00200 _mav_put_float(buf, 8, x);
00201 _mav_put_float(buf, 12, y);
00202 _mav_put_float(buf, 16, z);
00203 _mav_put_char_array(buf, 20, name, 10);
00204 #if MAVLINK_CRC_EXTRA
00205 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
00206 #else
00207 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
00208 #endif
00209 #else
00210 mavlink_debug_vect_t *packet = (mavlink_debug_vect_t *)msgbuf;
00211 packet->time_usec = time_usec;
00212 packet->x = x;
00213 packet->y = y;
00214 packet->z = z;
00215 mav_array_memcpy(packet->name, name, sizeof(char)*10);
00216 #if MAVLINK_CRC_EXTRA
00217 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
00218 #else
00219 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
00220 #endif
00221 #endif
00222 }
00223 #endif
00224
00225 #endif
00226
00227
00228
00229
00235 static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name)
00236 {
00237 return _MAV_RETURN_char_array(msg, name, 10, 20);
00238 }
00239
00245 static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg)
00246 {
00247 return _MAV_RETURN_uint64_t(msg, 0);
00248 }
00249
00255 static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg)
00256 {
00257 return _MAV_RETURN_float(msg, 8);
00258 }
00259
00265 static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg)
00266 {
00267 return _MAV_RETURN_float(msg, 12);
00268 }
00269
00275 static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
00276 {
00277 return _MAV_RETURN_float(msg, 16);
00278 }
00279
00286 static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect)
00287 {
00288 #if MAVLINK_NEED_BYTE_SWAP
00289 debug_vect->time_usec = mavlink_msg_debug_vect_get_time_usec(msg);
00290 debug_vect->x = mavlink_msg_debug_vect_get_x(msg);
00291 debug_vect->y = mavlink_msg_debug_vect_get_y(msg);
00292 debug_vect->z = mavlink_msg_debug_vect_get_z(msg);
00293 mavlink_msg_debug_vect_get_name(msg, debug_vect->name);
00294 #else
00295 memcpy(debug_vect, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DEBUG_VECT_LEN);
00296 #endif
00297 }