mavlink_msg_vision_speed_estimate.h
Go to the documentation of this file.
00001 // MESSAGE VISION_SPEED_ESTIMATE PACKING
00002 
00003 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103
00004 
00005 typedef struct __mavlink_vision_speed_estimate_t
00006 {
00007  uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/
00008  float x; /*< Global X speed*/
00009  float y; /*< Global Y speed*/
00010  float z; /*< Global Z speed*/
00011 } mavlink_vision_speed_estimate_t;
00012 
00013 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20
00014 #define MAVLINK_MSG_ID_103_LEN 20
00015 
00016 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208
00017 #define MAVLINK_MSG_ID_103_CRC 208
00018 
00019 
00020 
00021 #define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \
00022         "VISION_SPEED_ESTIMATE", \
00023         4, \
00024         {  { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \
00025          { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \
00026          { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \
00027          { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \
00028          } \
00029 }
00030 
00031 
00044 static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00045                                                        uint64_t usec, float x, float y, float z)
00046 {
00047 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00048         char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN];
00049         _mav_put_uint64_t(buf, 0, usec);
00050         _mav_put_float(buf, 8, x);
00051         _mav_put_float(buf, 12, y);
00052         _mav_put_float(buf, 16, z);
00053 
00054         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
00055 #else
00056         mavlink_vision_speed_estimate_t packet;
00057         packet.usec = usec;
00058         packet.x = x;
00059         packet.y = y;
00060         packet.z = z;
00061 
00062         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
00063 #endif
00064 
00065         msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
00066 #if MAVLINK_CRC_EXTRA
00067     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
00068 #else
00069     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
00070 #endif
00071 }
00072 
00085 static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00086                                                            mavlink_message_t* msg,
00087                                                            uint64_t usec,float x,float y,float z)
00088 {
00089 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00090         char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN];
00091         _mav_put_uint64_t(buf, 0, usec);
00092         _mav_put_float(buf, 8, x);
00093         _mav_put_float(buf, 12, y);
00094         _mav_put_float(buf, 16, z);
00095 
00096         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
00097 #else
00098         mavlink_vision_speed_estimate_t packet;
00099         packet.usec = usec;
00100         packet.x = x;
00101         packet.y = y;
00102         packet.z = z;
00103 
00104         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
00105 #endif
00106 
00107         msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
00108 #if MAVLINK_CRC_EXTRA
00109     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
00110 #else
00111     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
00112 #endif
00113 }
00114 
00123 static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate)
00124 {
00125         return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z);
00126 }
00127 
00137 static inline uint16_t mavlink_msg_vision_speed_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate)
00138 {
00139         return mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, chan, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z);
00140 }
00141 
00151 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00152 
00153 static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z)
00154 {
00155 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00156         char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN];
00157         _mav_put_uint64_t(buf, 0, usec);
00158         _mav_put_float(buf, 8, x);
00159         _mav_put_float(buf, 12, y);
00160         _mav_put_float(buf, 16, z);
00161 
00162 #if MAVLINK_CRC_EXTRA
00163     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
00164 #else
00165     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
00166 #endif
00167 #else
00168         mavlink_vision_speed_estimate_t packet;
00169         packet.usec = usec;
00170         packet.x = x;
00171         packet.y = y;
00172         packet.z = z;
00173 
00174 #if MAVLINK_CRC_EXTRA
00175     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
00176 #else
00177     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
00178 #endif
00179 #endif
00180 }
00181 
00182 #if MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00183 /*
00184   This varient of _send() can be used to save stack space by re-using
00185   memory from the receive buffer.  The caller provides a
00186   mavlink_message_t which is the size of a full mavlink message. This
00187   is usually the receive buffer for the channel, and allows a reply to an
00188   incoming message with minimum stack space usage.
00189  */
00190 static inline void mavlink_msg_vision_speed_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t usec, float x, float y, float z)
00191 {
00192 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00193         char *buf = (char *)msgbuf;
00194         _mav_put_uint64_t(buf, 0, usec);
00195         _mav_put_float(buf, 8, x);
00196         _mav_put_float(buf, 12, y);
00197         _mav_put_float(buf, 16, z);
00198 
00199 #if MAVLINK_CRC_EXTRA
00200     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
00201 #else
00202     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
00203 #endif
00204 #else
00205         mavlink_vision_speed_estimate_t *packet = (mavlink_vision_speed_estimate_t *)msgbuf;
00206         packet->usec = usec;
00207         packet->x = x;
00208         packet->y = y;
00209         packet->z = z;
00210 
00211 #if MAVLINK_CRC_EXTRA
00212     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
00213 #else
00214     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
00215 #endif
00216 #endif
00217 }
00218 #endif
00219 
00220 #endif
00221 
00222 // MESSAGE VISION_SPEED_ESTIMATE UNPACKING
00223 
00224 
00230 static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg)
00231 {
00232         return _MAV_RETURN_uint64_t(msg,  0);
00233 }
00234 
00240 static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg)
00241 {
00242         return _MAV_RETURN_float(msg,  8);
00243 }
00244 
00250 static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg)
00251 {
00252         return _MAV_RETURN_float(msg,  12);
00253 }
00254 
00260 static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg)
00261 {
00262         return _MAV_RETURN_float(msg,  16);
00263 }
00264 
00271 static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate)
00272 {
00273 #if MAVLINK_NEED_BYTE_SWAP
00274         vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg);
00275         vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg);
00276         vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg);
00277         vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg);
00278 #else
00279         memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
00280 #endif
00281 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:35