Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Committer:
shimniok
Date:
Wed Jun 20 14:57:48 2012 +0000
Revision:
0:826c6171fc1b
Updated documentation

Who changed what in which revision?

UserRevisionLine numberNew contents of line
shimniok 0:826c6171fc1b 1 // MESSAGE WATCHDOG_HEARTBEAT PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT 150
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_watchdog_heartbeat_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 uint16_t watchdog_id; ///< Watchdog ID
shimniok 0:826c6171fc1b 8 uint16_t process_count; ///< Number of processes
shimniok 0:826c6171fc1b 9
shimniok 0:826c6171fc1b 10 } mavlink_watchdog_heartbeat_t;
shimniok 0:826c6171fc1b 11
shimniok 0:826c6171fc1b 12
shimniok 0:826c6171fc1b 13
shimniok 0:826c6171fc1b 14 /**
shimniok 0:826c6171fc1b 15 * @brief Pack a watchdog_heartbeat message
shimniok 0:826c6171fc1b 16 * @param system_id ID of this system
shimniok 0:826c6171fc1b 17 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 18 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 19 *
shimniok 0:826c6171fc1b 20 * @param watchdog_id Watchdog ID
shimniok 0:826c6171fc1b 21 * @param process_count Number of processes
shimniok 0:826c6171fc1b 22 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 23 */
shimniok 0:826c6171fc1b 24 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)
shimniok 0:826c6171fc1b 25 {
shimniok 0:826c6171fc1b 26 uint16_t i = 0;
shimniok 0:826c6171fc1b 27 msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT;
shimniok 0:826c6171fc1b 28
shimniok 0:826c6171fc1b 29 i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
shimniok 0:826c6171fc1b 30 i += put_uint16_t_by_index(process_count, i, msg->payload); // Number of processes
shimniok 0:826c6171fc1b 31
shimniok 0:826c6171fc1b 32 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:826c6171fc1b 33 }
shimniok 0:826c6171fc1b 34
shimniok 0:826c6171fc1b 35 /**
shimniok 0:826c6171fc1b 36 * @brief Pack a watchdog_heartbeat message
shimniok 0:826c6171fc1b 37 * @param system_id ID of this system
shimniok 0:826c6171fc1b 38 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 39 * @param chan The MAVLink channel this message was sent over
shimniok 0:826c6171fc1b 40 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 41 * @param watchdog_id Watchdog ID
shimniok 0:826c6171fc1b 42 * @param process_count Number of processes
shimniok 0:826c6171fc1b 43 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 44 */
shimniok 0:826c6171fc1b 45 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)
shimniok 0:826c6171fc1b 46 {
shimniok 0:826c6171fc1b 47 uint16_t i = 0;
shimniok 0:826c6171fc1b 48 msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT;
shimniok 0:826c6171fc1b 49
shimniok 0:826c6171fc1b 50 i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
shimniok 0:826c6171fc1b 51 i += put_uint16_t_by_index(process_count, i, msg->payload); // Number of processes
shimniok 0:826c6171fc1b 52
shimniok 0:826c6171fc1b 53 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:826c6171fc1b 54 }
shimniok 0:826c6171fc1b 55
shimniok 0:826c6171fc1b 56 /**
shimniok 0:826c6171fc1b 57 * @brief Encode a watchdog_heartbeat struct into a message
shimniok 0:826c6171fc1b 58 *
shimniok 0:826c6171fc1b 59 * @param system_id ID of this system
shimniok 0:826c6171fc1b 60 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 61 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 62 * @param watchdog_heartbeat C-struct to read the message contents from
shimniok 0:826c6171fc1b 63 */
shimniok 0:826c6171fc1b 64 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)
shimniok 0:826c6171fc1b 65 {
shimniok 0:826c6171fc1b 66 return mavlink_msg_watchdog_heartbeat_pack(system_id, component_id, msg, watchdog_heartbeat->watchdog_id, watchdog_heartbeat->process_count);
shimniok 0:826c6171fc1b 67 }
shimniok 0:826c6171fc1b 68
shimniok 0:826c6171fc1b 69 /**
shimniok 0:826c6171fc1b 70 * @brief Send a watchdog_heartbeat message
shimniok 0:826c6171fc1b 71 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 72 *
shimniok 0:826c6171fc1b 73 * @param watchdog_id Watchdog ID
shimniok 0:826c6171fc1b 74 * @param process_count Number of processes
shimniok 0:826c6171fc1b 75 */
shimniok 0:826c6171fc1b 76 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:826c6171fc1b 77
shimniok 0:826c6171fc1b 78 static inline void mavlink_msg_watchdog_heartbeat_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_count)
shimniok 0:826c6171fc1b 79 {
shimniok 0:826c6171fc1b 80 mavlink_message_t msg;
shimniok 0:826c6171fc1b 81 mavlink_msg_watchdog_heartbeat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, watchdog_id, process_count);
shimniok 0:826c6171fc1b 82 mavlink_send_uart(chan, &msg);
shimniok 0:826c6171fc1b 83 }
shimniok 0:826c6171fc1b 84
shimniok 0:826c6171fc1b 85 #endif
shimniok 0:826c6171fc1b 86 // MESSAGE WATCHDOG_HEARTBEAT UNPACKING
shimniok 0:826c6171fc1b 87
shimniok 0:826c6171fc1b 88 /**
shimniok 0:826c6171fc1b 89 * @brief Get field watchdog_id from watchdog_heartbeat message
shimniok 0:826c6171fc1b 90 *
shimniok 0:826c6171fc1b 91 * @return Watchdog ID
shimniok 0:826c6171fc1b 92 */
shimniok 0:826c6171fc1b 93 static inline uint16_t mavlink_msg_watchdog_heartbeat_get_watchdog_id(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 94 {
shimniok 0:826c6171fc1b 95 generic_16bit r;
shimniok 0:826c6171fc1b 96 r.b[1] = (msg->payload)[0];
shimniok 0:826c6171fc1b 97 r.b[0] = (msg->payload)[1];
shimniok 0:826c6171fc1b 98 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 99 }
shimniok 0:826c6171fc1b 100
shimniok 0:826c6171fc1b 101 /**
shimniok 0:826c6171fc1b 102 * @brief Get field process_count from watchdog_heartbeat message
shimniok 0:826c6171fc1b 103 *
shimniok 0:826c6171fc1b 104 * @return Number of processes
shimniok 0:826c6171fc1b 105 */
shimniok 0:826c6171fc1b 106 static inline uint16_t mavlink_msg_watchdog_heartbeat_get_process_count(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 107 {
shimniok 0:826c6171fc1b 108 generic_16bit r;
shimniok 0:826c6171fc1b 109 r.b[1] = (msg->payload+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 110 r.b[0] = (msg->payload+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 111 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 112 }
shimniok 0:826c6171fc1b 113
shimniok 0:826c6171fc1b 114 /**
shimniok 0:826c6171fc1b 115 * @brief Decode a watchdog_heartbeat message into a struct
shimniok 0:826c6171fc1b 116 *
shimniok 0:826c6171fc1b 117 * @param msg The message to decode
shimniok 0:826c6171fc1b 118 * @param watchdog_heartbeat C-struct to decode the message contents into
shimniok 0:826c6171fc1b 119 */
shimniok 0:826c6171fc1b 120 static inline void mavlink_msg_watchdog_heartbeat_decode(const mavlink_message_t* msg, mavlink_watchdog_heartbeat_t* watchdog_heartbeat)
shimniok 0:826c6171fc1b 121 {
shimniok 0:826c6171fc1b 122 watchdog_heartbeat->watchdog_id = mavlink_msg_watchdog_heartbeat_get_watchdog_id(msg);
shimniok 0:826c6171fc1b 123 watchdog_heartbeat->process_count = mavlink_msg_watchdog_heartbeat_get_process_count(msg);
shimniok 0:826c6171fc1b 124 }