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_command.h
00001 // MESSAGE COMMAND PACKING 00002 00003 #define MAVLINK_MSG_ID_COMMAND 75 00004 00005 typedef struct __mavlink_command_t 00006 { 00007 uint8_t target_system; ///< System which should execute the command 00008 uint8_t target_component; ///< Component which should execute the command, 0 for all components 00009 uint8_t command; ///< Command ID, as defined by MAV_CMD enum. 00010 uint8_t confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) 00011 float param1; ///< Parameter 1, as defined by MAV_CMD enum. 00012 float param2; ///< Parameter 2, as defined by MAV_CMD enum. 00013 float param3; ///< Parameter 3, as defined by MAV_CMD enum. 00014 float param4; ///< Parameter 4, as defined by MAV_CMD enum. 00015 00016 } mavlink_command_t; 00017 00018 00019 00020 /** 00021 * @brief Pack a command message 00022 * @param system_id ID of this system 00023 * @param component_id ID of this component (e.g. 200 for IMU) 00024 * @param msg The MAVLink message to compress the data into 00025 * 00026 * @param target_system System which should execute the command 00027 * @param target_component Component which should execute the command, 0 for all components 00028 * @param command Command ID, as defined by MAV_CMD enum. 00029 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) 00030 * @param param1 Parameter 1, as defined by MAV_CMD enum. 00031 * @param param2 Parameter 2, as defined by MAV_CMD enum. 00032 * @param param3 Parameter 3, as defined by MAV_CMD enum. 00033 * @param param4 Parameter 4, as defined by MAV_CMD enum. 00034 * @return length of the message in bytes (excluding serial stream start sign) 00035 */ 00036 static inline uint16_t mavlink_msg_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4) 00037 { 00038 uint16_t i = 0; 00039 msg->msgid = MAVLINK_MSG_ID_COMMAND; 00040 00041 i += put_uint8_t_by_index(target_system, i, msg->payload); // System which should execute the command 00042 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component which should execute the command, 0 for all components 00043 i += put_uint8_t_by_index(command, i, msg->payload); // Command ID, as defined by MAV_CMD enum. 00044 i += put_uint8_t_by_index(confirmation, i, msg->payload); // 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) 00045 i += put_float_by_index(param1, i, msg->payload); // Parameter 1, as defined by MAV_CMD enum. 00046 i += put_float_by_index(param2, i, msg->payload); // Parameter 2, as defined by MAV_CMD enum. 00047 i += put_float_by_index(param3, i, msg->payload); // Parameter 3, as defined by MAV_CMD enum. 00048 i += put_float_by_index(param4, i, msg->payload); // Parameter 4, as defined by MAV_CMD enum. 00049 00050 return mavlink_finalize_message(msg, system_id, component_id, i); 00051 } 00052 00053 /** 00054 * @brief Pack a command message 00055 * @param system_id ID of this system 00056 * @param component_id ID of this component (e.g. 200 for IMU) 00057 * @param chan The MAVLink channel this message was sent over 00058 * @param msg The MAVLink message to compress the data into 00059 * @param target_system System which should execute the command 00060 * @param target_component Component which should execute the command, 0 for all components 00061 * @param command Command ID, as defined by MAV_CMD enum. 00062 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) 00063 * @param param1 Parameter 1, as defined by MAV_CMD enum. 00064 * @param param2 Parameter 2, as defined by MAV_CMD enum. 00065 * @param param3 Parameter 3, as defined by MAV_CMD enum. 00066 * @param param4 Parameter 4, as defined by MAV_CMD enum. 00067 * @return length of the message in bytes (excluding serial stream start sign) 00068 */ 00069 static inline uint16_t mavlink_msg_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4) 00070 { 00071 uint16_t i = 0; 00072 msg->msgid = MAVLINK_MSG_ID_COMMAND; 00073 00074 i += put_uint8_t_by_index(target_system, i, msg->payload); // System which should execute the command 00075 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component which should execute the command, 0 for all components 00076 i += put_uint8_t_by_index(command, i, msg->payload); // Command ID, as defined by MAV_CMD enum. 00077 i += put_uint8_t_by_index(confirmation, i, msg->payload); // 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) 00078 i += put_float_by_index(param1, i, msg->payload); // Parameter 1, as defined by MAV_CMD enum. 00079 i += put_float_by_index(param2, i, msg->payload); // Parameter 2, as defined by MAV_CMD enum. 00080 i += put_float_by_index(param3, i, msg->payload); // Parameter 3, as defined by MAV_CMD enum. 00081 i += put_float_by_index(param4, i, msg->payload); // Parameter 4, as defined by MAV_CMD enum. 00082 00083 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00084 } 00085 00086 /** 00087 * @brief Encode a command struct into a message 00088 * 00089 * @param system_id ID of this system 00090 * @param component_id ID of this component (e.g. 200 for IMU) 00091 * @param msg The MAVLink message to compress the data into 00092 * @param command C-struct to read the message contents from 00093 */ 00094 static inline uint16_t mavlink_msg_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_t* command) 00095 { 00096 return mavlink_msg_command_pack(system_id, component_id, msg, command->target_system, command->target_component, command->command, command->confirmation, command->param1, command->param2, command->param3, command->param4); 00097 } 00098 00099 /** 00100 * @brief Send a command message 00101 * @param chan MAVLink channel to send the message 00102 * 00103 * @param target_system System which should execute the command 00104 * @param target_component Component which should execute the command, 0 for all components 00105 * @param command Command ID, as defined by MAV_CMD enum. 00106 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) 00107 * @param param1 Parameter 1, as defined by MAV_CMD enum. 00108 * @param param2 Parameter 2, as defined by MAV_CMD enum. 00109 * @param param3 Parameter 3, as defined by MAV_CMD enum. 00110 * @param param4 Parameter 4, as defined by MAV_CMD enum. 00111 */ 00112 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00113 00114 static inline void mavlink_msg_command_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4) 00115 { 00116 mavlink_message_t msg; 00117 mavlink_msg_command_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, command, confirmation, param1, param2, param3, param4); 00118 mavlink_send_uart(chan, &msg); 00119 } 00120 00121 #endif 00122 // MESSAGE COMMAND UNPACKING 00123 00124 /** 00125 * @brief Get field target_system from command message 00126 * 00127 * @return System which should execute the command 00128 */ 00129 static inline uint8_t mavlink_msg_command_get_target_system(const mavlink_message_t* msg) 00130 { 00131 return (uint8_t)(msg->payload)[0]; 00132 } 00133 00134 /** 00135 * @brief Get field target_component from command message 00136 * 00137 * @return Component which should execute the command, 0 for all components 00138 */ 00139 static inline uint8_t mavlink_msg_command_get_target_component(const mavlink_message_t* msg) 00140 { 00141 return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; 00142 } 00143 00144 /** 00145 * @brief Get field command from command message 00146 * 00147 * @return Command ID, as defined by MAV_CMD enum. 00148 */ 00149 static inline uint8_t mavlink_msg_command_get_command(const mavlink_message_t* msg) 00150 { 00151 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; 00152 } 00153 00154 /** 00155 * @brief Get field confirmation from command message 00156 * 00157 * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) 00158 */ 00159 static inline uint8_t mavlink_msg_command_get_confirmation(const mavlink_message_t* msg) 00160 { 00161 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; 00162 } 00163 00164 /** 00165 * @brief Get field param1 from command message 00166 * 00167 * @return Parameter 1, as defined by MAV_CMD enum. 00168 */ 00169 static inline float mavlink_msg_command_get_param1(const mavlink_message_t* msg) 00170 { 00171 generic_32bit r; 00172 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; 00173 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; 00174 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[2]; 00175 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[3]; 00176 return (float)r.f; 00177 } 00178 00179 /** 00180 * @brief Get field param2 from command message 00181 * 00182 * @return Parameter 2, as defined by MAV_CMD enum. 00183 */ 00184 static inline float mavlink_msg_command_get_param2(const mavlink_message_t* msg) 00185 { 00186 generic_32bit r; 00187 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; 00188 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1]; 00189 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2]; 00190 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3]; 00191 return (float)r.f; 00192 } 00193 00194 /** 00195 * @brief Get field param3 from command message 00196 * 00197 * @return Parameter 3, as defined by MAV_CMD enum. 00198 */ 00199 static inline float mavlink_msg_command_get_param3(const mavlink_message_t* msg) 00200 { 00201 generic_32bit r; 00202 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; 00203 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; 00204 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; 00205 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; 00206 return (float)r.f; 00207 } 00208 00209 /** 00210 * @brief Get field param4 from command message 00211 * 00212 * @return Parameter 4, as defined by MAV_CMD enum. 00213 */ 00214 static inline float mavlink_msg_command_get_param4(const mavlink_message_t* msg) 00215 { 00216 generic_32bit r; 00217 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00218 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00219 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00220 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00221 return (float)r.f; 00222 } 00223 00224 /** 00225 * @brief Decode a command message into a struct 00226 * 00227 * @param msg The message to decode 00228 * @param command C-struct to decode the message contents into 00229 */ 00230 static inline void mavlink_msg_command_decode(const mavlink_message_t* msg, mavlink_command_t* command) 00231 { 00232 command->target_system = mavlink_msg_command_get_target_system(msg); 00233 command->target_component = mavlink_msg_command_get_target_component(msg); 00234 command->command = mavlink_msg_command_get_command(msg); 00235 command->confirmation = mavlink_msg_command_get_confirmation(msg); 00236 command->param1 = mavlink_msg_command_get_param1(msg); 00237 command->param2 = mavlink_msg_command_get_param2(msg); 00238 command->param3 = mavlink_msg_command_get_param3(msg); 00239 command->param4 = mavlink_msg_command_get_param4(msg); 00240 }
Generated on Tue Jul 12 2022 14:09:26 by 1.7.2