Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.
Dependencies: Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo
mavlink_msg_action_ack.h
00001 // MESSAGE ACTION_ACK PACKING 00002 00003 #define MAVLINK_MSG_ID_ACTION_ACK 9 00004 00005 typedef struct __mavlink_action_ack_t 00006 { 00007 uint8_t action; ///< The action id 00008 uint8_t result; ///< 0: Action DENIED, 1: Action executed 00009 00010 } mavlink_action_ack_t; 00011 00012 00013 00014 /** 00015 * @brief Pack a action_ack 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 action The action id 00021 * @param result 0: Action DENIED, 1: Action executed 00022 * @return length of the message in bytes (excluding serial stream start sign) 00023 */ 00024 static inline uint16_t mavlink_msg_action_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t action, uint8_t result) 00025 { 00026 uint16_t i = 0; 00027 msg->msgid = MAVLINK_MSG_ID_ACTION_ACK; 00028 00029 i += put_uint8_t_by_index(action, i, msg->payload); // The action id 00030 i += put_uint8_t_by_index(result, i, msg->payload); // 0: Action DENIED, 1: Action executed 00031 00032 return mavlink_finalize_message(msg, system_id, component_id, i); 00033 } 00034 00035 /** 00036 * @brief Pack a action_ack 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 action The action id 00042 * @param result 0: Action DENIED, 1: Action executed 00043 * @return length of the message in bytes (excluding serial stream start sign) 00044 */ 00045 static inline uint16_t mavlink_msg_action_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t action, uint8_t result) 00046 { 00047 uint16_t i = 0; 00048 msg->msgid = MAVLINK_MSG_ID_ACTION_ACK; 00049 00050 i += put_uint8_t_by_index(action, i, msg->payload); // The action id 00051 i += put_uint8_t_by_index(result, i, msg->payload); // 0: Action DENIED, 1: Action executed 00052 00053 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00054 } 00055 00056 /** 00057 * @brief Encode a action_ack 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 action_ack C-struct to read the message contents from 00063 */ 00064 static inline uint16_t mavlink_msg_action_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_action_ack_t* action_ack) 00065 { 00066 return mavlink_msg_action_ack_pack(system_id, component_id, msg, action_ack->action, action_ack->result); 00067 } 00068 00069 /** 00070 * @brief Send a action_ack message 00071 * @param chan MAVLink channel to send the message 00072 * 00073 * @param action The action id 00074 * @param result 0: Action DENIED, 1: Action executed 00075 */ 00076 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00077 00078 static inline void mavlink_msg_action_ack_send(mavlink_channel_t chan, uint8_t action, uint8_t result) 00079 { 00080 mavlink_message_t msg; 00081 mavlink_msg_action_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, action, result); 00082 mavlink_send_uart(chan, &msg); 00083 } 00084 00085 #endif 00086 // MESSAGE ACTION_ACK UNPACKING 00087 00088 /** 00089 * @brief Get field action from action_ack message 00090 * 00091 * @return The action id 00092 */ 00093 static inline uint8_t mavlink_msg_action_ack_get_action(const mavlink_message_t* msg) 00094 { 00095 return (uint8_t)(msg->payload)[0]; 00096 } 00097 00098 /** 00099 * @brief Get field result from action_ack message 00100 * 00101 * @return 0: Action DENIED, 1: Action executed 00102 */ 00103 static inline uint8_t mavlink_msg_action_ack_get_result(const mavlink_message_t* msg) 00104 { 00105 return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; 00106 } 00107 00108 /** 00109 * @brief Decode a action_ack message into a struct 00110 * 00111 * @param msg The message to decode 00112 * @param action_ack C-struct to decode the message contents into 00113 */ 00114 static inline void mavlink_msg_action_ack_decode(const mavlink_message_t* msg, mavlink_action_ack_t* action_ack) 00115 { 00116 action_ack->action = mavlink_msg_action_ack_get_action(msg); 00117 action_ack->result = mavlink_msg_action_ack_get_result(msg); 00118 }
Generated on Tue Jul 12 2022 14:09:26 by 1.7.2