mavlink_msg_rc_channels_raw.h
Go to the documentation of this file.
00001 // MESSAGE RC_CHANNELS_RAW PACKING
00002 
00003 #define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35
00004 
00005 typedef struct __mavlink_rc_channels_raw_t
00006 {
00007  uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
00008  uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/
00009  uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/
00010  uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/
00011  uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/
00012  uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/
00013  uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/
00014  uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/
00015  uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/
00016  uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.*/
00017  uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/
00018 } mavlink_rc_channels_raw_t;
00019 
00020 #define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22
00021 #define MAVLINK_MSG_ID_35_LEN 22
00022 
00023 #define MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC 244
00024 #define MAVLINK_MSG_ID_35_CRC 244
00025 
00026 
00027 
00028 #define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \
00029         "RC_CHANNELS_RAW", \
00030         11, \
00031         {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \
00032          { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \
00033          { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \
00034          { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \
00035          { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \
00036          { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \
00037          { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \
00038          { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \
00039          { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \
00040          { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \
00041          { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \
00042          } \
00043 }
00044 
00045 
00065 static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00066                                                        uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
00067 {
00068 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00069         char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN];
00070         _mav_put_uint32_t(buf, 0, time_boot_ms);
00071         _mav_put_uint16_t(buf, 4, chan1_raw);
00072         _mav_put_uint16_t(buf, 6, chan2_raw);
00073         _mav_put_uint16_t(buf, 8, chan3_raw);
00074         _mav_put_uint16_t(buf, 10, chan4_raw);
00075         _mav_put_uint16_t(buf, 12, chan5_raw);
00076         _mav_put_uint16_t(buf, 14, chan6_raw);
00077         _mav_put_uint16_t(buf, 16, chan7_raw);
00078         _mav_put_uint16_t(buf, 18, chan8_raw);
00079         _mav_put_uint8_t(buf, 20, port);
00080         _mav_put_uint8_t(buf, 21, rssi);
00081 
00082         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
00083 #else
00084         mavlink_rc_channels_raw_t packet;
00085         packet.time_boot_ms = time_boot_ms;
00086         packet.chan1_raw = chan1_raw;
00087         packet.chan2_raw = chan2_raw;
00088         packet.chan3_raw = chan3_raw;
00089         packet.chan4_raw = chan4_raw;
00090         packet.chan5_raw = chan5_raw;
00091         packet.chan6_raw = chan6_raw;
00092         packet.chan7_raw = chan7_raw;
00093         packet.chan8_raw = chan8_raw;
00094         packet.port = port;
00095         packet.rssi = rssi;
00096 
00097         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
00098 #endif
00099 
00100         msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
00101 #if MAVLINK_CRC_EXTRA
00102     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
00103 #else
00104     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
00105 #endif
00106 }
00107 
00127 static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00128                                                            mavlink_message_t* msg,
00129                                                            uint32_t time_boot_ms,uint8_t port,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint8_t rssi)
00130 {
00131 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00132         char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN];
00133         _mav_put_uint32_t(buf, 0, time_boot_ms);
00134         _mav_put_uint16_t(buf, 4, chan1_raw);
00135         _mav_put_uint16_t(buf, 6, chan2_raw);
00136         _mav_put_uint16_t(buf, 8, chan3_raw);
00137         _mav_put_uint16_t(buf, 10, chan4_raw);
00138         _mav_put_uint16_t(buf, 12, chan5_raw);
00139         _mav_put_uint16_t(buf, 14, chan6_raw);
00140         _mav_put_uint16_t(buf, 16, chan7_raw);
00141         _mav_put_uint16_t(buf, 18, chan8_raw);
00142         _mav_put_uint8_t(buf, 20, port);
00143         _mav_put_uint8_t(buf, 21, rssi);
00144 
00145         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
00146 #else
00147         mavlink_rc_channels_raw_t packet;
00148         packet.time_boot_ms = time_boot_ms;
00149         packet.chan1_raw = chan1_raw;
00150         packet.chan2_raw = chan2_raw;
00151         packet.chan3_raw = chan3_raw;
00152         packet.chan4_raw = chan4_raw;
00153         packet.chan5_raw = chan5_raw;
00154         packet.chan6_raw = chan6_raw;
00155         packet.chan7_raw = chan7_raw;
00156         packet.chan8_raw = chan8_raw;
00157         packet.port = port;
00158         packet.rssi = rssi;
00159 
00160         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
00161 #endif
00162 
00163         msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
00164 #if MAVLINK_CRC_EXTRA
00165     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
00166 #else
00167     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
00168 #endif
00169 }
00170 
00179 static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw)
00180 {
00181         return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi);
00182 }
00183 
00193 static inline uint16_t mavlink_msg_rc_channels_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw)
00194 {
00195         return mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, chan, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi);
00196 }
00197 
00214 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00215 
00216 static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
00217 {
00218 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00219         char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN];
00220         _mav_put_uint32_t(buf, 0, time_boot_ms);
00221         _mav_put_uint16_t(buf, 4, chan1_raw);
00222         _mav_put_uint16_t(buf, 6, chan2_raw);
00223         _mav_put_uint16_t(buf, 8, chan3_raw);
00224         _mav_put_uint16_t(buf, 10, chan4_raw);
00225         _mav_put_uint16_t(buf, 12, chan5_raw);
00226         _mav_put_uint16_t(buf, 14, chan6_raw);
00227         _mav_put_uint16_t(buf, 16, chan7_raw);
00228         _mav_put_uint16_t(buf, 18, chan8_raw);
00229         _mav_put_uint8_t(buf, 20, port);
00230         _mav_put_uint8_t(buf, 21, rssi);
00231 
00232 #if MAVLINK_CRC_EXTRA
00233     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
00234 #else
00235     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
00236 #endif
00237 #else
00238         mavlink_rc_channels_raw_t packet;
00239         packet.time_boot_ms = time_boot_ms;
00240         packet.chan1_raw = chan1_raw;
00241         packet.chan2_raw = chan2_raw;
00242         packet.chan3_raw = chan3_raw;
00243         packet.chan4_raw = chan4_raw;
00244         packet.chan5_raw = chan5_raw;
00245         packet.chan6_raw = chan6_raw;
00246         packet.chan7_raw = chan7_raw;
00247         packet.chan8_raw = chan8_raw;
00248         packet.port = port;
00249         packet.rssi = rssi;
00250 
00251 #if MAVLINK_CRC_EXTRA
00252     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
00253 #else
00254     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
00255 #endif
00256 #endif
00257 }
00258 
00259 #if MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00260 /*
00261   This varient of _send() can be used to save stack space by re-using
00262   memory from the receive buffer.  The caller provides a
00263   mavlink_message_t which is the size of a full mavlink message. This
00264   is usually the receive buffer for the channel, and allows a reply to an
00265   incoming message with minimum stack space usage.
00266  */
00267 static inline void mavlink_msg_rc_channels_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
00268 {
00269 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00270         char *buf = (char *)msgbuf;
00271         _mav_put_uint32_t(buf, 0, time_boot_ms);
00272         _mav_put_uint16_t(buf, 4, chan1_raw);
00273         _mav_put_uint16_t(buf, 6, chan2_raw);
00274         _mav_put_uint16_t(buf, 8, chan3_raw);
00275         _mav_put_uint16_t(buf, 10, chan4_raw);
00276         _mav_put_uint16_t(buf, 12, chan5_raw);
00277         _mav_put_uint16_t(buf, 14, chan6_raw);
00278         _mav_put_uint16_t(buf, 16, chan7_raw);
00279         _mav_put_uint16_t(buf, 18, chan8_raw);
00280         _mav_put_uint8_t(buf, 20, port);
00281         _mav_put_uint8_t(buf, 21, rssi);
00282 
00283 #if MAVLINK_CRC_EXTRA
00284     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
00285 #else
00286     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
00287 #endif
00288 #else
00289         mavlink_rc_channels_raw_t *packet = (mavlink_rc_channels_raw_t *)msgbuf;
00290         packet->time_boot_ms = time_boot_ms;
00291         packet->chan1_raw = chan1_raw;
00292         packet->chan2_raw = chan2_raw;
00293         packet->chan3_raw = chan3_raw;
00294         packet->chan4_raw = chan4_raw;
00295         packet->chan5_raw = chan5_raw;
00296         packet->chan6_raw = chan6_raw;
00297         packet->chan7_raw = chan7_raw;
00298         packet->chan8_raw = chan8_raw;
00299         packet->port = port;
00300         packet->rssi = rssi;
00301 
00302 #if MAVLINK_CRC_EXTRA
00303     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
00304 #else
00305     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
00306 #endif
00307 #endif
00308 }
00309 #endif
00310 
00311 #endif
00312 
00313 // MESSAGE RC_CHANNELS_RAW UNPACKING
00314 
00315 
00321 static inline uint32_t mavlink_msg_rc_channels_raw_get_time_boot_ms(const mavlink_message_t* msg)
00322 {
00323         return _MAV_RETURN_uint32_t(msg,  0);
00324 }
00325 
00331 static inline uint8_t mavlink_msg_rc_channels_raw_get_port(const mavlink_message_t* msg)
00332 {
00333         return _MAV_RETURN_uint8_t(msg,  20);
00334 }
00335 
00341 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg)
00342 {
00343         return _MAV_RETURN_uint16_t(msg,  4);
00344 }
00345 
00351 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg)
00352 {
00353         return _MAV_RETURN_uint16_t(msg,  6);
00354 }
00355 
00361 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg)
00362 {
00363         return _MAV_RETURN_uint16_t(msg,  8);
00364 }
00365 
00371 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg)
00372 {
00373         return _MAV_RETURN_uint16_t(msg,  10);
00374 }
00375 
00381 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg)
00382 {
00383         return _MAV_RETURN_uint16_t(msg,  12);
00384 }
00385 
00391 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg)
00392 {
00393         return _MAV_RETURN_uint16_t(msg,  14);
00394 }
00395 
00401 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg)
00402 {
00403         return _MAV_RETURN_uint16_t(msg,  16);
00404 }
00405 
00411 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg)
00412 {
00413         return _MAV_RETURN_uint16_t(msg,  18);
00414 }
00415 
00421 static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg)
00422 {
00423         return _MAV_RETURN_uint8_t(msg,  21);
00424 }
00425 
00432 static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw)
00433 {
00434 #if MAVLINK_NEED_BYTE_SWAP
00435         rc_channels_raw->time_boot_ms = mavlink_msg_rc_channels_raw_get_time_boot_ms(msg);
00436         rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg);
00437         rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg);
00438         rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg);
00439         rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg);
00440         rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg);
00441         rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg);
00442         rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg);
00443         rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg);
00444         rc_channels_raw->port = mavlink_msg_rc_channels_raw_get_port(msg);
00445         rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg);
00446 #else
00447         memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
00448 #endif
00449 }


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