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

mavlink_msg_watchdog_heartbeat.h

00001 // MESSAGE WATCHDOG_HEARTBEAT PACKING
00002 
00003 #define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT 150
00004 
00005 typedef struct __mavlink_watchdog_heartbeat_t 
00006 {
00007     uint16_t watchdog_id; ///< Watchdog ID
00008     uint16_t process_count; ///< Number of processes
00009 
00010 } mavlink_watchdog_heartbeat_t;
00011 
00012 
00013 
00014 /**
00015  * @brief Pack a watchdog_heartbeat message
00016  * @param system_id ID of this system
00017  * @param component_id ID of this component (e.g. 200 for IMU)
00018  * @param msg The MAVLink message to compress the data into
00019  *
00020  * @param watchdog_id Watchdog ID
00021  * @param process_count Number of processes
00022  * @return length of the message in bytes (excluding serial stream start sign)
00023  */
00024 static inline uint16_t mavlink_msg_watchdog_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_count)
00025 {
00026     uint16_t i = 0;
00027     msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT;
00028 
00029     i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
00030     i += put_uint16_t_by_index(process_count, i, msg->payload); // Number of processes
00031 
00032     return mavlink_finalize_message(msg, system_id, component_id, i);
00033 }
00034 
00035 /**
00036  * @brief Pack a watchdog_heartbeat message
00037  * @param system_id ID of this system
00038  * @param component_id ID of this component (e.g. 200 for IMU)
00039  * @param chan The MAVLink channel this message was sent over
00040  * @param msg The MAVLink message to compress the data into
00041  * @param watchdog_id Watchdog ID
00042  * @param process_count Number of processes
00043  * @return length of the message in bytes (excluding serial stream start sign)
00044  */
00045 static inline uint16_t mavlink_msg_watchdog_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_count)
00046 {
00047     uint16_t i = 0;
00048     msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT;
00049 
00050     i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
00051     i += put_uint16_t_by_index(process_count, i, msg->payload); // Number of processes
00052 
00053     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00054 }
00055 
00056 /**
00057  * @brief Encode a watchdog_heartbeat struct into a message
00058  *
00059  * @param system_id ID of this system
00060  * @param component_id ID of this component (e.g. 200 for IMU)
00061  * @param msg The MAVLink message to compress the data into
00062  * @param watchdog_heartbeat C-struct to read the message contents from
00063  */
00064 static inline uint16_t mavlink_msg_watchdog_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_heartbeat_t* watchdog_heartbeat)
00065 {
00066     return mavlink_msg_watchdog_heartbeat_pack(system_id, component_id, msg, watchdog_heartbeat->watchdog_id, watchdog_heartbeat->process_count);
00067 }
00068 
00069 /**
00070  * @brief Send a watchdog_heartbeat message
00071  * @param chan MAVLink channel to send the message
00072  *
00073  * @param watchdog_id Watchdog ID
00074  * @param process_count Number of processes
00075  */
00076 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00077 
00078 static inline void mavlink_msg_watchdog_heartbeat_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_count)
00079 {
00080     mavlink_message_t msg;
00081     mavlink_msg_watchdog_heartbeat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, watchdog_id, process_count);
00082     mavlink_send_uart(chan, &msg);
00083 }
00084 
00085 #endif
00086 // MESSAGE WATCHDOG_HEARTBEAT UNPACKING
00087 
00088 /**
00089  * @brief Get field watchdog_id from watchdog_heartbeat message
00090  *
00091  * @return Watchdog ID
00092  */
00093 static inline uint16_t mavlink_msg_watchdog_heartbeat_get_watchdog_id(const mavlink_message_t* msg)
00094 {
00095     generic_16bit r;
00096     r.b[1] = (msg->payload)[0];
00097     r.b[0] = (msg->payload)[1];
00098     return (uint16_t)r.s;
00099 }
00100 
00101 /**
00102  * @brief Get field process_count from watchdog_heartbeat message
00103  *
00104  * @return Number of processes
00105  */
00106 static inline uint16_t mavlink_msg_watchdog_heartbeat_get_process_count(const mavlink_message_t* msg)
00107 {
00108     generic_16bit r;
00109     r.b[1] = (msg->payload+sizeof(uint16_t))[0];
00110     r.b[0] = (msg->payload+sizeof(uint16_t))[1];
00111     return (uint16_t)r.s;
00112 }
00113 
00114 /**
00115  * @brief Decode a watchdog_heartbeat message into a struct
00116  *
00117  * @param msg The message to decode
00118  * @param watchdog_heartbeat C-struct to decode the message contents into
00119  */
00120 static inline void mavlink_msg_watchdog_heartbeat_decode(const mavlink_message_t* msg, mavlink_watchdog_heartbeat_t* watchdog_heartbeat)
00121 {
00122     watchdog_heartbeat->watchdog_id = mavlink_msg_watchdog_heartbeat_get_watchdog_id(msg);
00123     watchdog_heartbeat->process_count = mavlink_msg_watchdog_heartbeat_get_process_count(msg);
00124 }