Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.
Dependencies: Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo
mavlink_msg_diagnostic.h
00001 // MESSAGE DIAGNOSTIC PACKING 00002 00003 #define MAVLINK_MSG_ID_DIAGNOSTIC 173 00004 00005 typedef struct __mavlink_diagnostic_t 00006 { 00007 float diagFl1; ///< Diagnostic float 1 00008 float diagFl2; ///< Diagnostic float 2 00009 float diagFl3; ///< Diagnostic float 3 00010 int16_t diagSh1; ///< Diagnostic short 1 00011 int16_t diagSh2; ///< Diagnostic short 2 00012 int16_t diagSh3; ///< Diagnostic short 3 00013 00014 } mavlink_diagnostic_t; 00015 00016 00017 00018 /** 00019 * @brief Pack a diagnostic message 00020 * @param system_id ID of this system 00021 * @param component_id ID of this component (e.g. 200 for IMU) 00022 * @param msg The MAVLink message to compress the data into 00023 * 00024 * @param diagFl1 Diagnostic float 1 00025 * @param diagFl2 Diagnostic float 2 00026 * @param diagFl3 Diagnostic float 3 00027 * @param diagSh1 Diagnostic short 1 00028 * @param diagSh2 Diagnostic short 2 00029 * @param diagSh3 Diagnostic short 3 00030 * @return length of the message in bytes (excluding serial stream start sign) 00031 */ 00032 static inline uint16_t mavlink_msg_diagnostic_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3) 00033 { 00034 uint16_t i = 0; 00035 msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC; 00036 00037 i += put_float_by_index(diagFl1, i, msg->payload); // Diagnostic float 1 00038 i += put_float_by_index(diagFl2, i, msg->payload); // Diagnostic float 2 00039 i += put_float_by_index(diagFl3, i, msg->payload); // Diagnostic float 3 00040 i += put_int16_t_by_index(diagSh1, i, msg->payload); // Diagnostic short 1 00041 i += put_int16_t_by_index(diagSh2, i, msg->payload); // Diagnostic short 2 00042 i += put_int16_t_by_index(diagSh3, i, msg->payload); // Diagnostic short 3 00043 00044 return mavlink_finalize_message(msg, system_id, component_id, i); 00045 } 00046 00047 /** 00048 * @brief Pack a diagnostic message 00049 * @param system_id ID of this system 00050 * @param component_id ID of this component (e.g. 200 for IMU) 00051 * @param chan The MAVLink channel this message was sent over 00052 * @param msg The MAVLink message to compress the data into 00053 * @param diagFl1 Diagnostic float 1 00054 * @param diagFl2 Diagnostic float 2 00055 * @param diagFl3 Diagnostic float 3 00056 * @param diagSh1 Diagnostic short 1 00057 * @param diagSh2 Diagnostic short 2 00058 * @param diagSh3 Diagnostic short 3 00059 * @return length of the message in bytes (excluding serial stream start sign) 00060 */ 00061 static inline uint16_t mavlink_msg_diagnostic_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3) 00062 { 00063 uint16_t i = 0; 00064 msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC; 00065 00066 i += put_float_by_index(diagFl1, i, msg->payload); // Diagnostic float 1 00067 i += put_float_by_index(diagFl2, i, msg->payload); // Diagnostic float 2 00068 i += put_float_by_index(diagFl3, i, msg->payload); // Diagnostic float 3 00069 i += put_int16_t_by_index(diagSh1, i, msg->payload); // Diagnostic short 1 00070 i += put_int16_t_by_index(diagSh2, i, msg->payload); // Diagnostic short 2 00071 i += put_int16_t_by_index(diagSh3, i, msg->payload); // Diagnostic short 3 00072 00073 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00074 } 00075 00076 /** 00077 * @brief Encode a diagnostic struct into a message 00078 * 00079 * @param system_id ID of this system 00080 * @param component_id ID of this component (e.g. 200 for IMU) 00081 * @param msg The MAVLink message to compress the data into 00082 * @param diagnostic C-struct to read the message contents from 00083 */ 00084 static inline uint16_t mavlink_msg_diagnostic_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_diagnostic_t* diagnostic) 00085 { 00086 return mavlink_msg_diagnostic_pack(system_id, component_id, msg, diagnostic->diagFl1, diagnostic->diagFl2, diagnostic->diagFl3, diagnostic->diagSh1, diagnostic->diagSh2, diagnostic->diagSh3); 00087 } 00088 00089 /** 00090 * @brief Send a diagnostic message 00091 * @param chan MAVLink channel to send the message 00092 * 00093 * @param diagFl1 Diagnostic float 1 00094 * @param diagFl2 Diagnostic float 2 00095 * @param diagFl3 Diagnostic float 3 00096 * @param diagSh1 Diagnostic short 1 00097 * @param diagSh2 Diagnostic short 2 00098 * @param diagSh3 Diagnostic short 3 00099 */ 00100 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00101 00102 static inline void mavlink_msg_diagnostic_send(mavlink_channel_t chan, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3) 00103 { 00104 mavlink_message_t msg; 00105 mavlink_msg_diagnostic_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, diagFl1, diagFl2, diagFl3, diagSh1, diagSh2, diagSh3); 00106 mavlink_send_uart(chan, &msg); 00107 } 00108 00109 #endif 00110 // MESSAGE DIAGNOSTIC UNPACKING 00111 00112 /** 00113 * @brief Get field diagFl1 from diagnostic message 00114 * 00115 * @return Diagnostic float 1 00116 */ 00117 static inline float mavlink_msg_diagnostic_get_diagFl1(const mavlink_message_t* msg) 00118 { 00119 generic_32bit r; 00120 r.b[3] = (msg->payload)[0]; 00121 r.b[2] = (msg->payload)[1]; 00122 r.b[1] = (msg->payload)[2]; 00123 r.b[0] = (msg->payload)[3]; 00124 return (float)r.f; 00125 } 00126 00127 /** 00128 * @brief Get field diagFl2 from diagnostic message 00129 * 00130 * @return Diagnostic float 2 00131 */ 00132 static inline float mavlink_msg_diagnostic_get_diagFl2(const mavlink_message_t* msg) 00133 { 00134 generic_32bit r; 00135 r.b[3] = (msg->payload+sizeof(float))[0]; 00136 r.b[2] = (msg->payload+sizeof(float))[1]; 00137 r.b[1] = (msg->payload+sizeof(float))[2]; 00138 r.b[0] = (msg->payload+sizeof(float))[3]; 00139 return (float)r.f; 00140 } 00141 00142 /** 00143 * @brief Get field diagFl3 from diagnostic message 00144 * 00145 * @return Diagnostic float 3 00146 */ 00147 static inline float mavlink_msg_diagnostic_get_diagFl3(const mavlink_message_t* msg) 00148 { 00149 generic_32bit r; 00150 r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0]; 00151 r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1]; 00152 r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2]; 00153 r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3]; 00154 return (float)r.f; 00155 } 00156 00157 /** 00158 * @brief Get field diagSh1 from diagnostic message 00159 * 00160 * @return Diagnostic short 1 00161 */ 00162 static inline int16_t mavlink_msg_diagnostic_get_diagSh1(const mavlink_message_t* msg) 00163 { 00164 generic_16bit r; 00165 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00166 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00167 return (int16_t)r.s; 00168 } 00169 00170 /** 00171 * @brief Get field diagSh2 from diagnostic message 00172 * 00173 * @return Diagnostic short 2 00174 */ 00175 static inline int16_t mavlink_msg_diagnostic_get_diagSh2(const mavlink_message_t* msg) 00176 { 00177 generic_16bit r; 00178 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t))[0]; 00179 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t))[1]; 00180 return (int16_t)r.s; 00181 } 00182 00183 /** 00184 * @brief Get field diagSh3 from diagnostic message 00185 * 00186 * @return Diagnostic short 3 00187 */ 00188 static inline int16_t mavlink_msg_diagnostic_get_diagSh3(const mavlink_message_t* msg) 00189 { 00190 generic_16bit r; 00191 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[0]; 00192 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[1]; 00193 return (int16_t)r.s; 00194 } 00195 00196 /** 00197 * @brief Decode a diagnostic message into a struct 00198 * 00199 * @param msg The message to decode 00200 * @param diagnostic C-struct to decode the message contents into 00201 */ 00202 static inline void mavlink_msg_diagnostic_decode(const mavlink_message_t* msg, mavlink_diagnostic_t* diagnostic) 00203 { 00204 diagnostic->diagFl1 = mavlink_msg_diagnostic_get_diagFl1(msg); 00205 diagnostic->diagFl2 = mavlink_msg_diagnostic_get_diagFl2(msg); 00206 diagnostic->diagFl3 = mavlink_msg_diagnostic_get_diagFl3(msg); 00207 diagnostic->diagSh1 = mavlink_msg_diagnostic_get_diagSh1(msg); 00208 diagnostic->diagSh2 = mavlink_msg_diagnostic_get_diagSh2(msg); 00209 diagnostic->diagSh3 = mavlink_msg_diagnostic_get_diagSh3(msg); 00210 }
Generated on Tue Jul 12 2022 14:09:26 by 1.7.2