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

mavlink_msg_watchdog_process_info.h

00001 // MESSAGE WATCHDOG_PROCESS_INFO PACKING
00002 
00003 #define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO 151
00004 
00005 typedef struct __mavlink_watchdog_process_info_t 
00006 {
00007     uint16_t watchdog_id; ///< Watchdog ID
00008     uint16_t process_id; ///< Process ID
00009     int8_t name[100]; ///< Process name
00010     int8_t arguments[147]; ///< Process arguments
00011     int32_t timeout; ///< Timeout (seconds)
00012 
00013 } mavlink_watchdog_process_info_t;
00014 
00015 #define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_NAME_LEN 100
00016 #define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_ARGUMENTS_LEN 147
00017 
00018 
00019 /**
00020  * @brief Pack a watchdog_process_info message
00021  * @param system_id ID of this system
00022  * @param component_id ID of this component (e.g. 200 for IMU)
00023  * @param msg The MAVLink message to compress the data into
00024  *
00025  * @param watchdog_id Watchdog ID
00026  * @param process_id Process ID
00027  * @param name Process name
00028  * @param arguments Process arguments
00029  * @param timeout Timeout (seconds)
00030  * @return length of the message in bytes (excluding serial stream start sign)
00031  */
00032 static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, const int8_t* name, const int8_t* arguments, int32_t timeout)
00033 {
00034     uint16_t i = 0;
00035     msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO;
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_array_by_index(name, 100, i, msg->payload); // Process name
00040     i += put_array_by_index(arguments, 147, i, msg->payload); // Process arguments
00041     i += put_int32_t_by_index(timeout, i, msg->payload); // Timeout (seconds)
00042 
00043     return mavlink_finalize_message(msg, system_id, component_id, i);
00044 }
00045 
00046 /**
00047  * @brief Pack a watchdog_process_info message
00048  * @param system_id ID of this system
00049  * @param component_id ID of this component (e.g. 200 for IMU)
00050  * @param chan The MAVLink channel this message was sent over
00051  * @param msg The MAVLink message to compress the data into
00052  * @param watchdog_id Watchdog ID
00053  * @param process_id Process ID
00054  * @param name Process name
00055  * @param arguments Process arguments
00056  * @param timeout Timeout (seconds)
00057  * @return length of the message in bytes (excluding serial stream start sign)
00058  */
00059 static inline uint16_t mavlink_msg_watchdog_process_info_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, const int8_t* name, const int8_t* arguments, int32_t timeout)
00060 {
00061     uint16_t i = 0;
00062     msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO;
00063 
00064     i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
00065     i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
00066     i += put_array_by_index(name, 100, i, msg->payload); // Process name
00067     i += put_array_by_index(arguments, 147, i, msg->payload); // Process arguments
00068     i += put_int32_t_by_index(timeout, i, msg->payload); // Timeout (seconds)
00069 
00070     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00071 }
00072 
00073 /**
00074  * @brief Encode a watchdog_process_info struct into a message
00075  *
00076  * @param system_id ID of this system
00077  * @param component_id ID of this component (e.g. 200 for IMU)
00078  * @param msg The MAVLink message to compress the data into
00079  * @param watchdog_process_info C-struct to read the message contents from
00080  */
00081 static inline uint16_t mavlink_msg_watchdog_process_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_info_t* watchdog_process_info)
00082 {
00083     return mavlink_msg_watchdog_process_info_pack(system_id, component_id, msg, watchdog_process_info->watchdog_id, watchdog_process_info->process_id, watchdog_process_info->name, watchdog_process_info->arguments, watchdog_process_info->timeout);
00084 }
00085 
00086 /**
00087  * @brief Send a watchdog_process_info message
00088  * @param chan MAVLink channel to send the message
00089  *
00090  * @param watchdog_id Watchdog ID
00091  * @param process_id Process ID
00092  * @param name Process name
00093  * @param arguments Process arguments
00094  * @param timeout Timeout (seconds)
00095  */
00096 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00097 
00098 static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, const int8_t* name, const int8_t* arguments, int32_t timeout)
00099 {
00100     mavlink_message_t msg;
00101     mavlink_msg_watchdog_process_info_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, watchdog_id, process_id, name, arguments, timeout);
00102     mavlink_send_uart(chan, &msg);
00103 }
00104 
00105 #endif
00106 // MESSAGE WATCHDOG_PROCESS_INFO UNPACKING
00107 
00108 /**
00109  * @brief Get field watchdog_id from watchdog_process_info message
00110  *
00111  * @return Watchdog ID
00112  */
00113 static inline uint16_t mavlink_msg_watchdog_process_info_get_watchdog_id(const mavlink_message_t* msg)
00114 {
00115     generic_16bit r;
00116     r.b[1] = (msg->payload)[0];
00117     r.b[0] = (msg->payload)[1];
00118     return (uint16_t)r.s;
00119 }
00120 
00121 /**
00122  * @brief Get field process_id from watchdog_process_info message
00123  *
00124  * @return Process ID
00125  */
00126 static inline uint16_t mavlink_msg_watchdog_process_info_get_process_id(const mavlink_message_t* msg)
00127 {
00128     generic_16bit r;
00129     r.b[1] = (msg->payload+sizeof(uint16_t))[0];
00130     r.b[0] = (msg->payload+sizeof(uint16_t))[1];
00131     return (uint16_t)r.s;
00132 }
00133 
00134 /**
00135  * @brief Get field name from watchdog_process_info message
00136  *
00137  * @return Process name
00138  */
00139 static inline uint16_t mavlink_msg_watchdog_process_info_get_name(const mavlink_message_t* msg, int8_t* r_data)
00140 {
00141 
00142     memcpy(r_data, msg->payload+sizeof(uint16_t)+sizeof(uint16_t), 100);
00143     return 100;
00144 }
00145 
00146 /**
00147  * @brief Get field arguments from watchdog_process_info message
00148  *
00149  * @return Process arguments
00150  */
00151 static inline uint16_t mavlink_msg_watchdog_process_info_get_arguments(const mavlink_message_t* msg, int8_t* r_data)
00152 {
00153 
00154     memcpy(r_data, msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100, 147);
00155     return 147;
00156 }
00157 
00158 /**
00159  * @brief Get field timeout from watchdog_process_info message
00160  *
00161  * @return Timeout (seconds)
00162  */
00163 static inline int32_t mavlink_msg_watchdog_process_info_get_timeout(const mavlink_message_t* msg)
00164 {
00165     generic_32bit r;
00166     r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[0];
00167     r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[1];
00168     r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[2];
00169     r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[3];
00170     return (int32_t)r.i;
00171 }
00172 
00173 /**
00174  * @brief Decode a watchdog_process_info message into a struct
00175  *
00176  * @param msg The message to decode
00177  * @param watchdog_process_info C-struct to decode the message contents into
00178  */
00179 static inline void mavlink_msg_watchdog_process_info_decode(const mavlink_message_t* msg, mavlink_watchdog_process_info_t* watchdog_process_info)
00180 {
00181     watchdog_process_info->watchdog_id = mavlink_msg_watchdog_process_info_get_watchdog_id(msg);
00182     watchdog_process_info->process_id = mavlink_msg_watchdog_process_info_get_process_id(msg);
00183     mavlink_msg_watchdog_process_info_get_name(msg, watchdog_process_info->name);
00184     mavlink_msg_watchdog_process_info_get_arguments(msg, watchdog_process_info->arguments);
00185     watchdog_process_info->timeout = mavlink_msg_watchdog_process_info_get_timeout(msg);
00186 }