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 COMMAND PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_COMMAND 75
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_command_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 uint8_t target_system; ///< System which should execute the command
shimniok 0:826c6171fc1b 8 uint8_t target_component; ///< Component which should execute the command, 0 for all components
shimniok 0:826c6171fc1b 9 uint8_t command; ///< Command ID, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 10 uint8_t confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
shimniok 0:826c6171fc1b 11 float param1; ///< Parameter 1, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 12 float param2; ///< Parameter 2, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 13 float param3; ///< Parameter 3, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 14 float param4; ///< Parameter 4, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 15
shimniok 0:826c6171fc1b 16 } mavlink_command_t;
shimniok 0:826c6171fc1b 17
shimniok 0:826c6171fc1b 18
shimniok 0:826c6171fc1b 19
shimniok 0:826c6171fc1b 20 /**
shimniok 0:826c6171fc1b 21 * @brief Pack a command message
shimniok 0:826c6171fc1b 22 * @param system_id ID of this system
shimniok 0:826c6171fc1b 23 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 24 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 25 *
shimniok 0:826c6171fc1b 26 * @param target_system System which should execute the command
shimniok 0:826c6171fc1b 27 * @param target_component Component which should execute the command, 0 for all components
shimniok 0:826c6171fc1b 28 * @param command Command ID, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 29 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
shimniok 0:826c6171fc1b 30 * @param param1 Parameter 1, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 31 * @param param2 Parameter 2, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 32 * @param param3 Parameter 3, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 33 * @param param4 Parameter 4, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 34 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 35 */
shimniok 0:826c6171fc1b 36 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)
shimniok 0:826c6171fc1b 37 {
shimniok 0:826c6171fc1b 38 uint16_t i = 0;
shimniok 0:826c6171fc1b 39 msg->msgid = MAVLINK_MSG_ID_COMMAND;
shimniok 0:826c6171fc1b 40
shimniok 0:826c6171fc1b 41 i += put_uint8_t_by_index(target_system, i, msg->payload); // System which should execute the command
shimniok 0:826c6171fc1b 42 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component which should execute the command, 0 for all components
shimniok 0:826c6171fc1b 43 i += put_uint8_t_by_index(command, i, msg->payload); // Command ID, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 44 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)
shimniok 0:826c6171fc1b 45 i += put_float_by_index(param1, i, msg->payload); // Parameter 1, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 46 i += put_float_by_index(param2, i, msg->payload); // Parameter 2, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 47 i += put_float_by_index(param3, i, msg->payload); // Parameter 3, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 48 i += put_float_by_index(param4, i, msg->payload); // Parameter 4, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 49
shimniok 0:826c6171fc1b 50 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:826c6171fc1b 51 }
shimniok 0:826c6171fc1b 52
shimniok 0:826c6171fc1b 53 /**
shimniok 0:826c6171fc1b 54 * @brief Pack a command message
shimniok 0:826c6171fc1b 55 * @param system_id ID of this system
shimniok 0:826c6171fc1b 56 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 57 * @param chan The MAVLink channel this message was sent over
shimniok 0:826c6171fc1b 58 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 59 * @param target_system System which should execute the command
shimniok 0:826c6171fc1b 60 * @param target_component Component which should execute the command, 0 for all components
shimniok 0:826c6171fc1b 61 * @param command Command ID, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 62 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
shimniok 0:826c6171fc1b 63 * @param param1 Parameter 1, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 64 * @param param2 Parameter 2, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 65 * @param param3 Parameter 3, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 66 * @param param4 Parameter 4, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 67 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 68 */
shimniok 0:826c6171fc1b 69 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)
shimniok 0:826c6171fc1b 70 {
shimniok 0:826c6171fc1b 71 uint16_t i = 0;
shimniok 0:826c6171fc1b 72 msg->msgid = MAVLINK_MSG_ID_COMMAND;
shimniok 0:826c6171fc1b 73
shimniok 0:826c6171fc1b 74 i += put_uint8_t_by_index(target_system, i, msg->payload); // System which should execute the command
shimniok 0:826c6171fc1b 75 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component which should execute the command, 0 for all components
shimniok 0:826c6171fc1b 76 i += put_uint8_t_by_index(command, i, msg->payload); // Command ID, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 77 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)
shimniok 0:826c6171fc1b 78 i += put_float_by_index(param1, i, msg->payload); // Parameter 1, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 79 i += put_float_by_index(param2, i, msg->payload); // Parameter 2, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 80 i += put_float_by_index(param3, i, msg->payload); // Parameter 3, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 81 i += put_float_by_index(param4, i, msg->payload); // Parameter 4, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 82
shimniok 0:826c6171fc1b 83 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:826c6171fc1b 84 }
shimniok 0:826c6171fc1b 85
shimniok 0:826c6171fc1b 86 /**
shimniok 0:826c6171fc1b 87 * @brief Encode a command struct into a message
shimniok 0:826c6171fc1b 88 *
shimniok 0:826c6171fc1b 89 * @param system_id ID of this system
shimniok 0:826c6171fc1b 90 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 91 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 92 * @param command C-struct to read the message contents from
shimniok 0:826c6171fc1b 93 */
shimniok 0:826c6171fc1b 94 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)
shimniok 0:826c6171fc1b 95 {
shimniok 0:826c6171fc1b 96 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);
shimniok 0:826c6171fc1b 97 }
shimniok 0:826c6171fc1b 98
shimniok 0:826c6171fc1b 99 /**
shimniok 0:826c6171fc1b 100 * @brief Send a command message
shimniok 0:826c6171fc1b 101 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 102 *
shimniok 0:826c6171fc1b 103 * @param target_system System which should execute the command
shimniok 0:826c6171fc1b 104 * @param target_component Component which should execute the command, 0 for all components
shimniok 0:826c6171fc1b 105 * @param command Command ID, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 106 * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
shimniok 0:826c6171fc1b 107 * @param param1 Parameter 1, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 108 * @param param2 Parameter 2, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 109 * @param param3 Parameter 3, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 110 * @param param4 Parameter 4, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 111 */
shimniok 0:826c6171fc1b 112 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:826c6171fc1b 113
shimniok 0:826c6171fc1b 114 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)
shimniok 0:826c6171fc1b 115 {
shimniok 0:826c6171fc1b 116 mavlink_message_t msg;
shimniok 0:826c6171fc1b 117 mavlink_msg_command_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, command, confirmation, param1, param2, param3, param4);
shimniok 0:826c6171fc1b 118 mavlink_send_uart(chan, &msg);
shimniok 0:826c6171fc1b 119 }
shimniok 0:826c6171fc1b 120
shimniok 0:826c6171fc1b 121 #endif
shimniok 0:826c6171fc1b 122 // MESSAGE COMMAND UNPACKING
shimniok 0:826c6171fc1b 123
shimniok 0:826c6171fc1b 124 /**
shimniok 0:826c6171fc1b 125 * @brief Get field target_system from command message
shimniok 0:826c6171fc1b 126 *
shimniok 0:826c6171fc1b 127 * @return System which should execute the command
shimniok 0:826c6171fc1b 128 */
shimniok 0:826c6171fc1b 129 static inline uint8_t mavlink_msg_command_get_target_system(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 130 {
shimniok 0:826c6171fc1b 131 return (uint8_t)(msg->payload)[0];
shimniok 0:826c6171fc1b 132 }
shimniok 0:826c6171fc1b 133
shimniok 0:826c6171fc1b 134 /**
shimniok 0:826c6171fc1b 135 * @brief Get field target_component from command message
shimniok 0:826c6171fc1b 136 *
shimniok 0:826c6171fc1b 137 * @return Component which should execute the command, 0 for all components
shimniok 0:826c6171fc1b 138 */
shimniok 0:826c6171fc1b 139 static inline uint8_t mavlink_msg_command_get_target_component(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 140 {
shimniok 0:826c6171fc1b 141 return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
shimniok 0:826c6171fc1b 142 }
shimniok 0:826c6171fc1b 143
shimniok 0:826c6171fc1b 144 /**
shimniok 0:826c6171fc1b 145 * @brief Get field command from command message
shimniok 0:826c6171fc1b 146 *
shimniok 0:826c6171fc1b 147 * @return Command ID, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 148 */
shimniok 0:826c6171fc1b 149 static inline uint8_t mavlink_msg_command_get_command(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 150 {
shimniok 0:826c6171fc1b 151 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
shimniok 0:826c6171fc1b 152 }
shimniok 0:826c6171fc1b 153
shimniok 0:826c6171fc1b 154 /**
shimniok 0:826c6171fc1b 155 * @brief Get field confirmation from command message
shimniok 0:826c6171fc1b 156 *
shimniok 0:826c6171fc1b 157 * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
shimniok 0:826c6171fc1b 158 */
shimniok 0:826c6171fc1b 159 static inline uint8_t mavlink_msg_command_get_confirmation(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 160 {
shimniok 0:826c6171fc1b 161 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
shimniok 0:826c6171fc1b 162 }
shimniok 0:826c6171fc1b 163
shimniok 0:826c6171fc1b 164 /**
shimniok 0:826c6171fc1b 165 * @brief Get field param1 from command message
shimniok 0:826c6171fc1b 166 *
shimniok 0:826c6171fc1b 167 * @return Parameter 1, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 168 */
shimniok 0:826c6171fc1b 169 static inline float mavlink_msg_command_get_param1(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 170 {
shimniok 0:826c6171fc1b 171 generic_32bit r;
shimniok 0:826c6171fc1b 172 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
shimniok 0:826c6171fc1b 173 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
shimniok 0:826c6171fc1b 174 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[2];
shimniok 0:826c6171fc1b 175 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[3];
shimniok 0:826c6171fc1b 176 return (float)r.f;
shimniok 0:826c6171fc1b 177 }
shimniok 0:826c6171fc1b 178
shimniok 0:826c6171fc1b 179 /**
shimniok 0:826c6171fc1b 180 * @brief Get field param2 from command message
shimniok 0:826c6171fc1b 181 *
shimniok 0:826c6171fc1b 182 * @return Parameter 2, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 183 */
shimniok 0:826c6171fc1b 184 static inline float mavlink_msg_command_get_param2(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 185 {
shimniok 0:826c6171fc1b 186 generic_32bit r;
shimniok 0:826c6171fc1b 187 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
shimniok 0:826c6171fc1b 188 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
shimniok 0:826c6171fc1b 189 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
shimniok 0:826c6171fc1b 190 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
shimniok 0:826c6171fc1b 191 return (float)r.f;
shimniok 0:826c6171fc1b 192 }
shimniok 0:826c6171fc1b 193
shimniok 0:826c6171fc1b 194 /**
shimniok 0:826c6171fc1b 195 * @brief Get field param3 from command message
shimniok 0:826c6171fc1b 196 *
shimniok 0:826c6171fc1b 197 * @return Parameter 3, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 198 */
shimniok 0:826c6171fc1b 199 static inline float mavlink_msg_command_get_param3(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 200 {
shimniok 0:826c6171fc1b 201 generic_32bit r;
shimniok 0:826c6171fc1b 202 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 203 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 204 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 205 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 206 return (float)r.f;
shimniok 0:826c6171fc1b 207 }
shimniok 0:826c6171fc1b 208
shimniok 0:826c6171fc1b 209 /**
shimniok 0:826c6171fc1b 210 * @brief Get field param4 from command message
shimniok 0:826c6171fc1b 211 *
shimniok 0:826c6171fc1b 212 * @return Parameter 4, as defined by MAV_CMD enum.
shimniok 0:826c6171fc1b 213 */
shimniok 0:826c6171fc1b 214 static inline float mavlink_msg_command_get_param4(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 215 {
shimniok 0:826c6171fc1b 216 generic_32bit r;
shimniok 0:826c6171fc1b 217 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 218 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 219 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 220 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 221 return (float)r.f;
shimniok 0:826c6171fc1b 222 }
shimniok 0:826c6171fc1b 223
shimniok 0:826c6171fc1b 224 /**
shimniok 0:826c6171fc1b 225 * @brief Decode a command message into a struct
shimniok 0:826c6171fc1b 226 *
shimniok 0:826c6171fc1b 227 * @param msg The message to decode
shimniok 0:826c6171fc1b 228 * @param command C-struct to decode the message contents into
shimniok 0:826c6171fc1b 229 */
shimniok 0:826c6171fc1b 230 static inline void mavlink_msg_command_decode(const mavlink_message_t* msg, mavlink_command_t* command)
shimniok 0:826c6171fc1b 231 {
shimniok 0:826c6171fc1b 232 command->target_system = mavlink_msg_command_get_target_system(msg);
shimniok 0:826c6171fc1b 233 command->target_component = mavlink_msg_command_get_target_component(msg);
shimniok 0:826c6171fc1b 234 command->command = mavlink_msg_command_get_command(msg);
shimniok 0:826c6171fc1b 235 command->confirmation = mavlink_msg_command_get_confirmation(msg);
shimniok 0:826c6171fc1b 236 command->param1 = mavlink_msg_command_get_param1(msg);
shimniok 0:826c6171fc1b 237 command->param2 = mavlink_msg_command_get_param2(msg);
shimniok 0:826c6171fc1b 238 command->param3 = mavlink_msg_command_get_param3(msg);
shimniok 0:826c6171fc1b 239 command->param4 = mavlink_msg_command_get_param4(msg);
shimniok 0:826c6171fc1b 240 }