Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.
Dependencies: Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo
MAVlink/include/pixhawk/mavlink_msg_watchdog_command.h@0:826c6171fc1b, 2012-06-20 (annotated)
- Committer:
- shimniok
- Date:
- Wed Jun 20 14:57:48 2012 +0000
- Revision:
- 0:826c6171fc1b
Updated documentation
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
shimniok | 0:826c6171fc1b | 1 | // MESSAGE WATCHDOG_COMMAND PACKING |
shimniok | 0:826c6171fc1b | 2 | |
shimniok | 0:826c6171fc1b | 3 | #define MAVLINK_MSG_ID_WATCHDOG_COMMAND 153 |
shimniok | 0:826c6171fc1b | 4 | |
shimniok | 0:826c6171fc1b | 5 | typedef struct __mavlink_watchdog_command_t |
shimniok | 0:826c6171fc1b | 6 | { |
shimniok | 0:826c6171fc1b | 7 | uint8_t target_system_id; ///< Target system ID |
shimniok | 0:826c6171fc1b | 8 | uint16_t watchdog_id; ///< Watchdog ID |
shimniok | 0:826c6171fc1b | 9 | uint16_t process_id; ///< Process ID |
shimniok | 0:826c6171fc1b | 10 | uint8_t command_id; ///< Command ID |
shimniok | 0:826c6171fc1b | 11 | |
shimniok | 0:826c6171fc1b | 12 | } mavlink_watchdog_command_t; |
shimniok | 0:826c6171fc1b | 13 | |
shimniok | 0:826c6171fc1b | 14 | |
shimniok | 0:826c6171fc1b | 15 | |
shimniok | 0:826c6171fc1b | 16 | /** |
shimniok | 0:826c6171fc1b | 17 | * @brief Pack a watchdog_command message |
shimniok | 0:826c6171fc1b | 18 | * @param system_id ID of this system |
shimniok | 0:826c6171fc1b | 19 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:826c6171fc1b | 20 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:826c6171fc1b | 21 | * |
shimniok | 0:826c6171fc1b | 22 | * @param target_system_id Target system ID |
shimniok | 0:826c6171fc1b | 23 | * @param watchdog_id Watchdog ID |
shimniok | 0:826c6171fc1b | 24 | * @param process_id Process ID |
shimniok | 0:826c6171fc1b | 25 | * @param command_id Command ID |
shimniok | 0:826c6171fc1b | 26 | * @return length of the message in bytes (excluding serial stream start sign) |
shimniok | 0:826c6171fc1b | 27 | */ |
shimniok | 0:826c6171fc1b | 28 | static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) |
shimniok | 0:826c6171fc1b | 29 | { |
shimniok | 0:826c6171fc1b | 30 | uint16_t i = 0; |
shimniok | 0:826c6171fc1b | 31 | msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND; |
shimniok | 0:826c6171fc1b | 32 | |
shimniok | 0:826c6171fc1b | 33 | i += put_uint8_t_by_index(target_system_id, i, msg->payload); // Target system ID |
shimniok | 0:826c6171fc1b | 34 | i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID |
shimniok | 0:826c6171fc1b | 35 | i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID |
shimniok | 0:826c6171fc1b | 36 | i += put_uint8_t_by_index(command_id, i, msg->payload); // Command ID |
shimniok | 0:826c6171fc1b | 37 | |
shimniok | 0:826c6171fc1b | 38 | return mavlink_finalize_message(msg, system_id, component_id, i); |
shimniok | 0:826c6171fc1b | 39 | } |
shimniok | 0:826c6171fc1b | 40 | |
shimniok | 0:826c6171fc1b | 41 | /** |
shimniok | 0:826c6171fc1b | 42 | * @brief Pack a watchdog_command message |
shimniok | 0:826c6171fc1b | 43 | * @param system_id ID of this system |
shimniok | 0:826c6171fc1b | 44 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:826c6171fc1b | 45 | * @param chan The MAVLink channel this message was sent over |
shimniok | 0:826c6171fc1b | 46 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:826c6171fc1b | 47 | * @param target_system_id Target system ID |
shimniok | 0:826c6171fc1b | 48 | * @param watchdog_id Watchdog ID |
shimniok | 0:826c6171fc1b | 49 | * @param process_id Process ID |
shimniok | 0:826c6171fc1b | 50 | * @param command_id Command ID |
shimniok | 0:826c6171fc1b | 51 | * @return length of the message in bytes (excluding serial stream start sign) |
shimniok | 0:826c6171fc1b | 52 | */ |
shimniok | 0:826c6171fc1b | 53 | static inline uint16_t mavlink_msg_watchdog_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) |
shimniok | 0:826c6171fc1b | 54 | { |
shimniok | 0:826c6171fc1b | 55 | uint16_t i = 0; |
shimniok | 0:826c6171fc1b | 56 | msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND; |
shimniok | 0:826c6171fc1b | 57 | |
shimniok | 0:826c6171fc1b | 58 | i += put_uint8_t_by_index(target_system_id, i, msg->payload); // Target system ID |
shimniok | 0:826c6171fc1b | 59 | i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID |
shimniok | 0:826c6171fc1b | 60 | i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID |
shimniok | 0:826c6171fc1b | 61 | i += put_uint8_t_by_index(command_id, i, msg->payload); // Command ID |
shimniok | 0:826c6171fc1b | 62 | |
shimniok | 0:826c6171fc1b | 63 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); |
shimniok | 0:826c6171fc1b | 64 | } |
shimniok | 0:826c6171fc1b | 65 | |
shimniok | 0:826c6171fc1b | 66 | /** |
shimniok | 0:826c6171fc1b | 67 | * @brief Encode a watchdog_command struct into a message |
shimniok | 0:826c6171fc1b | 68 | * |
shimniok | 0:826c6171fc1b | 69 | * @param system_id ID of this system |
shimniok | 0:826c6171fc1b | 70 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:826c6171fc1b | 71 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:826c6171fc1b | 72 | * @param watchdog_command C-struct to read the message contents from |
shimniok | 0:826c6171fc1b | 73 | */ |
shimniok | 0:826c6171fc1b | 74 | static inline uint16_t mavlink_msg_watchdog_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_command_t* watchdog_command) |
shimniok | 0:826c6171fc1b | 75 | { |
shimniok | 0:826c6171fc1b | 76 | return mavlink_msg_watchdog_command_pack(system_id, component_id, msg, watchdog_command->target_system_id, watchdog_command->watchdog_id, watchdog_command->process_id, watchdog_command->command_id); |
shimniok | 0:826c6171fc1b | 77 | } |
shimniok | 0:826c6171fc1b | 78 | |
shimniok | 0:826c6171fc1b | 79 | /** |
shimniok | 0:826c6171fc1b | 80 | * @brief Send a watchdog_command message |
shimniok | 0:826c6171fc1b | 81 | * @param chan MAVLink channel to send the message |
shimniok | 0:826c6171fc1b | 82 | * |
shimniok | 0:826c6171fc1b | 83 | * @param target_system_id Target system ID |
shimniok | 0:826c6171fc1b | 84 | * @param watchdog_id Watchdog ID |
shimniok | 0:826c6171fc1b | 85 | * @param process_id Process ID |
shimniok | 0:826c6171fc1b | 86 | * @param command_id Command ID |
shimniok | 0:826c6171fc1b | 87 | */ |
shimniok | 0:826c6171fc1b | 88 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
shimniok | 0:826c6171fc1b | 89 | |
shimniok | 0:826c6171fc1b | 90 | static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) |
shimniok | 0:826c6171fc1b | 91 | { |
shimniok | 0:826c6171fc1b | 92 | mavlink_message_t msg; |
shimniok | 0:826c6171fc1b | 93 | mavlink_msg_watchdog_command_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system_id, watchdog_id, process_id, command_id); |
shimniok | 0:826c6171fc1b | 94 | mavlink_send_uart(chan, &msg); |
shimniok | 0:826c6171fc1b | 95 | } |
shimniok | 0:826c6171fc1b | 96 | |
shimniok | 0:826c6171fc1b | 97 | #endif |
shimniok | 0:826c6171fc1b | 98 | // MESSAGE WATCHDOG_COMMAND UNPACKING |
shimniok | 0:826c6171fc1b | 99 | |
shimniok | 0:826c6171fc1b | 100 | /** |
shimniok | 0:826c6171fc1b | 101 | * @brief Get field target_system_id from watchdog_command message |
shimniok | 0:826c6171fc1b | 102 | * |
shimniok | 0:826c6171fc1b | 103 | * @return Target system ID |
shimniok | 0:826c6171fc1b | 104 | */ |
shimniok | 0:826c6171fc1b | 105 | static inline uint8_t mavlink_msg_watchdog_command_get_target_system_id(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 106 | { |
shimniok | 0:826c6171fc1b | 107 | return (uint8_t)(msg->payload)[0]; |
shimniok | 0:826c6171fc1b | 108 | } |
shimniok | 0:826c6171fc1b | 109 | |
shimniok | 0:826c6171fc1b | 110 | /** |
shimniok | 0:826c6171fc1b | 111 | * @brief Get field watchdog_id from watchdog_command message |
shimniok | 0:826c6171fc1b | 112 | * |
shimniok | 0:826c6171fc1b | 113 | * @return Watchdog ID |
shimniok | 0:826c6171fc1b | 114 | */ |
shimniok | 0:826c6171fc1b | 115 | static inline uint16_t mavlink_msg_watchdog_command_get_watchdog_id(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 116 | { |
shimniok | 0:826c6171fc1b | 117 | generic_16bit r; |
shimniok | 0:826c6171fc1b | 118 | r.b[1] = (msg->payload+sizeof(uint8_t))[0]; |
shimniok | 0:826c6171fc1b | 119 | r.b[0] = (msg->payload+sizeof(uint8_t))[1]; |
shimniok | 0:826c6171fc1b | 120 | return (uint16_t)r.s; |
shimniok | 0:826c6171fc1b | 121 | } |
shimniok | 0:826c6171fc1b | 122 | |
shimniok | 0:826c6171fc1b | 123 | /** |
shimniok | 0:826c6171fc1b | 124 | * @brief Get field process_id from watchdog_command message |
shimniok | 0:826c6171fc1b | 125 | * |
shimniok | 0:826c6171fc1b | 126 | * @return Process ID |
shimniok | 0:826c6171fc1b | 127 | */ |
shimniok | 0:826c6171fc1b | 128 | static inline uint16_t mavlink_msg_watchdog_command_get_process_id(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 129 | { |
shimniok | 0:826c6171fc1b | 130 | generic_16bit r; |
shimniok | 0:826c6171fc1b | 131 | r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[0]; |
shimniok | 0:826c6171fc1b | 132 | r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[1]; |
shimniok | 0:826c6171fc1b | 133 | return (uint16_t)r.s; |
shimniok | 0:826c6171fc1b | 134 | } |
shimniok | 0:826c6171fc1b | 135 | |
shimniok | 0:826c6171fc1b | 136 | /** |
shimniok | 0:826c6171fc1b | 137 | * @brief Get field command_id from watchdog_command message |
shimniok | 0:826c6171fc1b | 138 | * |
shimniok | 0:826c6171fc1b | 139 | * @return Command ID |
shimniok | 0:826c6171fc1b | 140 | */ |
shimniok | 0:826c6171fc1b | 141 | static inline uint8_t mavlink_msg_watchdog_command_get_command_id(const mavlink_message_t* msg) |
shimniok | 0:826c6171fc1b | 142 | { |
shimniok | 0:826c6171fc1b | 143 | return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; |
shimniok | 0:826c6171fc1b | 144 | } |
shimniok | 0:826c6171fc1b | 145 | |
shimniok | 0:826c6171fc1b | 146 | /** |
shimniok | 0:826c6171fc1b | 147 | * @brief Decode a watchdog_command message into a struct |
shimniok | 0:826c6171fc1b | 148 | * |
shimniok | 0:826c6171fc1b | 149 | * @param msg The message to decode |
shimniok | 0:826c6171fc1b | 150 | * @param watchdog_command C-struct to decode the message contents into |
shimniok | 0:826c6171fc1b | 151 | */ |
shimniok | 0:826c6171fc1b | 152 | static inline void mavlink_msg_watchdog_command_decode(const mavlink_message_t* msg, mavlink_watchdog_command_t* watchdog_command) |
shimniok | 0:826c6171fc1b | 153 | { |
shimniok | 0:826c6171fc1b | 154 | watchdog_command->target_system_id = mavlink_msg_watchdog_command_get_target_system_id(msg); |
shimniok | 0:826c6171fc1b | 155 | watchdog_command->watchdog_id = mavlink_msg_watchdog_command_get_watchdog_id(msg); |
shimniok | 0:826c6171fc1b | 156 | watchdog_command->process_id = mavlink_msg_watchdog_command_get_process_id(msg); |
shimniok | 0:826c6171fc1b | 157 | watchdog_command->command_id = mavlink_msg_watchdog_command_get_command_id(msg); |
shimniok | 0:826c6171fc1b | 158 | } |