mavlink_msg_mission_item_int.h
Go to the documentation of this file.
00001 // MESSAGE MISSION_ITEM_INT PACKING
00002 
00003 #define MAVLINK_MSG_ID_MISSION_ITEM_INT 73
00004 
00005 typedef struct __mavlink_mission_item_int_t
00006 {
00007  float param1; /*< PARAM1, see MAV_CMD enum*/
00008  float param2; /*< PARAM2, see MAV_CMD enum*/
00009  float param3; /*< PARAM3, see MAV_CMD enum*/
00010  float param4; /*< PARAM4, see MAV_CMD enum*/
00011  int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/
00012  int32_t y; /*< PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7*/
00013  float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/
00014  uint16_t seq; /*< Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).*/
00015  uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/
00016  uint8_t target_system; /*< System ID*/
00017  uint8_t target_component; /*< Component ID*/
00018  uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/
00019  uint8_t current; /*< false:0, true:1*/
00020  uint8_t autocontinue; /*< autocontinue to next wp*/
00021 } mavlink_mission_item_int_t;
00022 
00023 #define MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN 37
00024 #define MAVLINK_MSG_ID_73_LEN 37
00025 
00026 #define MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC 38
00027 #define MAVLINK_MSG_ID_73_CRC 38
00028 
00029 
00030 
00031 #define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \
00032         "MISSION_ITEM_INT", \
00033         14, \
00034         {  { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \
00035          { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \
00036          { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \
00037          { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \
00038          { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \
00039          { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \
00040          { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \
00041          { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \
00042          { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \
00043          { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \
00044          { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \
00045          { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \
00046          { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \
00047          { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \
00048          } \
00049 }
00050 
00051 
00074 static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00075                                                        uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
00076 {
00077 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00078         char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
00079         _mav_put_float(buf, 0, param1);
00080         _mav_put_float(buf, 4, param2);
00081         _mav_put_float(buf, 8, param3);
00082         _mav_put_float(buf, 12, param4);
00083         _mav_put_int32_t(buf, 16, x);
00084         _mav_put_int32_t(buf, 20, y);
00085         _mav_put_float(buf, 24, z);
00086         _mav_put_uint16_t(buf, 28, seq);
00087         _mav_put_uint16_t(buf, 30, command);
00088         _mav_put_uint8_t(buf, 32, target_system);
00089         _mav_put_uint8_t(buf, 33, target_component);
00090         _mav_put_uint8_t(buf, 34, frame);
00091         _mav_put_uint8_t(buf, 35, current);
00092         _mav_put_uint8_t(buf, 36, autocontinue);
00093 
00094         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
00095 #else
00096         mavlink_mission_item_int_t packet;
00097         packet.param1 = param1;
00098         packet.param2 = param2;
00099         packet.param3 = param3;
00100         packet.param4 = param4;
00101         packet.x = x;
00102         packet.y = y;
00103         packet.z = z;
00104         packet.seq = seq;
00105         packet.command = command;
00106         packet.target_system = target_system;
00107         packet.target_component = target_component;
00108         packet.frame = frame;
00109         packet.current = current;
00110         packet.autocontinue = autocontinue;
00111 
00112         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
00113 #endif
00114 
00115         msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT;
00116 #if MAVLINK_CRC_EXTRA
00117     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
00118 #else
00119     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
00120 #endif
00121 }
00122 
00145 static inline uint16_t mavlink_msg_mission_item_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00146                                                            mavlink_message_t* msg,
00147                                                            uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,int32_t x,int32_t y,float z)
00148 {
00149 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00150         char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
00151         _mav_put_float(buf, 0, param1);
00152         _mav_put_float(buf, 4, param2);
00153         _mav_put_float(buf, 8, param3);
00154         _mav_put_float(buf, 12, param4);
00155         _mav_put_int32_t(buf, 16, x);
00156         _mav_put_int32_t(buf, 20, y);
00157         _mav_put_float(buf, 24, z);
00158         _mav_put_uint16_t(buf, 28, seq);
00159         _mav_put_uint16_t(buf, 30, command);
00160         _mav_put_uint8_t(buf, 32, target_system);
00161         _mav_put_uint8_t(buf, 33, target_component);
00162         _mav_put_uint8_t(buf, 34, frame);
00163         _mav_put_uint8_t(buf, 35, current);
00164         _mav_put_uint8_t(buf, 36, autocontinue);
00165 
00166         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
00167 #else
00168         mavlink_mission_item_int_t packet;
00169         packet.param1 = param1;
00170         packet.param2 = param2;
00171         packet.param3 = param3;
00172         packet.param4 = param4;
00173         packet.x = x;
00174         packet.y = y;
00175         packet.z = z;
00176         packet.seq = seq;
00177         packet.command = command;
00178         packet.target_system = target_system;
00179         packet.target_component = target_component;
00180         packet.frame = frame;
00181         packet.current = current;
00182         packet.autocontinue = autocontinue;
00183 
00184         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
00185 #endif
00186 
00187         msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT;
00188 #if MAVLINK_CRC_EXTRA
00189     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
00190 #else
00191     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
00192 #endif
00193 }
00194 
00203 static inline uint16_t mavlink_msg_mission_item_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int)
00204 {
00205         return mavlink_msg_mission_item_int_pack(system_id, component_id, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z);
00206 }
00207 
00217 static inline uint16_t mavlink_msg_mission_item_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int)
00218 {
00219         return mavlink_msg_mission_item_int_pack_chan(system_id, component_id, chan, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z);
00220 }
00221 
00241 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00242 
00243 static inline void mavlink_msg_mission_item_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
00244 {
00245 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00246         char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
00247         _mav_put_float(buf, 0, param1);
00248         _mav_put_float(buf, 4, param2);
00249         _mav_put_float(buf, 8, param3);
00250         _mav_put_float(buf, 12, param4);
00251         _mav_put_int32_t(buf, 16, x);
00252         _mav_put_int32_t(buf, 20, y);
00253         _mav_put_float(buf, 24, z);
00254         _mav_put_uint16_t(buf, 28, seq);
00255         _mav_put_uint16_t(buf, 30, command);
00256         _mav_put_uint8_t(buf, 32, target_system);
00257         _mav_put_uint8_t(buf, 33, target_component);
00258         _mav_put_uint8_t(buf, 34, frame);
00259         _mav_put_uint8_t(buf, 35, current);
00260         _mav_put_uint8_t(buf, 36, autocontinue);
00261 
00262 #if MAVLINK_CRC_EXTRA
00263     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
00264 #else
00265     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
00266 #endif
00267 #else
00268         mavlink_mission_item_int_t packet;
00269         packet.param1 = param1;
00270         packet.param2 = param2;
00271         packet.param3 = param3;
00272         packet.param4 = param4;
00273         packet.x = x;
00274         packet.y = y;
00275         packet.z = z;
00276         packet.seq = seq;
00277         packet.command = command;
00278         packet.target_system = target_system;
00279         packet.target_component = target_component;
00280         packet.frame = frame;
00281         packet.current = current;
00282         packet.autocontinue = autocontinue;
00283 
00284 #if MAVLINK_CRC_EXTRA
00285     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
00286 #else
00287     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
00288 #endif
00289 #endif
00290 }
00291 
00292 #if MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00293 /*
00294   This varient of _send() can be used to save stack space by re-using
00295   memory from the receive buffer.  The caller provides a
00296   mavlink_message_t which is the size of a full mavlink message. This
00297   is usually the receive buffer for the channel, and allows a reply to an
00298   incoming message with minimum stack space usage.
00299  */
00300 static inline void mavlink_msg_mission_item_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
00301 {
00302 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00303         char *buf = (char *)msgbuf;
00304         _mav_put_float(buf, 0, param1);
00305         _mav_put_float(buf, 4, param2);
00306         _mav_put_float(buf, 8, param3);
00307         _mav_put_float(buf, 12, param4);
00308         _mav_put_int32_t(buf, 16, x);
00309         _mav_put_int32_t(buf, 20, y);
00310         _mav_put_float(buf, 24, z);
00311         _mav_put_uint16_t(buf, 28, seq);
00312         _mav_put_uint16_t(buf, 30, command);
00313         _mav_put_uint8_t(buf, 32, target_system);
00314         _mav_put_uint8_t(buf, 33, target_component);
00315         _mav_put_uint8_t(buf, 34, frame);
00316         _mav_put_uint8_t(buf, 35, current);
00317         _mav_put_uint8_t(buf, 36, autocontinue);
00318 
00319 #if MAVLINK_CRC_EXTRA
00320     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
00321 #else
00322     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
00323 #endif
00324 #else
00325         mavlink_mission_item_int_t *packet = (mavlink_mission_item_int_t *)msgbuf;
00326         packet->param1 = param1;
00327         packet->param2 = param2;
00328         packet->param3 = param3;
00329         packet->param4 = param4;
00330         packet->x = x;
00331         packet->y = y;
00332         packet->z = z;
00333         packet->seq = seq;
00334         packet->command = command;
00335         packet->target_system = target_system;
00336         packet->target_component = target_component;
00337         packet->frame = frame;
00338         packet->current = current;
00339         packet->autocontinue = autocontinue;
00340 
00341 #if MAVLINK_CRC_EXTRA
00342     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
00343 #else
00344     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
00345 #endif
00346 #endif
00347 }
00348 #endif
00349 
00350 #endif
00351 
00352 // MESSAGE MISSION_ITEM_INT UNPACKING
00353 
00354 
00360 static inline uint8_t mavlink_msg_mission_item_int_get_target_system(const mavlink_message_t* msg)
00361 {
00362         return _MAV_RETURN_uint8_t(msg,  32);
00363 }
00364 
00370 static inline uint8_t mavlink_msg_mission_item_int_get_target_component(const mavlink_message_t* msg)
00371 {
00372         return _MAV_RETURN_uint8_t(msg,  33);
00373 }
00374 
00380 static inline uint16_t mavlink_msg_mission_item_int_get_seq(const mavlink_message_t* msg)
00381 {
00382         return _MAV_RETURN_uint16_t(msg,  28);
00383 }
00384 
00390 static inline uint8_t mavlink_msg_mission_item_int_get_frame(const mavlink_message_t* msg)
00391 {
00392         return _MAV_RETURN_uint8_t(msg,  34);
00393 }
00394 
00400 static inline uint16_t mavlink_msg_mission_item_int_get_command(const mavlink_message_t* msg)
00401 {
00402         return _MAV_RETURN_uint16_t(msg,  30);
00403 }
00404 
00410 static inline uint8_t mavlink_msg_mission_item_int_get_current(const mavlink_message_t* msg)
00411 {
00412         return _MAV_RETURN_uint8_t(msg,  35);
00413 }
00414 
00420 static inline uint8_t mavlink_msg_mission_item_int_get_autocontinue(const mavlink_message_t* msg)
00421 {
00422         return _MAV_RETURN_uint8_t(msg,  36);
00423 }
00424 
00430 static inline float mavlink_msg_mission_item_int_get_param1(const mavlink_message_t* msg)
00431 {
00432         return _MAV_RETURN_float(msg,  0);
00433 }
00434 
00440 static inline float mavlink_msg_mission_item_int_get_param2(const mavlink_message_t* msg)
00441 {
00442         return _MAV_RETURN_float(msg,  4);
00443 }
00444 
00450 static inline float mavlink_msg_mission_item_int_get_param3(const mavlink_message_t* msg)
00451 {
00452         return _MAV_RETURN_float(msg,  8);
00453 }
00454 
00460 static inline float mavlink_msg_mission_item_int_get_param4(const mavlink_message_t* msg)
00461 {
00462         return _MAV_RETURN_float(msg,  12);
00463 }
00464 
00470 static inline int32_t mavlink_msg_mission_item_int_get_x(const mavlink_message_t* msg)
00471 {
00472         return _MAV_RETURN_int32_t(msg,  16);
00473 }
00474 
00480 static inline int32_t mavlink_msg_mission_item_int_get_y(const mavlink_message_t* msg)
00481 {
00482         return _MAV_RETURN_int32_t(msg,  20);
00483 }
00484 
00490 static inline float mavlink_msg_mission_item_int_get_z(const mavlink_message_t* msg)
00491 {
00492         return _MAV_RETURN_float(msg,  24);
00493 }
00494 
00501 static inline void mavlink_msg_mission_item_int_decode(const mavlink_message_t* msg, mavlink_mission_item_int_t* mission_item_int)
00502 {
00503 #if MAVLINK_NEED_BYTE_SWAP
00504         mission_item_int->param1 = mavlink_msg_mission_item_int_get_param1(msg);
00505         mission_item_int->param2 = mavlink_msg_mission_item_int_get_param2(msg);
00506         mission_item_int->param3 = mavlink_msg_mission_item_int_get_param3(msg);
00507         mission_item_int->param4 = mavlink_msg_mission_item_int_get_param4(msg);
00508         mission_item_int->x = mavlink_msg_mission_item_int_get_x(msg);
00509         mission_item_int->y = mavlink_msg_mission_item_int_get_y(msg);
00510         mission_item_int->z = mavlink_msg_mission_item_int_get_z(msg);
00511         mission_item_int->seq = mavlink_msg_mission_item_int_get_seq(msg);
00512         mission_item_int->command = mavlink_msg_mission_item_int_get_command(msg);
00513         mission_item_int->target_system = mavlink_msg_mission_item_int_get_target_system(msg);
00514         mission_item_int->target_component = mavlink_msg_mission_item_int_get_target_component(msg);
00515         mission_item_int->frame = mavlink_msg_mission_item_int_get_frame(msg);
00516         mission_item_int->current = mavlink_msg_mission_item_int_get_current(msg);
00517         mission_item_int->autocontinue = mavlink_msg_mission_item_int_get_autocontinue(msg);
00518 #else
00519         memcpy(mission_item_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
00520 #endif
00521 }


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