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 MID_LVL_CMDS PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_MID_LVL_CMDS 180
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_mid_lvl_cmds_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 uint8_t target; ///< The system setting the commands
shimniok 0:826c6171fc1b 8 float hCommand; ///< Commanded Airspeed
shimniok 0:826c6171fc1b 9 float uCommand; ///< Log value 2
shimniok 0:826c6171fc1b 10 float rCommand; ///< Log value 3
shimniok 0:826c6171fc1b 11
shimniok 0:826c6171fc1b 12 } mavlink_mid_lvl_cmds_t;
shimniok 0:826c6171fc1b 13
shimniok 0:826c6171fc1b 14
shimniok 0:826c6171fc1b 15
shimniok 0:826c6171fc1b 16 /**
shimniok 0:826c6171fc1b 17 * @brief Pack a mid_lvl_cmds 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 The system setting the commands
shimniok 0:826c6171fc1b 23 * @param hCommand Commanded Airspeed
shimniok 0:826c6171fc1b 24 * @param uCommand Log value 2
shimniok 0:826c6171fc1b 25 * @param rCommand Log value 3
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_mid_lvl_cmds_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float hCommand, float uCommand, float rCommand)
shimniok 0:826c6171fc1b 29 {
shimniok 0:826c6171fc1b 30 uint16_t i = 0;
shimniok 0:826c6171fc1b 31 msg->msgid = MAVLINK_MSG_ID_MID_LVL_CMDS;
shimniok 0:826c6171fc1b 32
shimniok 0:826c6171fc1b 33 i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands
shimniok 0:826c6171fc1b 34 i += put_float_by_index(hCommand, i, msg->payload); // Commanded Airspeed
shimniok 0:826c6171fc1b 35 i += put_float_by_index(uCommand, i, msg->payload); // Log value 2
shimniok 0:826c6171fc1b 36 i += put_float_by_index(rCommand, i, msg->payload); // Log value 3
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 mid_lvl_cmds 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 The system setting the commands
shimniok 0:826c6171fc1b 48 * @param hCommand Commanded Airspeed
shimniok 0:826c6171fc1b 49 * @param uCommand Log value 2
shimniok 0:826c6171fc1b 50 * @param rCommand Log value 3
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_mid_lvl_cmds_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float hCommand, float uCommand, float rCommand)
shimniok 0:826c6171fc1b 54 {
shimniok 0:826c6171fc1b 55 uint16_t i = 0;
shimniok 0:826c6171fc1b 56 msg->msgid = MAVLINK_MSG_ID_MID_LVL_CMDS;
shimniok 0:826c6171fc1b 57
shimniok 0:826c6171fc1b 58 i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands
shimniok 0:826c6171fc1b 59 i += put_float_by_index(hCommand, i, msg->payload); // Commanded Airspeed
shimniok 0:826c6171fc1b 60 i += put_float_by_index(uCommand, i, msg->payload); // Log value 2
shimniok 0:826c6171fc1b 61 i += put_float_by_index(rCommand, i, msg->payload); // Log value 3
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 mid_lvl_cmds 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 mid_lvl_cmds C-struct to read the message contents from
shimniok 0:826c6171fc1b 73 */
shimniok 0:826c6171fc1b 74 static inline uint16_t mavlink_msg_mid_lvl_cmds_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mid_lvl_cmds_t* mid_lvl_cmds)
shimniok 0:826c6171fc1b 75 {
shimniok 0:826c6171fc1b 76 return mavlink_msg_mid_lvl_cmds_pack(system_id, component_id, msg, mid_lvl_cmds->target, mid_lvl_cmds->hCommand, mid_lvl_cmds->uCommand, mid_lvl_cmds->rCommand);
shimniok 0:826c6171fc1b 77 }
shimniok 0:826c6171fc1b 78
shimniok 0:826c6171fc1b 79 /**
shimniok 0:826c6171fc1b 80 * @brief Send a mid_lvl_cmds message
shimniok 0:826c6171fc1b 81 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 82 *
shimniok 0:826c6171fc1b 83 * @param target The system setting the commands
shimniok 0:826c6171fc1b 84 * @param hCommand Commanded Airspeed
shimniok 0:826c6171fc1b 85 * @param uCommand Log value 2
shimniok 0:826c6171fc1b 86 * @param rCommand Log value 3
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_mid_lvl_cmds_send(mavlink_channel_t chan, uint8_t target, float hCommand, float uCommand, float rCommand)
shimniok 0:826c6171fc1b 91 {
shimniok 0:826c6171fc1b 92 mavlink_message_t msg;
shimniok 0:826c6171fc1b 93 mavlink_msg_mid_lvl_cmds_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, hCommand, uCommand, rCommand);
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 MID_LVL_CMDS UNPACKING
shimniok 0:826c6171fc1b 99
shimniok 0:826c6171fc1b 100 /**
shimniok 0:826c6171fc1b 101 * @brief Get field target from mid_lvl_cmds message
shimniok 0:826c6171fc1b 102 *
shimniok 0:826c6171fc1b 103 * @return The system setting the commands
shimniok 0:826c6171fc1b 104 */
shimniok 0:826c6171fc1b 105 static inline uint8_t mavlink_msg_mid_lvl_cmds_get_target(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 hCommand from mid_lvl_cmds message
shimniok 0:826c6171fc1b 112 *
shimniok 0:826c6171fc1b 113 * @return Commanded Airspeed
shimniok 0:826c6171fc1b 114 */
shimniok 0:826c6171fc1b 115 static inline float mavlink_msg_mid_lvl_cmds_get_hCommand(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 116 {
shimniok 0:826c6171fc1b 117 generic_32bit r;
shimniok 0:826c6171fc1b 118 r.b[3] = (msg->payload+sizeof(uint8_t))[0];
shimniok 0:826c6171fc1b 119 r.b[2] = (msg->payload+sizeof(uint8_t))[1];
shimniok 0:826c6171fc1b 120 r.b[1] = (msg->payload+sizeof(uint8_t))[2];
shimniok 0:826c6171fc1b 121 r.b[0] = (msg->payload+sizeof(uint8_t))[3];
shimniok 0:826c6171fc1b 122 return (float)r.f;
shimniok 0:826c6171fc1b 123 }
shimniok 0:826c6171fc1b 124
shimniok 0:826c6171fc1b 125 /**
shimniok 0:826c6171fc1b 126 * @brief Get field uCommand from mid_lvl_cmds message
shimniok 0:826c6171fc1b 127 *
shimniok 0:826c6171fc1b 128 * @return Log value 2
shimniok 0:826c6171fc1b 129 */
shimniok 0:826c6171fc1b 130 static inline float mavlink_msg_mid_lvl_cmds_get_uCommand(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 131 {
shimniok 0:826c6171fc1b 132 generic_32bit r;
shimniok 0:826c6171fc1b 133 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0];
shimniok 0:826c6171fc1b 134 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1];
shimniok 0:826c6171fc1b 135 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2];
shimniok 0:826c6171fc1b 136 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3];
shimniok 0:826c6171fc1b 137 return (float)r.f;
shimniok 0:826c6171fc1b 138 }
shimniok 0:826c6171fc1b 139
shimniok 0:826c6171fc1b 140 /**
shimniok 0:826c6171fc1b 141 * @brief Get field rCommand from mid_lvl_cmds message
shimniok 0:826c6171fc1b 142 *
shimniok 0:826c6171fc1b 143 * @return Log value 3
shimniok 0:826c6171fc1b 144 */
shimniok 0:826c6171fc1b 145 static inline float mavlink_msg_mid_lvl_cmds_get_rCommand(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 146 {
shimniok 0:826c6171fc1b 147 generic_32bit r;
shimniok 0:826c6171fc1b 148 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 149 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 150 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 151 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 152 return (float)r.f;
shimniok 0:826c6171fc1b 153 }
shimniok 0:826c6171fc1b 154
shimniok 0:826c6171fc1b 155 /**
shimniok 0:826c6171fc1b 156 * @brief Decode a mid_lvl_cmds message into a struct
shimniok 0:826c6171fc1b 157 *
shimniok 0:826c6171fc1b 158 * @param msg The message to decode
shimniok 0:826c6171fc1b 159 * @param mid_lvl_cmds C-struct to decode the message contents into
shimniok 0:826c6171fc1b 160 */
shimniok 0:826c6171fc1b 161 static inline void mavlink_msg_mid_lvl_cmds_decode(const mavlink_message_t* msg, mavlink_mid_lvl_cmds_t* mid_lvl_cmds)
shimniok 0:826c6171fc1b 162 {
shimniok 0:826c6171fc1b 163 mid_lvl_cmds->target = mavlink_msg_mid_lvl_cmds_get_target(msg);
shimniok 0:826c6171fc1b 164 mid_lvl_cmds->hCommand = mavlink_msg_mid_lvl_cmds_get_hCommand(msg);
shimniok 0:826c6171fc1b 165 mid_lvl_cmds->uCommand = mavlink_msg_mid_lvl_cmds_get_uCommand(msg);
shimniok 0:826c6171fc1b 166 mid_lvl_cmds->rCommand = mavlink_msg_mid_lvl_cmds_get_rCommand(msg);
shimniok 0:826c6171fc1b 167 }