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

mavlink_msg_watchdog_process_status.h

00001 // MESSAGE WATCHDOG_PROCESS_STATUS PACKING
00002 
00003 #define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS 152
00004 
00005 typedef struct __mavlink_watchdog_process_status_t 
00006 {
00007     uint16_t watchdog_id; ///< Watchdog ID
00008     uint16_t process_id; ///< Process ID
00009     uint8_t state; ///< Is running / finished / suspended / crashed
00010     uint8_t muted; ///< Is muted
00011     int32_t pid; ///< PID
00012     uint16_t crashes; ///< Number of crashes
00013 
00014 } mavlink_watchdog_process_status_t;
00015 
00016 
00017 
00018 /**
00019  * @brief Pack a watchdog_process_status 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 watchdog_id Watchdog ID
00025  * @param process_id Process ID
00026  * @param state Is running / finished / suspended / crashed
00027  * @param muted Is muted
00028  * @param pid PID
00029  * @param crashes Number of crashes
00030  * @return length of the message in bytes (excluding serial stream start sign)
00031  */
00032 static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
00033 {
00034     uint16_t i = 0;
00035     msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS;
00036 
00037     i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
00038     i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
00039     i += put_uint8_t_by_index(state, i, msg->payload); // Is running / finished / suspended / crashed
00040     i += put_uint8_t_by_index(muted, i, msg->payload); // Is muted
00041     i += put_int32_t_by_index(pid, i, msg->payload); // PID
00042     i += put_uint16_t_by_index(crashes, i, msg->payload); // Number of crashes
00043 
00044     return mavlink_finalize_message(msg, system_id, component_id, i);
00045 }
00046 
00047 /**
00048  * @brief Pack a watchdog_process_status 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 watchdog_id Watchdog ID
00054  * @param process_id Process ID
00055  * @param state Is running / finished / suspended / crashed
00056  * @param muted Is muted
00057  * @param pid PID
00058  * @param crashes Number of crashes
00059  * @return length of the message in bytes (excluding serial stream start sign)
00060  */
00061 static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
00062 {
00063     uint16_t i = 0;
00064     msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS;
00065 
00066     i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
00067     i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
00068     i += put_uint8_t_by_index(state, i, msg->payload); // Is running / finished / suspended / crashed
00069     i += put_uint8_t_by_index(muted, i, msg->payload); // Is muted
00070     i += put_int32_t_by_index(pid, i, msg->payload); // PID
00071     i += put_uint16_t_by_index(crashes, i, msg->payload); // Number of crashes
00072 
00073     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00074 }
00075 
00076 /**
00077  * @brief Encode a watchdog_process_status 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 watchdog_process_status C-struct to read the message contents from
00083  */
00084 static inline uint16_t mavlink_msg_watchdog_process_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_status_t* watchdog_process_status)
00085 {
00086     return mavlink_msg_watchdog_process_status_pack(system_id, component_id, msg, watchdog_process_status->watchdog_id, watchdog_process_status->process_id, watchdog_process_status->state, watchdog_process_status->muted, watchdog_process_status->pid, watchdog_process_status->crashes);
00087 }
00088 
00089 /**
00090  * @brief Send a watchdog_process_status message
00091  * @param chan MAVLink channel to send the message
00092  *
00093  * @param watchdog_id Watchdog ID
00094  * @param process_id Process ID
00095  * @param state Is running / finished / suspended / crashed
00096  * @param muted Is muted
00097  * @param pid PID
00098  * @param crashes Number of crashes
00099  */
00100 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00101 
00102 static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
00103 {
00104     mavlink_message_t msg;
00105     mavlink_msg_watchdog_process_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, watchdog_id, process_id, state, muted, pid, crashes);
00106     mavlink_send_uart(chan, &msg);
00107 }
00108 
00109 #endif
00110 // MESSAGE WATCHDOG_PROCESS_STATUS UNPACKING
00111 
00112 /**
00113  * @brief Get field watchdog_id from watchdog_process_status message
00114  *
00115  * @return Watchdog ID
00116  */
00117 static inline uint16_t mavlink_msg_watchdog_process_status_get_watchdog_id(const mavlink_message_t* msg)
00118 {
00119     generic_16bit r;
00120     r.b[1] = (msg->payload)[0];
00121     r.b[0] = (msg->payload)[1];
00122     return (uint16_t)r.s;
00123 }
00124 
00125 /**
00126  * @brief Get field process_id from watchdog_process_status message
00127  *
00128  * @return Process ID
00129  */
00130 static inline uint16_t mavlink_msg_watchdog_process_status_get_process_id(const mavlink_message_t* msg)
00131 {
00132     generic_16bit r;
00133     r.b[1] = (msg->payload+sizeof(uint16_t))[0];
00134     r.b[0] = (msg->payload+sizeof(uint16_t))[1];
00135     return (uint16_t)r.s;
00136 }
00137 
00138 /**
00139  * @brief Get field state from watchdog_process_status message
00140  *
00141  * @return Is running / finished / suspended / crashed
00142  */
00143 static inline uint8_t mavlink_msg_watchdog_process_status_get_state(const mavlink_message_t* msg)
00144 {
00145     return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0];
00146 }
00147 
00148 /**
00149  * @brief Get field muted from watchdog_process_status message
00150  *
00151  * @return Is muted
00152  */
00153 static inline uint8_t mavlink_msg_watchdog_process_status_get_muted(const mavlink_message_t* msg)
00154 {
00155     return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[0];
00156 }
00157 
00158 /**
00159  * @brief Get field pid from watchdog_process_status message
00160  *
00161  * @return PID
00162  */
00163 static inline int32_t mavlink_msg_watchdog_process_status_get_pid(const mavlink_message_t* msg)
00164 {
00165     generic_32bit r;
00166     r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
00167     r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
00168     r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[2];
00169     r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[3];
00170     return (int32_t)r.i;
00171 }
00172 
00173 /**
00174  * @brief Get field crashes from watchdog_process_status message
00175  *
00176  * @return Number of crashes
00177  */
00178 static inline uint16_t mavlink_msg_watchdog_process_status_get_crashes(const mavlink_message_t* msg)
00179 {
00180     generic_16bit r;
00181     r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[0];
00182     r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[1];
00183     return (uint16_t)r.s;
00184 }
00185 
00186 /**
00187  * @brief Decode a watchdog_process_status message into a struct
00188  *
00189  * @param msg The message to decode
00190  * @param watchdog_process_status C-struct to decode the message contents into
00191  */
00192 static inline void mavlink_msg_watchdog_process_status_decode(const mavlink_message_t* msg, mavlink_watchdog_process_status_t* watchdog_process_status)
00193 {
00194     watchdog_process_status->watchdog_id = mavlink_msg_watchdog_process_status_get_watchdog_id(msg);
00195     watchdog_process_status->process_id = mavlink_msg_watchdog_process_status_get_process_id(msg);
00196     watchdog_process_status->state = mavlink_msg_watchdog_process_status_get_state(msg);
00197     watchdog_process_status->muted = mavlink_msg_watchdog_process_status_get_muted(msg);
00198     watchdog_process_status->pid = mavlink_msg_watchdog_process_status_get_pid(msg);
00199     watchdog_process_status->crashes = mavlink_msg_watchdog_process_status_get_crashes(msg);
00200 }