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

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers mavlink_msg_rc_channels_override.h Source File

mavlink_msg_rc_channels_override.h

00001 // MESSAGE RC_CHANNELS_OVERRIDE PACKING
00002 
00003 #define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70
00004 
00005 typedef struct __mavlink_rc_channels_override_t 
00006 {
00007     uint8_t target_system; ///< System ID
00008     uint8_t target_component; ///< Component ID
00009     uint16_t chan1_raw; ///< RC channel 1 value, in microseconds
00010     uint16_t chan2_raw; ///< RC channel 2 value, in microseconds
00011     uint16_t chan3_raw; ///< RC channel 3 value, in microseconds
00012     uint16_t chan4_raw; ///< RC channel 4 value, in microseconds
00013     uint16_t chan5_raw; ///< RC channel 5 value, in microseconds
00014     uint16_t chan6_raw; ///< RC channel 6 value, in microseconds
00015     uint16_t chan7_raw; ///< RC channel 7 value, in microseconds
00016     uint16_t chan8_raw; ///< RC channel 8 value, in microseconds
00017 
00018 } mavlink_rc_channels_override_t;
00019 
00020 
00021 
00022 /**
00023  * @brief Pack a rc_channels_override message
00024  * @param system_id ID of this system
00025  * @param component_id ID of this component (e.g. 200 for IMU)
00026  * @param msg The MAVLink message to compress the data into
00027  *
00028  * @param target_system System ID
00029  * @param target_component Component ID
00030  * @param chan1_raw RC channel 1 value, in microseconds
00031  * @param chan2_raw RC channel 2 value, in microseconds
00032  * @param chan3_raw RC channel 3 value, in microseconds
00033  * @param chan4_raw RC channel 4 value, in microseconds
00034  * @param chan5_raw RC channel 5 value, in microseconds
00035  * @param chan6_raw RC channel 6 value, in microseconds
00036  * @param chan7_raw RC channel 7 value, in microseconds
00037  * @param chan8_raw RC channel 8 value, in microseconds
00038  * @return length of the message in bytes (excluding serial stream start sign)
00039  */
00040 static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, 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)
00041 {
00042     uint16_t i = 0;
00043     msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE;
00044 
00045     i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
00046     i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
00047     i += put_uint16_t_by_index(chan1_raw, i, msg->payload); // RC channel 1 value, in microseconds
00048     i += put_uint16_t_by_index(chan2_raw, i, msg->payload); // RC channel 2 value, in microseconds
00049     i += put_uint16_t_by_index(chan3_raw, i, msg->payload); // RC channel 3 value, in microseconds
00050     i += put_uint16_t_by_index(chan4_raw, i, msg->payload); // RC channel 4 value, in microseconds
00051     i += put_uint16_t_by_index(chan5_raw, i, msg->payload); // RC channel 5 value, in microseconds
00052     i += put_uint16_t_by_index(chan6_raw, i, msg->payload); // RC channel 6 value, in microseconds
00053     i += put_uint16_t_by_index(chan7_raw, i, msg->payload); // RC channel 7 value, in microseconds
00054     i += put_uint16_t_by_index(chan8_raw, i, msg->payload); // RC channel 8 value, in microseconds
00055 
00056     return mavlink_finalize_message(msg, system_id, component_id, i);
00057 }
00058 
00059 /**
00060  * @brief Pack a rc_channels_override message
00061  * @param system_id ID of this system
00062  * @param component_id ID of this component (e.g. 200 for IMU)
00063  * @param chan The MAVLink channel this message was sent over
00064  * @param msg The MAVLink message to compress the data into
00065  * @param target_system System ID
00066  * @param target_component Component ID
00067  * @param chan1_raw RC channel 1 value, in microseconds
00068  * @param chan2_raw RC channel 2 value, in microseconds
00069  * @param chan3_raw RC channel 3 value, in microseconds
00070  * @param chan4_raw RC channel 4 value, in microseconds
00071  * @param chan5_raw RC channel 5 value, in microseconds
00072  * @param chan6_raw RC channel 6 value, in microseconds
00073  * @param chan7_raw RC channel 7 value, in microseconds
00074  * @param chan8_raw RC channel 8 value, in microseconds
00075  * @return length of the message in bytes (excluding serial stream start sign)
00076  */
00077 static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, 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)
00078 {
00079     uint16_t i = 0;
00080     msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE;
00081 
00082     i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
00083     i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
00084     i += put_uint16_t_by_index(chan1_raw, i, msg->payload); // RC channel 1 value, in microseconds
00085     i += put_uint16_t_by_index(chan2_raw, i, msg->payload); // RC channel 2 value, in microseconds
00086     i += put_uint16_t_by_index(chan3_raw, i, msg->payload); // RC channel 3 value, in microseconds
00087     i += put_uint16_t_by_index(chan4_raw, i, msg->payload); // RC channel 4 value, in microseconds
00088     i += put_uint16_t_by_index(chan5_raw, i, msg->payload); // RC channel 5 value, in microseconds
00089     i += put_uint16_t_by_index(chan6_raw, i, msg->payload); // RC channel 6 value, in microseconds
00090     i += put_uint16_t_by_index(chan7_raw, i, msg->payload); // RC channel 7 value, in microseconds
00091     i += put_uint16_t_by_index(chan8_raw, i, msg->payload); // RC channel 8 value, in microseconds
00092 
00093     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00094 }
00095 
00096 /**
00097  * @brief Encode a rc_channels_override struct into a message
00098  *
00099  * @param system_id ID of this system
00100  * @param component_id ID of this component (e.g. 200 for IMU)
00101  * @param msg The MAVLink message to compress the data into
00102  * @param rc_channels_override C-struct to read the message contents from
00103  */
00104 static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override)
00105 {
00106     return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw);
00107 }
00108 
00109 /**
00110  * @brief Send a rc_channels_override message
00111  * @param chan MAVLink channel to send the message
00112  *
00113  * @param target_system System ID
00114  * @param target_component Component ID
00115  * @param chan1_raw RC channel 1 value, in microseconds
00116  * @param chan2_raw RC channel 2 value, in microseconds
00117  * @param chan3_raw RC channel 3 value, in microseconds
00118  * @param chan4_raw RC channel 4 value, in microseconds
00119  * @param chan5_raw RC channel 5 value, in microseconds
00120  * @param chan6_raw RC channel 6 value, in microseconds
00121  * @param chan7_raw RC channel 7 value, in microseconds
00122  * @param chan8_raw RC channel 8 value, in microseconds
00123  */
00124 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00125 
00126 static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, 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)
00127 {
00128     mavlink_message_t msg;
00129     mavlink_msg_rc_channels_override_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw);
00130     mavlink_send_uart(chan, &msg);
00131 }
00132 
00133 #endif
00134 // MESSAGE RC_CHANNELS_OVERRIDE UNPACKING
00135 
00136 /**
00137  * @brief Get field target_system from rc_channels_override message
00138  *
00139  * @return System ID
00140  */
00141 static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg)
00142 {
00143     return (uint8_t)(msg->payload)[0];
00144 }
00145 
00146 /**
00147  * @brief Get field target_component from rc_channels_override message
00148  *
00149  * @return Component ID
00150  */
00151 static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg)
00152 {
00153     return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
00154 }
00155 
00156 /**
00157  * @brief Get field chan1_raw from rc_channels_override message
00158  *
00159  * @return RC channel 1 value, in microseconds
00160  */
00161 static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg)
00162 {
00163     generic_16bit r;
00164     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
00165     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
00166     return (uint16_t)r.s;
00167 }
00168 
00169 /**
00170  * @brief Get field chan2_raw from rc_channels_override message
00171  *
00172  * @return RC channel 2 value, in microseconds
00173  */
00174 static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg)
00175 {
00176     generic_16bit r;
00177     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
00178     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1];
00179     return (uint16_t)r.s;
00180 }
00181 
00182 /**
00183  * @brief Get field chan3_raw from rc_channels_override message
00184  *
00185  * @return RC channel 3 value, in microseconds
00186  */
00187 static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg)
00188 {
00189     generic_16bit r;
00190     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
00191     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
00192     return (uint16_t)r.s;
00193 }
00194 
00195 /**
00196  * @brief Get field chan4_raw from rc_channels_override message
00197  *
00198  * @return RC channel 4 value, in microseconds
00199  */
00200 static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg)
00201 {
00202     generic_16bit r;
00203     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
00204     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
00205     return (uint16_t)r.s;
00206 }
00207 
00208 /**
00209  * @brief Get field chan5_raw from rc_channels_override message
00210  *
00211  * @return RC channel 5 value, in microseconds
00212  */
00213 static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg)
00214 {
00215     generic_16bit r;
00216     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
00217     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
00218     return (uint16_t)r.s;
00219 }
00220 
00221 /**
00222  * @brief Get field chan6_raw from rc_channels_override message
00223  *
00224  * @return RC channel 6 value, in microseconds
00225  */
00226 static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg)
00227 {
00228     generic_16bit r;
00229     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
00230     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
00231     return (uint16_t)r.s;
00232 }
00233 
00234 /**
00235  * @brief Get field chan7_raw from rc_channels_override message
00236  *
00237  * @return RC channel 7 value, in microseconds
00238  */
00239 static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg)
00240 {
00241     generic_16bit r;
00242     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
00243     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
00244     return (uint16_t)r.s;
00245 }
00246 
00247 /**
00248  * @brief Get field chan8_raw from rc_channels_override message
00249  *
00250  * @return RC channel 8 value, in microseconds
00251  */
00252 static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg)
00253 {
00254     generic_16bit r;
00255     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
00256     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
00257     return (uint16_t)r.s;
00258 }
00259 
00260 /**
00261  * @brief Decode a rc_channels_override message into a struct
00262  *
00263  * @param msg The message to decode
00264  * @param rc_channels_override C-struct to decode the message contents into
00265  */
00266 static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message_t* msg, mavlink_rc_channels_override_t* rc_channels_override)
00267 {
00268     rc_channels_override->target_system = mavlink_msg_rc_channels_override_get_target_system(msg);
00269     rc_channels_override->target_component = mavlink_msg_rc_channels_override_get_target_component(msg);
00270     rc_channels_override->chan1_raw = mavlink_msg_rc_channels_override_get_chan1_raw(msg);
00271     rc_channels_override->chan2_raw = mavlink_msg_rc_channels_override_get_chan2_raw(msg);
00272     rc_channels_override->chan3_raw = mavlink_msg_rc_channels_override_get_chan3_raw(msg);
00273     rc_channels_override->chan4_raw = mavlink_msg_rc_channels_override_get_chan4_raw(msg);
00274     rc_channels_override->chan5_raw = mavlink_msg_rc_channels_override_get_chan5_raw(msg);
00275     rc_channels_override->chan6_raw = mavlink_msg_rc_channels_override_get_chan6_raw(msg);
00276     rc_channels_override->chan7_raw = mavlink_msg_rc_channels_override_get_chan7_raw(msg);
00277     rc_channels_override->chan8_raw = mavlink_msg_rc_channels_override_get_chan8_raw(msg);
00278 }