Code for autonomous rover for Sparkfun AVC. DataBus won 3rd in 2012 and the same code was used on Troubled Child, a 1986 Jeep Grand Wagoneer to win 1st in 2014.

Dependencies:   mbed Watchdog SDFileSystem DigoleSerialDisp

Committer:
shimniok
Date:
Fri Nov 30 16:11:53 2018 +0000
Revision:
25:bb5356402687
Parent:
0:a6a169de725f
Initial publish of revised version.

Who changed what in which revision?

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