mavlink_msg_manual_control.h
Go to the documentation of this file.
00001 // MESSAGE MANUAL_CONTROL PACKING
00002 
00003 #define MAVLINK_MSG_ID_MANUAL_CONTROL 69
00004 
00005 typedef struct __mavlink_manual_control_t
00006 {
00007  int16_t x; /*< X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.*/
00008  int16_t y; /*< Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.*/
00009  int16_t z; /*< Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle.*/
00010  int16_t r; /*< R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.*/
00011  uint16_t buttons; /*< A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.*/
00012  uint8_t target; /*< The system to be controlled.*/
00013 } mavlink_manual_control_t;
00014 
00015 #define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 11
00016 #define MAVLINK_MSG_ID_69_LEN 11
00017 
00018 #define MAVLINK_MSG_ID_MANUAL_CONTROL_CRC 243
00019 #define MAVLINK_MSG_ID_69_CRC 243
00020 
00021 
00022 
00023 #define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \
00024         "MANUAL_CONTROL", \
00025         6, \
00026         {  { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \
00027          { "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \
00028          { "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \
00029          { "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \
00030          { "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \
00031          { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \
00032          } \
00033 }
00034 
00035 
00050 static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00051                                                        uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons)
00052 {
00053 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00054         char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN];
00055         _mav_put_int16_t(buf, 0, x);
00056         _mav_put_int16_t(buf, 2, y);
00057         _mav_put_int16_t(buf, 4, z);
00058         _mav_put_int16_t(buf, 6, r);
00059         _mav_put_uint16_t(buf, 8, buttons);
00060         _mav_put_uint8_t(buf, 10, target);
00061 
00062         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
00063 #else
00064         mavlink_manual_control_t packet;
00065         packet.x = x;
00066         packet.y = y;
00067         packet.z = z;
00068         packet.r = r;
00069         packet.buttons = buttons;
00070         packet.target = target;
00071 
00072         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
00073 #endif
00074 
00075         msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
00076 #if MAVLINK_CRC_EXTRA
00077     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
00078 #else
00079     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
00080 #endif
00081 }
00082 
00097 static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00098                                                            mavlink_message_t* msg,
00099                                                            uint8_t target,int16_t x,int16_t y,int16_t z,int16_t r,uint16_t buttons)
00100 {
00101 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00102         char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN];
00103         _mav_put_int16_t(buf, 0, x);
00104         _mav_put_int16_t(buf, 2, y);
00105         _mav_put_int16_t(buf, 4, z);
00106         _mav_put_int16_t(buf, 6, r);
00107         _mav_put_uint16_t(buf, 8, buttons);
00108         _mav_put_uint8_t(buf, 10, target);
00109 
00110         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
00111 #else
00112         mavlink_manual_control_t packet;
00113         packet.x = x;
00114         packet.y = y;
00115         packet.z = z;
00116         packet.r = r;
00117         packet.buttons = buttons;
00118         packet.target = target;
00119 
00120         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
00121 #endif
00122 
00123         msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
00124 #if MAVLINK_CRC_EXTRA
00125     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
00126 #else
00127     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
00128 #endif
00129 }
00130 
00139 static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control)
00140 {
00141         return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons);
00142 }
00143 
00153 static inline uint16_t mavlink_msg_manual_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control)
00154 {
00155         return mavlink_msg_manual_control_pack_chan(system_id, component_id, chan, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons);
00156 }
00157 
00169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00170 
00171 static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons)
00172 {
00173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00174         char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN];
00175         _mav_put_int16_t(buf, 0, x);
00176         _mav_put_int16_t(buf, 2, y);
00177         _mav_put_int16_t(buf, 4, z);
00178         _mav_put_int16_t(buf, 6, r);
00179         _mav_put_uint16_t(buf, 8, buttons);
00180         _mav_put_uint8_t(buf, 10, target);
00181 
00182 #if MAVLINK_CRC_EXTRA
00183     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
00184 #else
00185     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
00186 #endif
00187 #else
00188         mavlink_manual_control_t packet;
00189         packet.x = x;
00190         packet.y = y;
00191         packet.z = z;
00192         packet.r = r;
00193         packet.buttons = buttons;
00194         packet.target = target;
00195 
00196 #if MAVLINK_CRC_EXTRA
00197     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
00198 #else
00199     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
00200 #endif
00201 #endif
00202 }
00203 
00204 #if MAVLINK_MSG_ID_MANUAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00205 /*
00206   This varient of _send() can be used to save stack space by re-using
00207   memory from the receive buffer.  The caller provides a
00208   mavlink_message_t which is the size of a full mavlink message. This
00209   is usually the receive buffer for the channel, and allows a reply to an
00210   incoming message with minimum stack space usage.
00211  */
00212 static inline void mavlink_msg_manual_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons)
00213 {
00214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00215         char *buf = (char *)msgbuf;
00216         _mav_put_int16_t(buf, 0, x);
00217         _mav_put_int16_t(buf, 2, y);
00218         _mav_put_int16_t(buf, 4, z);
00219         _mav_put_int16_t(buf, 6, r);
00220         _mav_put_uint16_t(buf, 8, buttons);
00221         _mav_put_uint8_t(buf, 10, target);
00222 
00223 #if MAVLINK_CRC_EXTRA
00224     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
00225 #else
00226     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
00227 #endif
00228 #else
00229         mavlink_manual_control_t *packet = (mavlink_manual_control_t *)msgbuf;
00230         packet->x = x;
00231         packet->y = y;
00232         packet->z = z;
00233         packet->r = r;
00234         packet->buttons = buttons;
00235         packet->target = target;
00236 
00237 #if MAVLINK_CRC_EXTRA
00238     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
00239 #else
00240     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
00241 #endif
00242 #endif
00243 }
00244 #endif
00245 
00246 #endif
00247 
00248 // MESSAGE MANUAL_CONTROL UNPACKING
00249 
00250 
00256 static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg)
00257 {
00258         return _MAV_RETURN_uint8_t(msg,  10);
00259 }
00260 
00266 static inline int16_t mavlink_msg_manual_control_get_x(const mavlink_message_t* msg)
00267 {
00268         return _MAV_RETURN_int16_t(msg,  0);
00269 }
00270 
00276 static inline int16_t mavlink_msg_manual_control_get_y(const mavlink_message_t* msg)
00277 {
00278         return _MAV_RETURN_int16_t(msg,  2);
00279 }
00280 
00286 static inline int16_t mavlink_msg_manual_control_get_z(const mavlink_message_t* msg)
00287 {
00288         return _MAV_RETURN_int16_t(msg,  4);
00289 }
00290 
00296 static inline int16_t mavlink_msg_manual_control_get_r(const mavlink_message_t* msg)
00297 {
00298         return _MAV_RETURN_int16_t(msg,  6);
00299 }
00300 
00306 static inline uint16_t mavlink_msg_manual_control_get_buttons(const mavlink_message_t* msg)
00307 {
00308         return _MAV_RETURN_uint16_t(msg,  8);
00309 }
00310 
00317 static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control)
00318 {
00319 #if MAVLINK_NEED_BYTE_SWAP
00320         manual_control->x = mavlink_msg_manual_control_get_x(msg);
00321         manual_control->y = mavlink_msg_manual_control_get_y(msg);
00322         manual_control->z = mavlink_msg_manual_control_get_z(msg);
00323         manual_control->r = mavlink_msg_manual_control_get_r(msg);
00324         manual_control->buttons = mavlink_msg_manual_control_get_buttons(msg);
00325         manual_control->target = mavlink_msg_manual_control_get_target(msg);
00326 #else
00327         memcpy(manual_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
00328 #endif
00329 }


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