Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Committer:
shimniok
Date:
Wed Jun 20 14:57:48 2012 +0000
Revision:
0:826c6171fc1b
Updated documentation

Who changed what in which revision?

UserRevisionLine numberNew contents of line
shimniok 0:826c6171fc1b 1 // MESSAGE RC_CHANNELS_RAW PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_rc_channels_raw_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 uint16_t chan1_raw; ///< RC channel 1 value, in microseconds
shimniok 0:826c6171fc1b 8 uint16_t chan2_raw; ///< RC channel 2 value, in microseconds
shimniok 0:826c6171fc1b 9 uint16_t chan3_raw; ///< RC channel 3 value, in microseconds
shimniok 0:826c6171fc1b 10 uint16_t chan4_raw; ///< RC channel 4 value, in microseconds
shimniok 0:826c6171fc1b 11 uint16_t chan5_raw; ///< RC channel 5 value, in microseconds
shimniok 0:826c6171fc1b 12 uint16_t chan6_raw; ///< RC channel 6 value, in microseconds
shimniok 0:826c6171fc1b 13 uint16_t chan7_raw; ///< RC channel 7 value, in microseconds
shimniok 0:826c6171fc1b 14 uint16_t chan8_raw; ///< RC channel 8 value, in microseconds
shimniok 0:826c6171fc1b 15 uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100%
shimniok 0:826c6171fc1b 16
shimniok 0:826c6171fc1b 17 } mavlink_rc_channels_raw_t;
shimniok 0:826c6171fc1b 18
shimniok 0:826c6171fc1b 19
shimniok 0:826c6171fc1b 20
shimniok 0:826c6171fc1b 21 /**
shimniok 0:826c6171fc1b 22 * @brief Pack a rc_channels_raw message
shimniok 0:826c6171fc1b 23 * @param system_id ID of this system
shimniok 0:826c6171fc1b 24 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 25 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 26 *
shimniok 0:826c6171fc1b 27 * @param chan1_raw RC channel 1 value, in microseconds
shimniok 0:826c6171fc1b 28 * @param chan2_raw RC channel 2 value, in microseconds
shimniok 0:826c6171fc1b 29 * @param chan3_raw RC channel 3 value, in microseconds
shimniok 0:826c6171fc1b 30 * @param chan4_raw RC channel 4 value, in microseconds
shimniok 0:826c6171fc1b 31 * @param chan5_raw RC channel 5 value, in microseconds
shimniok 0:826c6171fc1b 32 * @param chan6_raw RC channel 6 value, in microseconds
shimniok 0:826c6171fc1b 33 * @param chan7_raw RC channel 7 value, in microseconds
shimniok 0:826c6171fc1b 34 * @param chan8_raw RC channel 8 value, in microseconds
shimniok 0:826c6171fc1b 35 * @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
shimniok 0:826c6171fc1b 36 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 37 */
shimniok 0:826c6171fc1b 38 static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, 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)
shimniok 0:826c6171fc1b 39 {
shimniok 0:826c6171fc1b 40 uint16_t i = 0;
shimniok 0:826c6171fc1b 41 msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
shimniok 0:826c6171fc1b 42
shimniok 0:826c6171fc1b 43 i += put_uint16_t_by_index(chan1_raw, i, msg->payload); // RC channel 1 value, in microseconds
shimniok 0:826c6171fc1b 44 i += put_uint16_t_by_index(chan2_raw, i, msg->payload); // RC channel 2 value, in microseconds
shimniok 0:826c6171fc1b 45 i += put_uint16_t_by_index(chan3_raw, i, msg->payload); // RC channel 3 value, in microseconds
shimniok 0:826c6171fc1b 46 i += put_uint16_t_by_index(chan4_raw, i, msg->payload); // RC channel 4 value, in microseconds
shimniok 0:826c6171fc1b 47 i += put_uint16_t_by_index(chan5_raw, i, msg->payload); // RC channel 5 value, in microseconds
shimniok 0:826c6171fc1b 48 i += put_uint16_t_by_index(chan6_raw, i, msg->payload); // RC channel 6 value, in microseconds
shimniok 0:826c6171fc1b 49 i += put_uint16_t_by_index(chan7_raw, i, msg->payload); // RC channel 7 value, in microseconds
shimniok 0:826c6171fc1b 50 i += put_uint16_t_by_index(chan8_raw, i, msg->payload); // RC channel 8 value, in microseconds
shimniok 0:826c6171fc1b 51 i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100%
shimniok 0:826c6171fc1b 52
shimniok 0:826c6171fc1b 53 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:826c6171fc1b 54 }
shimniok 0:826c6171fc1b 55
shimniok 0:826c6171fc1b 56 /**
shimniok 0:826c6171fc1b 57 * @brief Pack a rc_channels_raw message
shimniok 0:826c6171fc1b 58 * @param system_id ID of this system
shimniok 0:826c6171fc1b 59 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 60 * @param chan The MAVLink channel this message was sent over
shimniok 0:826c6171fc1b 61 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 62 * @param chan1_raw RC channel 1 value, in microseconds
shimniok 0:826c6171fc1b 63 * @param chan2_raw RC channel 2 value, in microseconds
shimniok 0:826c6171fc1b 64 * @param chan3_raw RC channel 3 value, in microseconds
shimniok 0:826c6171fc1b 65 * @param chan4_raw RC channel 4 value, in microseconds
shimniok 0:826c6171fc1b 66 * @param chan5_raw RC channel 5 value, in microseconds
shimniok 0:826c6171fc1b 67 * @param chan6_raw RC channel 6 value, in microseconds
shimniok 0:826c6171fc1b 68 * @param chan7_raw RC channel 7 value, in microseconds
shimniok 0:826c6171fc1b 69 * @param chan8_raw RC channel 8 value, in microseconds
shimniok 0:826c6171fc1b 70 * @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
shimniok 0:826c6171fc1b 71 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 72 */
shimniok 0:826c6171fc1b 73 static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, 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)
shimniok 0:826c6171fc1b 74 {
shimniok 0:826c6171fc1b 75 uint16_t i = 0;
shimniok 0:826c6171fc1b 76 msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
shimniok 0:826c6171fc1b 77
shimniok 0:826c6171fc1b 78 i += put_uint16_t_by_index(chan1_raw, i, msg->payload); // RC channel 1 value, in microseconds
shimniok 0:826c6171fc1b 79 i += put_uint16_t_by_index(chan2_raw, i, msg->payload); // RC channel 2 value, in microseconds
shimniok 0:826c6171fc1b 80 i += put_uint16_t_by_index(chan3_raw, i, msg->payload); // RC channel 3 value, in microseconds
shimniok 0:826c6171fc1b 81 i += put_uint16_t_by_index(chan4_raw, i, msg->payload); // RC channel 4 value, in microseconds
shimniok 0:826c6171fc1b 82 i += put_uint16_t_by_index(chan5_raw, i, msg->payload); // RC channel 5 value, in microseconds
shimniok 0:826c6171fc1b 83 i += put_uint16_t_by_index(chan6_raw, i, msg->payload); // RC channel 6 value, in microseconds
shimniok 0:826c6171fc1b 84 i += put_uint16_t_by_index(chan7_raw, i, msg->payload); // RC channel 7 value, in microseconds
shimniok 0:826c6171fc1b 85 i += put_uint16_t_by_index(chan8_raw, i, msg->payload); // RC channel 8 value, in microseconds
shimniok 0:826c6171fc1b 86 i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100%
shimniok 0:826c6171fc1b 87
shimniok 0:826c6171fc1b 88 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:826c6171fc1b 89 }
shimniok 0:826c6171fc1b 90
shimniok 0:826c6171fc1b 91 /**
shimniok 0:826c6171fc1b 92 * @brief Encode a rc_channels_raw struct into a message
shimniok 0:826c6171fc1b 93 *
shimniok 0:826c6171fc1b 94 * @param system_id ID of this system
shimniok 0:826c6171fc1b 95 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 96 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 97 * @param rc_channels_raw C-struct to read the message contents from
shimniok 0:826c6171fc1b 98 */
shimniok 0:826c6171fc1b 99 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)
shimniok 0:826c6171fc1b 100 {
shimniok 0:826c6171fc1b 101 return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, 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);
shimniok 0:826c6171fc1b 102 }
shimniok 0:826c6171fc1b 103
shimniok 0:826c6171fc1b 104 /**
shimniok 0:826c6171fc1b 105 * @brief Send a rc_channels_raw message
shimniok 0:826c6171fc1b 106 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 107 *
shimniok 0:826c6171fc1b 108 * @param chan1_raw RC channel 1 value, in microseconds
shimniok 0:826c6171fc1b 109 * @param chan2_raw RC channel 2 value, in microseconds
shimniok 0:826c6171fc1b 110 * @param chan3_raw RC channel 3 value, in microseconds
shimniok 0:826c6171fc1b 111 * @param chan4_raw RC channel 4 value, in microseconds
shimniok 0:826c6171fc1b 112 * @param chan5_raw RC channel 5 value, in microseconds
shimniok 0:826c6171fc1b 113 * @param chan6_raw RC channel 6 value, in microseconds
shimniok 0:826c6171fc1b 114 * @param chan7_raw RC channel 7 value, in microseconds
shimniok 0:826c6171fc1b 115 * @param chan8_raw RC channel 8 value, in microseconds
shimniok 0:826c6171fc1b 116 * @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
shimniok 0:826c6171fc1b 117 */
shimniok 0:826c6171fc1b 118 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:826c6171fc1b 119
shimniok 0:826c6171fc1b 120 static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, 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)
shimniok 0:826c6171fc1b 121 {
shimniok 0:826c6171fc1b 122 mavlink_message_t msg;
shimniok 0:826c6171fc1b 123 mavlink_msg_rc_channels_raw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi);
shimniok 0:826c6171fc1b 124 mavlink_send_uart(chan, &msg);
shimniok 0:826c6171fc1b 125 }
shimniok 0:826c6171fc1b 126
shimniok 0:826c6171fc1b 127 #endif
shimniok 0:826c6171fc1b 128 // MESSAGE RC_CHANNELS_RAW UNPACKING
shimniok 0:826c6171fc1b 129
shimniok 0:826c6171fc1b 130 /**
shimniok 0:826c6171fc1b 131 * @brief Get field chan1_raw from rc_channels_raw message
shimniok 0:826c6171fc1b 132 *
shimniok 0:826c6171fc1b 133 * @return RC channel 1 value, in microseconds
shimniok 0:826c6171fc1b 134 */
shimniok 0:826c6171fc1b 135 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 136 {
shimniok 0:826c6171fc1b 137 generic_16bit r;
shimniok 0:826c6171fc1b 138 r.b[1] = (msg->payload)[0];
shimniok 0:826c6171fc1b 139 r.b[0] = (msg->payload)[1];
shimniok 0:826c6171fc1b 140 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 141 }
shimniok 0:826c6171fc1b 142
shimniok 0:826c6171fc1b 143 /**
shimniok 0:826c6171fc1b 144 * @brief Get field chan2_raw from rc_channels_raw message
shimniok 0:826c6171fc1b 145 *
shimniok 0:826c6171fc1b 146 * @return RC channel 2 value, in microseconds
shimniok 0:826c6171fc1b 147 */
shimniok 0:826c6171fc1b 148 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 149 {
shimniok 0:826c6171fc1b 150 generic_16bit r;
shimniok 0:826c6171fc1b 151 r.b[1] = (msg->payload+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 152 r.b[0] = (msg->payload+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 153 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 154 }
shimniok 0:826c6171fc1b 155
shimniok 0:826c6171fc1b 156 /**
shimniok 0:826c6171fc1b 157 * @brief Get field chan3_raw from rc_channels_raw message
shimniok 0:826c6171fc1b 158 *
shimniok 0:826c6171fc1b 159 * @return RC channel 3 value, in microseconds
shimniok 0:826c6171fc1b 160 */
shimniok 0:826c6171fc1b 161 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 162 {
shimniok 0:826c6171fc1b 163 generic_16bit r;
shimniok 0:826c6171fc1b 164 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 165 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 166 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 167 }
shimniok 0:826c6171fc1b 168
shimniok 0:826c6171fc1b 169 /**
shimniok 0:826c6171fc1b 170 * @brief Get field chan4_raw from rc_channels_raw message
shimniok 0:826c6171fc1b 171 *
shimniok 0:826c6171fc1b 172 * @return RC channel 4 value, in microseconds
shimniok 0:826c6171fc1b 173 */
shimniok 0:826c6171fc1b 174 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 175 {
shimniok 0:826c6171fc1b 176 generic_16bit r;
shimniok 0:826c6171fc1b 177 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 178 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 179 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 180 }
shimniok 0:826c6171fc1b 181
shimniok 0:826c6171fc1b 182 /**
shimniok 0:826c6171fc1b 183 * @brief Get field chan5_raw from rc_channels_raw message
shimniok 0:826c6171fc1b 184 *
shimniok 0:826c6171fc1b 185 * @return RC channel 5 value, in microseconds
shimniok 0:826c6171fc1b 186 */
shimniok 0:826c6171fc1b 187 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 188 {
shimniok 0:826c6171fc1b 189 generic_16bit r;
shimniok 0:826c6171fc1b 190 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 191 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 192 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 193 }
shimniok 0:826c6171fc1b 194
shimniok 0:826c6171fc1b 195 /**
shimniok 0:826c6171fc1b 196 * @brief Get field chan6_raw from rc_channels_raw message
shimniok 0:826c6171fc1b 197 *
shimniok 0:826c6171fc1b 198 * @return RC channel 6 value, in microseconds
shimniok 0:826c6171fc1b 199 */
shimniok 0:826c6171fc1b 200 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 201 {
shimniok 0:826c6171fc1b 202 generic_16bit r;
shimniok 0:826c6171fc1b 203 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 204 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 205 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 206 }
shimniok 0:826c6171fc1b 207
shimniok 0:826c6171fc1b 208 /**
shimniok 0:826c6171fc1b 209 * @brief Get field chan7_raw from rc_channels_raw message
shimniok 0:826c6171fc1b 210 *
shimniok 0:826c6171fc1b 211 * @return RC channel 7 value, in microseconds
shimniok 0:826c6171fc1b 212 */
shimniok 0:826c6171fc1b 213 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 214 {
shimniok 0:826c6171fc1b 215 generic_16bit r;
shimniok 0:826c6171fc1b 216 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 217 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 218 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 219 }
shimniok 0:826c6171fc1b 220
shimniok 0:826c6171fc1b 221 /**
shimniok 0:826c6171fc1b 222 * @brief Get field chan8_raw from rc_channels_raw message
shimniok 0:826c6171fc1b 223 *
shimniok 0:826c6171fc1b 224 * @return RC channel 8 value, in microseconds
shimniok 0:826c6171fc1b 225 */
shimniok 0:826c6171fc1b 226 static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 227 {
shimniok 0:826c6171fc1b 228 generic_16bit r;
shimniok 0:826c6171fc1b 229 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 230 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 231 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 232 }
shimniok 0:826c6171fc1b 233
shimniok 0:826c6171fc1b 234 /**
shimniok 0:826c6171fc1b 235 * @brief Get field rssi from rc_channels_raw message
shimniok 0:826c6171fc1b 236 *
shimniok 0:826c6171fc1b 237 * @return Receive signal strength indicator, 0: 0%, 255: 100%
shimniok 0:826c6171fc1b 238 */
shimniok 0:826c6171fc1b 239 static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 240 {
shimniok 0:826c6171fc1b 241 return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 242 }
shimniok 0:826c6171fc1b 243
shimniok 0:826c6171fc1b 244 /**
shimniok 0:826c6171fc1b 245 * @brief Decode a rc_channels_raw message into a struct
shimniok 0:826c6171fc1b 246 *
shimniok 0:826c6171fc1b 247 * @param msg The message to decode
shimniok 0:826c6171fc1b 248 * @param rc_channels_raw C-struct to decode the message contents into
shimniok 0:826c6171fc1b 249 */
shimniok 0:826c6171fc1b 250 static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw)
shimniok 0:826c6171fc1b 251 {
shimniok 0:826c6171fc1b 252 rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg);
shimniok 0:826c6171fc1b 253 rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg);
shimniok 0:826c6171fc1b 254 rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg);
shimniok 0:826c6171fc1b 255 rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg);
shimniok 0:826c6171fc1b 256 rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg);
shimniok 0:826c6171fc1b 257 rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg);
shimniok 0:826c6171fc1b 258 rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg);
shimniok 0:826c6171fc1b 259 rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg);
shimniok 0:826c6171fc1b 260 rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg);
shimniok 0:826c6171fc1b 261 }