mavlink_msg_servo_output_raw.h
Go to the documentation of this file.
00001 // MESSAGE SERVO_OUTPUT_RAW PACKING
00002 
00003 #define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 36
00004 
00005 typedef struct __mavlink_servo_output_raw_t
00006 {
00007  uint32_t time_usec; /*< Timestamp (microseconds since system boot)*/
00008  uint16_t servo1_raw; /*< Servo output 1 value, in microseconds*/
00009  uint16_t servo2_raw; /*< Servo output 2 value, in microseconds*/
00010  uint16_t servo3_raw; /*< Servo output 3 value, in microseconds*/
00011  uint16_t servo4_raw; /*< Servo output 4 value, in microseconds*/
00012  uint16_t servo5_raw; /*< Servo output 5 value, in microseconds*/
00013  uint16_t servo6_raw; /*< Servo output 6 value, in microseconds*/
00014  uint16_t servo7_raw; /*< Servo output 7 value, in microseconds*/
00015  uint16_t servo8_raw; /*< Servo output 8 value, in microseconds*/
00016  uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.*/
00017 } mavlink_servo_output_raw_t;
00018 
00019 #define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 21
00020 #define MAVLINK_MSG_ID_36_LEN 21
00021 
00022 #define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC 222
00023 #define MAVLINK_MSG_ID_36_CRC 222
00024 
00025 
00026 
00027 #define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \
00028         "SERVO_OUTPUT_RAW", \
00029         10, \
00030         {  { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \
00031          { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \
00032          { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \
00033          { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \
00034          { "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \
00035          { "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \
00036          { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \
00037          { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \
00038          { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \
00039          { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \
00040          } \
00041 }
00042 
00043 
00062 static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00063                                                        uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
00064 {
00065 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00066         char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN];
00067         _mav_put_uint32_t(buf, 0, time_usec);
00068         _mav_put_uint16_t(buf, 4, servo1_raw);
00069         _mav_put_uint16_t(buf, 6, servo2_raw);
00070         _mav_put_uint16_t(buf, 8, servo3_raw);
00071         _mav_put_uint16_t(buf, 10, servo4_raw);
00072         _mav_put_uint16_t(buf, 12, servo5_raw);
00073         _mav_put_uint16_t(buf, 14, servo6_raw);
00074         _mav_put_uint16_t(buf, 16, servo7_raw);
00075         _mav_put_uint16_t(buf, 18, servo8_raw);
00076         _mav_put_uint8_t(buf, 20, port);
00077 
00078         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN);
00079 #else
00080         mavlink_servo_output_raw_t packet;
00081         packet.time_usec = time_usec;
00082         packet.servo1_raw = servo1_raw;
00083         packet.servo2_raw = servo2_raw;
00084         packet.servo3_raw = servo3_raw;
00085         packet.servo4_raw = servo4_raw;
00086         packet.servo5_raw = servo5_raw;
00087         packet.servo6_raw = servo6_raw;
00088         packet.servo7_raw = servo7_raw;
00089         packet.servo8_raw = servo8_raw;
00090         packet.port = port;
00091 
00092         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN);
00093 #endif
00094 
00095         msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
00096 #if MAVLINK_CRC_EXTRA
00097     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC);
00098 #else
00099     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN);
00100 #endif
00101 }
00102 
00121 static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00122                                                            mavlink_message_t* msg,
00123                                                            uint32_t time_usec,uint8_t port,uint16_t servo1_raw,uint16_t servo2_raw,uint16_t servo3_raw,uint16_t servo4_raw,uint16_t servo5_raw,uint16_t servo6_raw,uint16_t servo7_raw,uint16_t servo8_raw)
00124 {
00125 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00126         char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN];
00127         _mav_put_uint32_t(buf, 0, time_usec);
00128         _mav_put_uint16_t(buf, 4, servo1_raw);
00129         _mav_put_uint16_t(buf, 6, servo2_raw);
00130         _mav_put_uint16_t(buf, 8, servo3_raw);
00131         _mav_put_uint16_t(buf, 10, servo4_raw);
00132         _mav_put_uint16_t(buf, 12, servo5_raw);
00133         _mav_put_uint16_t(buf, 14, servo6_raw);
00134         _mav_put_uint16_t(buf, 16, servo7_raw);
00135         _mav_put_uint16_t(buf, 18, servo8_raw);
00136         _mav_put_uint8_t(buf, 20, port);
00137 
00138         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN);
00139 #else
00140         mavlink_servo_output_raw_t packet;
00141         packet.time_usec = time_usec;
00142         packet.servo1_raw = servo1_raw;
00143         packet.servo2_raw = servo2_raw;
00144         packet.servo3_raw = servo3_raw;
00145         packet.servo4_raw = servo4_raw;
00146         packet.servo5_raw = servo5_raw;
00147         packet.servo6_raw = servo6_raw;
00148         packet.servo7_raw = servo7_raw;
00149         packet.servo8_raw = servo8_raw;
00150         packet.port = port;
00151 
00152         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN);
00153 #endif
00154 
00155         msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
00156 #if MAVLINK_CRC_EXTRA
00157     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC);
00158 #else
00159     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN);
00160 #endif
00161 }
00162 
00171 static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw)
00172 {
00173         return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw);
00174 }
00175 
00185 static inline uint16_t mavlink_msg_servo_output_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw)
00186 {
00187         return mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, chan, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw);
00188 }
00189 
00205 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00206 
00207 static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
00208 {
00209 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00210         char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN];
00211         _mav_put_uint32_t(buf, 0, time_usec);
00212         _mav_put_uint16_t(buf, 4, servo1_raw);
00213         _mav_put_uint16_t(buf, 6, servo2_raw);
00214         _mav_put_uint16_t(buf, 8, servo3_raw);
00215         _mav_put_uint16_t(buf, 10, servo4_raw);
00216         _mav_put_uint16_t(buf, 12, servo5_raw);
00217         _mav_put_uint16_t(buf, 14, servo6_raw);
00218         _mav_put_uint16_t(buf, 16, servo7_raw);
00219         _mav_put_uint16_t(buf, 18, servo8_raw);
00220         _mav_put_uint8_t(buf, 20, port);
00221 
00222 #if MAVLINK_CRC_EXTRA
00223     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC);
00224 #else
00225     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN);
00226 #endif
00227 #else
00228         mavlink_servo_output_raw_t packet;
00229         packet.time_usec = time_usec;
00230         packet.servo1_raw = servo1_raw;
00231         packet.servo2_raw = servo2_raw;
00232         packet.servo3_raw = servo3_raw;
00233         packet.servo4_raw = servo4_raw;
00234         packet.servo5_raw = servo5_raw;
00235         packet.servo6_raw = servo6_raw;
00236         packet.servo7_raw = servo7_raw;
00237         packet.servo8_raw = servo8_raw;
00238         packet.port = port;
00239 
00240 #if MAVLINK_CRC_EXTRA
00241     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC);
00242 #else
00243     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN);
00244 #endif
00245 #endif
00246 }
00247 
00248 #if MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00249 /*
00250   This varient of _send() can be used to save stack space by re-using
00251   memory from the receive buffer.  The caller provides a
00252   mavlink_message_t which is the size of a full mavlink message. This
00253   is usually the receive buffer for the channel, and allows a reply to an
00254   incoming message with minimum stack space usage.
00255  */
00256 static inline void mavlink_msg_servo_output_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
00257 {
00258 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00259         char *buf = (char *)msgbuf;
00260         _mav_put_uint32_t(buf, 0, time_usec);
00261         _mav_put_uint16_t(buf, 4, servo1_raw);
00262         _mav_put_uint16_t(buf, 6, servo2_raw);
00263         _mav_put_uint16_t(buf, 8, servo3_raw);
00264         _mav_put_uint16_t(buf, 10, servo4_raw);
00265         _mav_put_uint16_t(buf, 12, servo5_raw);
00266         _mav_put_uint16_t(buf, 14, servo6_raw);
00267         _mav_put_uint16_t(buf, 16, servo7_raw);
00268         _mav_put_uint16_t(buf, 18, servo8_raw);
00269         _mav_put_uint8_t(buf, 20, port);
00270 
00271 #if MAVLINK_CRC_EXTRA
00272     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC);
00273 #else
00274     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN);
00275 #endif
00276 #else
00277         mavlink_servo_output_raw_t *packet = (mavlink_servo_output_raw_t *)msgbuf;
00278         packet->time_usec = time_usec;
00279         packet->servo1_raw = servo1_raw;
00280         packet->servo2_raw = servo2_raw;
00281         packet->servo3_raw = servo3_raw;
00282         packet->servo4_raw = servo4_raw;
00283         packet->servo5_raw = servo5_raw;
00284         packet->servo6_raw = servo6_raw;
00285         packet->servo7_raw = servo7_raw;
00286         packet->servo8_raw = servo8_raw;
00287         packet->port = port;
00288 
00289 #if MAVLINK_CRC_EXTRA
00290     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC);
00291 #else
00292     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN);
00293 #endif
00294 #endif
00295 }
00296 #endif
00297 
00298 #endif
00299 
00300 // MESSAGE SERVO_OUTPUT_RAW UNPACKING
00301 
00302 
00308 static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_message_t* msg)
00309 {
00310         return _MAV_RETURN_uint32_t(msg,  0);
00311 }
00312 
00318 static inline uint8_t mavlink_msg_servo_output_raw_get_port(const mavlink_message_t* msg)
00319 {
00320         return _MAV_RETURN_uint8_t(msg,  20);
00321 }
00322 
00328 static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg)
00329 {
00330         return _MAV_RETURN_uint16_t(msg,  4);
00331 }
00332 
00338 static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg)
00339 {
00340         return _MAV_RETURN_uint16_t(msg,  6);
00341 }
00342 
00348 static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg)
00349 {
00350         return _MAV_RETURN_uint16_t(msg,  8);
00351 }
00352 
00358 static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg)
00359 {
00360         return _MAV_RETURN_uint16_t(msg,  10);
00361 }
00362 
00368 static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg)
00369 {
00370         return _MAV_RETURN_uint16_t(msg,  12);
00371 }
00372 
00378 static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg)
00379 {
00380         return _MAV_RETURN_uint16_t(msg,  14);
00381 }
00382 
00388 static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg)
00389 {
00390         return _MAV_RETURN_uint16_t(msg,  16);
00391 }
00392 
00398 static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg)
00399 {
00400         return _MAV_RETURN_uint16_t(msg,  18);
00401 }
00402 
00409 static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw)
00410 {
00411 #if MAVLINK_NEED_BYTE_SWAP
00412         servo_output_raw->time_usec = mavlink_msg_servo_output_raw_get_time_usec(msg);
00413         servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg);
00414         servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg);
00415         servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg);
00416         servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg);
00417         servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg);
00418         servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg);
00419         servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg);
00420         servo_output_raw->servo8_raw = mavlink_msg_servo_output_raw_get_servo8_raw(msg);
00421         servo_output_raw->port = mavlink_msg_servo_output_raw_get_port(msg);
00422 #else
00423         memcpy(servo_output_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN);
00424 #endif
00425 }


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