mavlink_msg_set_position_target_global_int.h
Go to the documentation of this file.
00001 // MESSAGE SET_POSITION_TARGET_GLOBAL_INT PACKING
00002 
00003 #define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT 86
00004 
00005 typedef struct __mavlink_set_position_target_global_int_t
00006 {
00007  uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/
00008  int32_t lat_int; /*< X Position in WGS84 frame in 1e7 * meters*/
00009  int32_t lon_int; /*< Y Position in WGS84 frame in 1e7 * meters*/
00010  float alt; /*< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT*/
00011  float vx; /*< X velocity in NED frame in meter / s*/
00012  float vy; /*< Y velocity in NED frame in meter / s*/
00013  float vz; /*< Z velocity in NED frame in meter / s*/
00014  float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
00015  float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
00016  float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
00017  float yaw; /*< yaw setpoint in rad*/
00018  float yaw_rate; /*< yaw rate setpoint in rad/s*/
00019  uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/
00020  uint8_t target_system; /*< System ID*/
00021  uint8_t target_component; /*< Component ID*/
00022  uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/
00023 } mavlink_set_position_target_global_int_t;
00024 
00025 #define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 53
00026 #define MAVLINK_MSG_ID_86_LEN 53
00027 
00028 #define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC 5
00029 #define MAVLINK_MSG_ID_86_CRC 5
00030 
00031 
00032 
00033 #define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \
00034         "SET_POSITION_TARGET_GLOBAL_INT", \
00035         16, \
00036         {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \
00037          { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \
00038          { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \
00039          { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \
00040          { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_global_int_t, vx) }, \
00041          { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_global_int_t, vy) }, \
00042          { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_global_int_t, vz) }, \
00043          { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \
00044          { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \
00045          { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \
00046          { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \
00047          { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \
00048          { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \
00049          { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \
00050          { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \
00051          { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \
00052          } \
00053 }
00054 
00055 
00080 static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00081                                                        uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
00082 {
00083 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00084         char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
00085         _mav_put_uint32_t(buf, 0, time_boot_ms);
00086         _mav_put_int32_t(buf, 4, lat_int);
00087         _mav_put_int32_t(buf, 8, lon_int);
00088         _mav_put_float(buf, 12, alt);
00089         _mav_put_float(buf, 16, vx);
00090         _mav_put_float(buf, 20, vy);
00091         _mav_put_float(buf, 24, vz);
00092         _mav_put_float(buf, 28, afx);
00093         _mav_put_float(buf, 32, afy);
00094         _mav_put_float(buf, 36, afz);
00095         _mav_put_float(buf, 40, yaw);
00096         _mav_put_float(buf, 44, yaw_rate);
00097         _mav_put_uint16_t(buf, 48, type_mask);
00098         _mav_put_uint8_t(buf, 50, target_system);
00099         _mav_put_uint8_t(buf, 51, target_component);
00100         _mav_put_uint8_t(buf, 52, coordinate_frame);
00101 
00102         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
00103 #else
00104         mavlink_set_position_target_global_int_t packet;
00105         packet.time_boot_ms = time_boot_ms;
00106         packet.lat_int = lat_int;
00107         packet.lon_int = lon_int;
00108         packet.alt = alt;
00109         packet.vx = vx;
00110         packet.vy = vy;
00111         packet.vz = vz;
00112         packet.afx = afx;
00113         packet.afy = afy;
00114         packet.afz = afz;
00115         packet.yaw = yaw;
00116         packet.yaw_rate = yaw_rate;
00117         packet.type_mask = type_mask;
00118         packet.target_system = target_system;
00119         packet.target_component = target_component;
00120         packet.coordinate_frame = coordinate_frame;
00121 
00122         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
00123 #endif
00124 
00125         msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT;
00126 #if MAVLINK_CRC_EXTRA
00127     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
00128 #else
00129     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
00130 #endif
00131 }
00132 
00157 static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00158                                                            mavlink_message_t* msg,
00159                                                            uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
00160 {
00161 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00162         char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
00163         _mav_put_uint32_t(buf, 0, time_boot_ms);
00164         _mav_put_int32_t(buf, 4, lat_int);
00165         _mav_put_int32_t(buf, 8, lon_int);
00166         _mav_put_float(buf, 12, alt);
00167         _mav_put_float(buf, 16, vx);
00168         _mav_put_float(buf, 20, vy);
00169         _mav_put_float(buf, 24, vz);
00170         _mav_put_float(buf, 28, afx);
00171         _mav_put_float(buf, 32, afy);
00172         _mav_put_float(buf, 36, afz);
00173         _mav_put_float(buf, 40, yaw);
00174         _mav_put_float(buf, 44, yaw_rate);
00175         _mav_put_uint16_t(buf, 48, type_mask);
00176         _mav_put_uint8_t(buf, 50, target_system);
00177         _mav_put_uint8_t(buf, 51, target_component);
00178         _mav_put_uint8_t(buf, 52, coordinate_frame);
00179 
00180         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
00181 #else
00182         mavlink_set_position_target_global_int_t packet;
00183         packet.time_boot_ms = time_boot_ms;
00184         packet.lat_int = lat_int;
00185         packet.lon_int = lon_int;
00186         packet.alt = alt;
00187         packet.vx = vx;
00188         packet.vy = vy;
00189         packet.vz = vz;
00190         packet.afx = afx;
00191         packet.afy = afy;
00192         packet.afz = afz;
00193         packet.yaw = yaw;
00194         packet.yaw_rate = yaw_rate;
00195         packet.type_mask = type_mask;
00196         packet.target_system = target_system;
00197         packet.target_component = target_component;
00198         packet.coordinate_frame = coordinate_frame;
00199 
00200         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
00201 #endif
00202 
00203         msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT;
00204 #if MAVLINK_CRC_EXTRA
00205     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
00206 #else
00207     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
00208 #endif
00209 }
00210 
00219 static inline uint16_t mavlink_msg_set_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int)
00220 {
00221         return mavlink_msg_set_position_target_global_int_pack(system_id, component_id, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate);
00222 }
00223 
00233 static inline uint16_t mavlink_msg_set_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int)
00234 {
00235         return mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, chan, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate);
00236 }
00237 
00259 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00260 
00261 static inline void mavlink_msg_set_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
00262 {
00263 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00264         char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
00265         _mav_put_uint32_t(buf, 0, time_boot_ms);
00266         _mav_put_int32_t(buf, 4, lat_int);
00267         _mav_put_int32_t(buf, 8, lon_int);
00268         _mav_put_float(buf, 12, alt);
00269         _mav_put_float(buf, 16, vx);
00270         _mav_put_float(buf, 20, vy);
00271         _mav_put_float(buf, 24, vz);
00272         _mav_put_float(buf, 28, afx);
00273         _mav_put_float(buf, 32, afy);
00274         _mav_put_float(buf, 36, afz);
00275         _mav_put_float(buf, 40, yaw);
00276         _mav_put_float(buf, 44, yaw_rate);
00277         _mav_put_uint16_t(buf, 48, type_mask);
00278         _mav_put_uint8_t(buf, 50, target_system);
00279         _mav_put_uint8_t(buf, 51, target_component);
00280         _mav_put_uint8_t(buf, 52, coordinate_frame);
00281 
00282 #if MAVLINK_CRC_EXTRA
00283     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
00284 #else
00285     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
00286 #endif
00287 #else
00288         mavlink_set_position_target_global_int_t packet;
00289         packet.time_boot_ms = time_boot_ms;
00290         packet.lat_int = lat_int;
00291         packet.lon_int = lon_int;
00292         packet.alt = alt;
00293         packet.vx = vx;
00294         packet.vy = vy;
00295         packet.vz = vz;
00296         packet.afx = afx;
00297         packet.afy = afy;
00298         packet.afz = afz;
00299         packet.yaw = yaw;
00300         packet.yaw_rate = yaw_rate;
00301         packet.type_mask = type_mask;
00302         packet.target_system = target_system;
00303         packet.target_component = target_component;
00304         packet.coordinate_frame = coordinate_frame;
00305 
00306 #if MAVLINK_CRC_EXTRA
00307     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
00308 #else
00309     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
00310 #endif
00311 #endif
00312 }
00313 
00314 #if MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00315 /*
00316   This varient of _send() can be used to save stack space by re-using
00317   memory from the receive buffer.  The caller provides a
00318   mavlink_message_t which is the size of a full mavlink message. This
00319   is usually the receive buffer for the channel, and allows a reply to an
00320   incoming message with minimum stack space usage.
00321  */
00322 static inline void mavlink_msg_set_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
00323 {
00324 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00325         char *buf = (char *)msgbuf;
00326         _mav_put_uint32_t(buf, 0, time_boot_ms);
00327         _mav_put_int32_t(buf, 4, lat_int);
00328         _mav_put_int32_t(buf, 8, lon_int);
00329         _mav_put_float(buf, 12, alt);
00330         _mav_put_float(buf, 16, vx);
00331         _mav_put_float(buf, 20, vy);
00332         _mav_put_float(buf, 24, vz);
00333         _mav_put_float(buf, 28, afx);
00334         _mav_put_float(buf, 32, afy);
00335         _mav_put_float(buf, 36, afz);
00336         _mav_put_float(buf, 40, yaw);
00337         _mav_put_float(buf, 44, yaw_rate);
00338         _mav_put_uint16_t(buf, 48, type_mask);
00339         _mav_put_uint8_t(buf, 50, target_system);
00340         _mav_put_uint8_t(buf, 51, target_component);
00341         _mav_put_uint8_t(buf, 52, coordinate_frame);
00342 
00343 #if MAVLINK_CRC_EXTRA
00344     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
00345 #else
00346     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
00347 #endif
00348 #else
00349         mavlink_set_position_target_global_int_t *packet = (mavlink_set_position_target_global_int_t *)msgbuf;
00350         packet->time_boot_ms = time_boot_ms;
00351         packet->lat_int = lat_int;
00352         packet->lon_int = lon_int;
00353         packet->alt = alt;
00354         packet->vx = vx;
00355         packet->vy = vy;
00356         packet->vz = vz;
00357         packet->afx = afx;
00358         packet->afy = afy;
00359         packet->afz = afz;
00360         packet->yaw = yaw;
00361         packet->yaw_rate = yaw_rate;
00362         packet->type_mask = type_mask;
00363         packet->target_system = target_system;
00364         packet->target_component = target_component;
00365         packet->coordinate_frame = coordinate_frame;
00366 
00367 #if MAVLINK_CRC_EXTRA
00368     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
00369 #else
00370     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
00371 #endif
00372 #endif
00373 }
00374 #endif
00375 
00376 #endif
00377 
00378 // MESSAGE SET_POSITION_TARGET_GLOBAL_INT UNPACKING
00379 
00380 
00386 static inline uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg)
00387 {
00388         return _MAV_RETURN_uint32_t(msg,  0);
00389 }
00390 
00396 static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_system(const mavlink_message_t* msg)
00397 {
00398         return _MAV_RETURN_uint8_t(msg,  50);
00399 }
00400 
00406 static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_component(const mavlink_message_t* msg)
00407 {
00408         return _MAV_RETURN_uint8_t(msg,  51);
00409 }
00410 
00416 static inline uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg)
00417 {
00418         return _MAV_RETURN_uint8_t(msg,  52);
00419 }
00420 
00426 static inline uint16_t mavlink_msg_set_position_target_global_int_get_type_mask(const mavlink_message_t* msg)
00427 {
00428         return _MAV_RETURN_uint16_t(msg,  48);
00429 }
00430 
00436 static inline int32_t mavlink_msg_set_position_target_global_int_get_lat_int(const mavlink_message_t* msg)
00437 {
00438         return _MAV_RETURN_int32_t(msg,  4);
00439 }
00440 
00446 static inline int32_t mavlink_msg_set_position_target_global_int_get_lon_int(const mavlink_message_t* msg)
00447 {
00448         return _MAV_RETURN_int32_t(msg,  8);
00449 }
00450 
00456 static inline float mavlink_msg_set_position_target_global_int_get_alt(const mavlink_message_t* msg)
00457 {
00458         return _MAV_RETURN_float(msg,  12);
00459 }
00460 
00466 static inline float mavlink_msg_set_position_target_global_int_get_vx(const mavlink_message_t* msg)
00467 {
00468         return _MAV_RETURN_float(msg,  16);
00469 }
00470 
00476 static inline float mavlink_msg_set_position_target_global_int_get_vy(const mavlink_message_t* msg)
00477 {
00478         return _MAV_RETURN_float(msg,  20);
00479 }
00480 
00486 static inline float mavlink_msg_set_position_target_global_int_get_vz(const mavlink_message_t* msg)
00487 {
00488         return _MAV_RETURN_float(msg,  24);
00489 }
00490 
00496 static inline float mavlink_msg_set_position_target_global_int_get_afx(const mavlink_message_t* msg)
00497 {
00498         return _MAV_RETURN_float(msg,  28);
00499 }
00500 
00506 static inline float mavlink_msg_set_position_target_global_int_get_afy(const mavlink_message_t* msg)
00507 {
00508         return _MAV_RETURN_float(msg,  32);
00509 }
00510 
00516 static inline float mavlink_msg_set_position_target_global_int_get_afz(const mavlink_message_t* msg)
00517 {
00518         return _MAV_RETURN_float(msg,  36);
00519 }
00520 
00526 static inline float mavlink_msg_set_position_target_global_int_get_yaw(const mavlink_message_t* msg)
00527 {
00528         return _MAV_RETURN_float(msg,  40);
00529 }
00530 
00536 static inline float mavlink_msg_set_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg)
00537 {
00538         return _MAV_RETURN_float(msg,  44);
00539 }
00540 
00547 static inline void mavlink_msg_set_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_set_position_target_global_int_t* set_position_target_global_int)
00548 {
00549 #if MAVLINK_NEED_BYTE_SWAP
00550         set_position_target_global_int->time_boot_ms = mavlink_msg_set_position_target_global_int_get_time_boot_ms(msg);
00551         set_position_target_global_int->lat_int = mavlink_msg_set_position_target_global_int_get_lat_int(msg);
00552         set_position_target_global_int->lon_int = mavlink_msg_set_position_target_global_int_get_lon_int(msg);
00553         set_position_target_global_int->alt = mavlink_msg_set_position_target_global_int_get_alt(msg);
00554         set_position_target_global_int->vx = mavlink_msg_set_position_target_global_int_get_vx(msg);
00555         set_position_target_global_int->vy = mavlink_msg_set_position_target_global_int_get_vy(msg);
00556         set_position_target_global_int->vz = mavlink_msg_set_position_target_global_int_get_vz(msg);
00557         set_position_target_global_int->afx = mavlink_msg_set_position_target_global_int_get_afx(msg);
00558         set_position_target_global_int->afy = mavlink_msg_set_position_target_global_int_get_afy(msg);
00559         set_position_target_global_int->afz = mavlink_msg_set_position_target_global_int_get_afz(msg);
00560         set_position_target_global_int->yaw = mavlink_msg_set_position_target_global_int_get_yaw(msg);
00561         set_position_target_global_int->yaw_rate = mavlink_msg_set_position_target_global_int_get_yaw_rate(msg);
00562         set_position_target_global_int->type_mask = mavlink_msg_set_position_target_global_int_get_type_mask(msg);
00563         set_position_target_global_int->target_system = mavlink_msg_set_position_target_global_int_get_target_system(msg);
00564         set_position_target_global_int->target_component = mavlink_msg_set_position_target_global_int_get_target_component(msg);
00565         set_position_target_global_int->coordinate_frame = mavlink_msg_set_position_target_global_int_get_coordinate_frame(msg);
00566 #else
00567         memcpy(set_position_target_global_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
00568 #endif
00569 }


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