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_servo_output_raw.h Source File

mavlink_msg_servo_output_raw.h

00001 // MESSAGE SERVO_OUTPUT_RAW PACKING
00002 
00003 #define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 37
00004 
00005 typedef struct __mavlink_servo_output_raw_t 
00006 {
00007     uint16_t servo1_raw; ///< Servo output 1 value, in microseconds
00008     uint16_t servo2_raw; ///< Servo output 2 value, in microseconds
00009     uint16_t servo3_raw; ///< Servo output 3 value, in microseconds
00010     uint16_t servo4_raw; ///< Servo output 4 value, in microseconds
00011     uint16_t servo5_raw; ///< Servo output 5 value, in microseconds
00012     uint16_t servo6_raw; ///< Servo output 6 value, in microseconds
00013     uint16_t servo7_raw; ///< Servo output 7 value, in microseconds
00014     uint16_t servo8_raw; ///< Servo output 8 value, in microseconds
00015 
00016 } mavlink_servo_output_raw_t;
00017 
00018 
00019 
00020 /**
00021  * @brief Pack a servo_output_raw message
00022  * @param system_id ID of this system
00023  * @param component_id ID of this component (e.g. 200 for IMU)
00024  * @param msg The MAVLink message to compress the data into
00025  *
00026  * @param servo1_raw Servo output 1 value, in microseconds
00027  * @param servo2_raw Servo output 2 value, in microseconds
00028  * @param servo3_raw Servo output 3 value, in microseconds
00029  * @param servo4_raw Servo output 4 value, in microseconds
00030  * @param servo5_raw Servo output 5 value, in microseconds
00031  * @param servo6_raw Servo output 6 value, in microseconds
00032  * @param servo7_raw Servo output 7 value, in microseconds
00033  * @param servo8_raw Servo output 8 value, in microseconds
00034  * @return length of the message in bytes (excluding serial stream start sign)
00035  */
00036 static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, 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)
00037 {
00038     uint16_t i = 0;
00039     msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
00040 
00041     i += put_uint16_t_by_index(servo1_raw, i, msg->payload); // Servo output 1 value, in microseconds
00042     i += put_uint16_t_by_index(servo2_raw, i, msg->payload); // Servo output 2 value, in microseconds
00043     i += put_uint16_t_by_index(servo3_raw, i, msg->payload); // Servo output 3 value, in microseconds
00044     i += put_uint16_t_by_index(servo4_raw, i, msg->payload); // Servo output 4 value, in microseconds
00045     i += put_uint16_t_by_index(servo5_raw, i, msg->payload); // Servo output 5 value, in microseconds
00046     i += put_uint16_t_by_index(servo6_raw, i, msg->payload); // Servo output 6 value, in microseconds
00047     i += put_uint16_t_by_index(servo7_raw, i, msg->payload); // Servo output 7 value, in microseconds
00048     i += put_uint16_t_by_index(servo8_raw, i, msg->payload); // Servo output 8 value, in microseconds
00049 
00050     return mavlink_finalize_message(msg, system_id, component_id, i);
00051 }
00052 
00053 /**
00054  * @brief Pack a servo_output_raw message
00055  * @param system_id ID of this system
00056  * @param component_id ID of this component (e.g. 200 for IMU)
00057  * @param chan The MAVLink channel this message was sent over
00058  * @param msg The MAVLink message to compress the data into
00059  * @param servo1_raw Servo output 1 value, in microseconds
00060  * @param servo2_raw Servo output 2 value, in microseconds
00061  * @param servo3_raw Servo output 3 value, in microseconds
00062  * @param servo4_raw Servo output 4 value, in microseconds
00063  * @param servo5_raw Servo output 5 value, in microseconds
00064  * @param servo6_raw Servo output 6 value, in microseconds
00065  * @param servo7_raw Servo output 7 value, in microseconds
00066  * @param servo8_raw Servo output 8 value, in microseconds
00067  * @return length of the message in bytes (excluding serial stream start sign)
00068  */
00069 static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, 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)
00070 {
00071     uint16_t i = 0;
00072     msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
00073 
00074     i += put_uint16_t_by_index(servo1_raw, i, msg->payload); // Servo output 1 value, in microseconds
00075     i += put_uint16_t_by_index(servo2_raw, i, msg->payload); // Servo output 2 value, in microseconds
00076     i += put_uint16_t_by_index(servo3_raw, i, msg->payload); // Servo output 3 value, in microseconds
00077     i += put_uint16_t_by_index(servo4_raw, i, msg->payload); // Servo output 4 value, in microseconds
00078     i += put_uint16_t_by_index(servo5_raw, i, msg->payload); // Servo output 5 value, in microseconds
00079     i += put_uint16_t_by_index(servo6_raw, i, msg->payload); // Servo output 6 value, in microseconds
00080     i += put_uint16_t_by_index(servo7_raw, i, msg->payload); // Servo output 7 value, in microseconds
00081     i += put_uint16_t_by_index(servo8_raw, i, msg->payload); // Servo output 8 value, in microseconds
00082 
00083     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00084 }
00085 
00086 /**
00087  * @brief Encode a servo_output_raw struct into a message
00088  *
00089  * @param system_id ID of this system
00090  * @param component_id ID of this component (e.g. 200 for IMU)
00091  * @param msg The MAVLink message to compress the data into
00092  * @param servo_output_raw C-struct to read the message contents from
00093  */
00094 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)
00095 {
00096     return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, 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);
00097 }
00098 
00099 /**
00100  * @brief Send a servo_output_raw message
00101  * @param chan MAVLink channel to send the message
00102  *
00103  * @param servo1_raw Servo output 1 value, in microseconds
00104  * @param servo2_raw Servo output 2 value, in microseconds
00105  * @param servo3_raw Servo output 3 value, in microseconds
00106  * @param servo4_raw Servo output 4 value, in microseconds
00107  * @param servo5_raw Servo output 5 value, in microseconds
00108  * @param servo6_raw Servo output 6 value, in microseconds
00109  * @param servo7_raw Servo output 7 value, in microseconds
00110  * @param servo8_raw Servo output 8 value, in microseconds
00111  */
00112 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00113 
00114 static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, 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)
00115 {
00116     mavlink_message_t msg;
00117     mavlink_msg_servo_output_raw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw);
00118     mavlink_send_uart(chan, &msg);
00119 }
00120 
00121 #endif
00122 // MESSAGE SERVO_OUTPUT_RAW UNPACKING
00123 
00124 /**
00125  * @brief Get field servo1_raw from servo_output_raw message
00126  *
00127  * @return Servo output 1 value, in microseconds
00128  */
00129 static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg)
00130 {
00131     generic_16bit r;
00132     r.b[1] = (msg->payload)[0];
00133     r.b[0] = (msg->payload)[1];
00134     return (uint16_t)r.s;
00135 }
00136 
00137 /**
00138  * @brief Get field servo2_raw from servo_output_raw message
00139  *
00140  * @return Servo output 2 value, in microseconds
00141  */
00142 static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg)
00143 {
00144     generic_16bit r;
00145     r.b[1] = (msg->payload+sizeof(uint16_t))[0];
00146     r.b[0] = (msg->payload+sizeof(uint16_t))[1];
00147     return (uint16_t)r.s;
00148 }
00149 
00150 /**
00151  * @brief Get field servo3_raw from servo_output_raw message
00152  *
00153  * @return Servo output 3 value, in microseconds
00154  */
00155 static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg)
00156 {
00157     generic_16bit r;
00158     r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0];
00159     r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1];
00160     return (uint16_t)r.s;
00161 }
00162 
00163 /**
00164  * @brief Get field servo4_raw from servo_output_raw message
00165  *
00166  * @return Servo output 4 value, in microseconds
00167  */
00168 static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg)
00169 {
00170     generic_16bit r;
00171     r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
00172     r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
00173     return (uint16_t)r.s;
00174 }
00175 
00176 /**
00177  * @brief Get field servo5_raw from servo_output_raw message
00178  *
00179  * @return Servo output 5 value, in microseconds
00180  */
00181 static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg)
00182 {
00183     generic_16bit r;
00184     r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
00185     r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
00186     return (uint16_t)r.s;
00187 }
00188 
00189 /**
00190  * @brief Get field servo6_raw from servo_output_raw message
00191  *
00192  * @return Servo output 6 value, in microseconds
00193  */
00194 static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg)
00195 {
00196     generic_16bit r;
00197     r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
00198     r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
00199     return (uint16_t)r.s;
00200 }
00201 
00202 /**
00203  * @brief Get field servo7_raw from servo_output_raw message
00204  *
00205  * @return Servo output 7 value, in microseconds
00206  */
00207 static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg)
00208 {
00209     generic_16bit r;
00210     r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
00211     r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
00212     return (uint16_t)r.s;
00213 }
00214 
00215 /**
00216  * @brief Get field servo8_raw from servo_output_raw message
00217  *
00218  * @return Servo output 8 value, in microseconds
00219  */
00220 static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg)
00221 {
00222     generic_16bit r;
00223     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];
00224     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];
00225     return (uint16_t)r.s;
00226 }
00227 
00228 /**
00229  * @brief Decode a servo_output_raw message into a struct
00230  *
00231  * @param msg The message to decode
00232  * @param servo_output_raw C-struct to decode the message contents into
00233  */
00234 static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw)
00235 {
00236     servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg);
00237     servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg);
00238     servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg);
00239     servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg);
00240     servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg);
00241     servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg);
00242     servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg);
00243     servo_output_raw->servo8_raw = mavlink_msg_servo_output_raw_get_servo8_raw(msg);
00244 }