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 HIL_CONTROLS PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_HIL_CONTROLS 68
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_hil_controls_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 uint64_t time_us; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 8 float roll_ailerons; ///< Control output -3 .. 1
shimniok 0:826c6171fc1b 9 float pitch_elevator; ///< Control output -1 .. 1
shimniok 0:826c6171fc1b 10 float yaw_rudder; ///< Control output -1 .. 1
shimniok 0:826c6171fc1b 11 float throttle; ///< Throttle 0 .. 1
shimniok 0:826c6171fc1b 12 uint8_t mode; ///< System mode (MAV_MODE)
shimniok 0:826c6171fc1b 13 uint8_t nav_mode; ///< Navigation mode (MAV_NAV_MODE)
shimniok 0:826c6171fc1b 14
shimniok 0:826c6171fc1b 15 } mavlink_hil_controls_t;
shimniok 0:826c6171fc1b 16
shimniok 0:826c6171fc1b 17
shimniok 0:826c6171fc1b 18
shimniok 0:826c6171fc1b 19 /**
shimniok 0:826c6171fc1b 20 * @brief Pack a hil_controls message
shimniok 0:826c6171fc1b 21 * @param system_id ID of this system
shimniok 0:826c6171fc1b 22 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 23 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 24 *
shimniok 0:826c6171fc1b 25 * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 26 * @param roll_ailerons Control output -3 .. 1
shimniok 0:826c6171fc1b 27 * @param pitch_elevator Control output -1 .. 1
shimniok 0:826c6171fc1b 28 * @param yaw_rudder Control output -1 .. 1
shimniok 0:826c6171fc1b 29 * @param throttle Throttle 0 .. 1
shimniok 0:826c6171fc1b 30 * @param mode System mode (MAV_MODE)
shimniok 0:826c6171fc1b 31 * @param nav_mode Navigation mode (MAV_NAV_MODE)
shimniok 0:826c6171fc1b 32 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 33 */
shimniok 0:826c6171fc1b 34 static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, uint8_t mode, uint8_t nav_mode)
shimniok 0:826c6171fc1b 35 {
shimniok 0:826c6171fc1b 36 uint16_t i = 0;
shimniok 0:826c6171fc1b 37 msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
shimniok 0:826c6171fc1b 38
shimniok 0:826c6171fc1b 39 i += put_uint64_t_by_index(time_us, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 40 i += put_float_by_index(roll_ailerons, i, msg->payload); // Control output -3 .. 1
shimniok 0:826c6171fc1b 41 i += put_float_by_index(pitch_elevator, i, msg->payload); // Control output -1 .. 1
shimniok 0:826c6171fc1b 42 i += put_float_by_index(yaw_rudder, i, msg->payload); // Control output -1 .. 1
shimniok 0:826c6171fc1b 43 i += put_float_by_index(throttle, i, msg->payload); // Throttle 0 .. 1
shimniok 0:826c6171fc1b 44 i += put_uint8_t_by_index(mode, i, msg->payload); // System mode (MAV_MODE)
shimniok 0:826c6171fc1b 45 i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode (MAV_NAV_MODE)
shimniok 0:826c6171fc1b 46
shimniok 0:826c6171fc1b 47 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:826c6171fc1b 48 }
shimniok 0:826c6171fc1b 49
shimniok 0:826c6171fc1b 50 /**
shimniok 0:826c6171fc1b 51 * @brief Pack a hil_controls message
shimniok 0:826c6171fc1b 52 * @param system_id ID of this system
shimniok 0:826c6171fc1b 53 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 54 * @param chan The MAVLink channel this message was sent over
shimniok 0:826c6171fc1b 55 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 56 * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 57 * @param roll_ailerons Control output -3 .. 1
shimniok 0:826c6171fc1b 58 * @param pitch_elevator Control output -1 .. 1
shimniok 0:826c6171fc1b 59 * @param yaw_rudder Control output -1 .. 1
shimniok 0:826c6171fc1b 60 * @param throttle Throttle 0 .. 1
shimniok 0:826c6171fc1b 61 * @param mode System mode (MAV_MODE)
shimniok 0:826c6171fc1b 62 * @param nav_mode Navigation mode (MAV_NAV_MODE)
shimniok 0:826c6171fc1b 63 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 64 */
shimniok 0:826c6171fc1b 65 static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, uint8_t mode, uint8_t nav_mode)
shimniok 0:826c6171fc1b 66 {
shimniok 0:826c6171fc1b 67 uint16_t i = 0;
shimniok 0:826c6171fc1b 68 msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
shimniok 0:826c6171fc1b 69
shimniok 0:826c6171fc1b 70 i += put_uint64_t_by_index(time_us, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 71 i += put_float_by_index(roll_ailerons, i, msg->payload); // Control output -3 .. 1
shimniok 0:826c6171fc1b 72 i += put_float_by_index(pitch_elevator, i, msg->payload); // Control output -1 .. 1
shimniok 0:826c6171fc1b 73 i += put_float_by_index(yaw_rudder, i, msg->payload); // Control output -1 .. 1
shimniok 0:826c6171fc1b 74 i += put_float_by_index(throttle, i, msg->payload); // Throttle 0 .. 1
shimniok 0:826c6171fc1b 75 i += put_uint8_t_by_index(mode, i, msg->payload); // System mode (MAV_MODE)
shimniok 0:826c6171fc1b 76 i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode (MAV_NAV_MODE)
shimniok 0:826c6171fc1b 77
shimniok 0:826c6171fc1b 78 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:826c6171fc1b 79 }
shimniok 0:826c6171fc1b 80
shimniok 0:826c6171fc1b 81 /**
shimniok 0:826c6171fc1b 82 * @brief Encode a hil_controls struct into a message
shimniok 0:826c6171fc1b 83 *
shimniok 0:826c6171fc1b 84 * @param system_id ID of this system
shimniok 0:826c6171fc1b 85 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 86 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 87 * @param hil_controls C-struct to read the message contents from
shimniok 0:826c6171fc1b 88 */
shimniok 0:826c6171fc1b 89 static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls)
shimniok 0:826c6171fc1b 90 {
shimniok 0:826c6171fc1b 91 return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_us, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->mode, hil_controls->nav_mode);
shimniok 0:826c6171fc1b 92 }
shimniok 0:826c6171fc1b 93
shimniok 0:826c6171fc1b 94 /**
shimniok 0:826c6171fc1b 95 * @brief Send a hil_controls message
shimniok 0:826c6171fc1b 96 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 97 *
shimniok 0:826c6171fc1b 98 * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 99 * @param roll_ailerons Control output -3 .. 1
shimniok 0:826c6171fc1b 100 * @param pitch_elevator Control output -1 .. 1
shimniok 0:826c6171fc1b 101 * @param yaw_rudder Control output -1 .. 1
shimniok 0:826c6171fc1b 102 * @param throttle Throttle 0 .. 1
shimniok 0:826c6171fc1b 103 * @param mode System mode (MAV_MODE)
shimniok 0:826c6171fc1b 104 * @param nav_mode Navigation mode (MAV_NAV_MODE)
shimniok 0:826c6171fc1b 105 */
shimniok 0:826c6171fc1b 106 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:826c6171fc1b 107
shimniok 0:826c6171fc1b 108 static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, uint8_t mode, uint8_t nav_mode)
shimniok 0:826c6171fc1b 109 {
shimniok 0:826c6171fc1b 110 mavlink_message_t msg;
shimniok 0:826c6171fc1b 111 mavlink_msg_hil_controls_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode);
shimniok 0:826c6171fc1b 112 mavlink_send_uart(chan, &msg);
shimniok 0:826c6171fc1b 113 }
shimniok 0:826c6171fc1b 114
shimniok 0:826c6171fc1b 115 #endif
shimniok 0:826c6171fc1b 116 // MESSAGE HIL_CONTROLS UNPACKING
shimniok 0:826c6171fc1b 117
shimniok 0:826c6171fc1b 118 /**
shimniok 0:826c6171fc1b 119 * @brief Get field time_us from hil_controls message
shimniok 0:826c6171fc1b 120 *
shimniok 0:826c6171fc1b 121 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
shimniok 0:826c6171fc1b 122 */
shimniok 0:826c6171fc1b 123 static inline uint64_t mavlink_msg_hil_controls_get_time_us(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 124 {
shimniok 0:826c6171fc1b 125 generic_64bit r;
shimniok 0:826c6171fc1b 126 r.b[7] = (msg->payload)[0];
shimniok 0:826c6171fc1b 127 r.b[6] = (msg->payload)[1];
shimniok 0:826c6171fc1b 128 r.b[5] = (msg->payload)[2];
shimniok 0:826c6171fc1b 129 r.b[4] = (msg->payload)[3];
shimniok 0:826c6171fc1b 130 r.b[3] = (msg->payload)[4];
shimniok 0:826c6171fc1b 131 r.b[2] = (msg->payload)[5];
shimniok 0:826c6171fc1b 132 r.b[1] = (msg->payload)[6];
shimniok 0:826c6171fc1b 133 r.b[0] = (msg->payload)[7];
shimniok 0:826c6171fc1b 134 return (uint64_t)r.ll;
shimniok 0:826c6171fc1b 135 }
shimniok 0:826c6171fc1b 136
shimniok 0:826c6171fc1b 137 /**
shimniok 0:826c6171fc1b 138 * @brief Get field roll_ailerons from hil_controls message
shimniok 0:826c6171fc1b 139 *
shimniok 0:826c6171fc1b 140 * @return Control output -3 .. 1
shimniok 0:826c6171fc1b 141 */
shimniok 0:826c6171fc1b 142 static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 143 {
shimniok 0:826c6171fc1b 144 generic_32bit r;
shimniok 0:826c6171fc1b 145 r.b[3] = (msg->payload+sizeof(uint64_t))[0];
shimniok 0:826c6171fc1b 146 r.b[2] = (msg->payload+sizeof(uint64_t))[1];
shimniok 0:826c6171fc1b 147 r.b[1] = (msg->payload+sizeof(uint64_t))[2];
shimniok 0:826c6171fc1b 148 r.b[0] = (msg->payload+sizeof(uint64_t))[3];
shimniok 0:826c6171fc1b 149 return (float)r.f;
shimniok 0:826c6171fc1b 150 }
shimniok 0:826c6171fc1b 151
shimniok 0:826c6171fc1b 152 /**
shimniok 0:826c6171fc1b 153 * @brief Get field pitch_elevator from hil_controls message
shimniok 0:826c6171fc1b 154 *
shimniok 0:826c6171fc1b 155 * @return Control output -1 .. 1
shimniok 0:826c6171fc1b 156 */
shimniok 0:826c6171fc1b 157 static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 158 {
shimniok 0:826c6171fc1b 159 generic_32bit r;
shimniok 0:826c6171fc1b 160 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
shimniok 0:826c6171fc1b 161 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
shimniok 0:826c6171fc1b 162 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
shimniok 0:826c6171fc1b 163 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
shimniok 0:826c6171fc1b 164 return (float)r.f;
shimniok 0:826c6171fc1b 165 }
shimniok 0:826c6171fc1b 166
shimniok 0:826c6171fc1b 167 /**
shimniok 0:826c6171fc1b 168 * @brief Get field yaw_rudder from hil_controls message
shimniok 0:826c6171fc1b 169 *
shimniok 0:826c6171fc1b 170 * @return Control output -1 .. 1
shimniok 0:826c6171fc1b 171 */
shimniok 0:826c6171fc1b 172 static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 173 {
shimniok 0:826c6171fc1b 174 generic_32bit r;
shimniok 0:826c6171fc1b 175 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 176 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 177 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 178 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 179 return (float)r.f;
shimniok 0:826c6171fc1b 180 }
shimniok 0:826c6171fc1b 181
shimniok 0:826c6171fc1b 182 /**
shimniok 0:826c6171fc1b 183 * @brief Get field throttle from hil_controls message
shimniok 0:826c6171fc1b 184 *
shimniok 0:826c6171fc1b 185 * @return Throttle 0 .. 1
shimniok 0:826c6171fc1b 186 */
shimniok 0:826c6171fc1b 187 static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 188 {
shimniok 0:826c6171fc1b 189 generic_32bit r;
shimniok 0:826c6171fc1b 190 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 191 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 192 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 193 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 194 return (float)r.f;
shimniok 0:826c6171fc1b 195 }
shimniok 0:826c6171fc1b 196
shimniok 0:826c6171fc1b 197 /**
shimniok 0:826c6171fc1b 198 * @brief Get field mode from hil_controls message
shimniok 0:826c6171fc1b 199 *
shimniok 0:826c6171fc1b 200 * @return System mode (MAV_MODE)
shimniok 0:826c6171fc1b 201 */
shimniok 0:826c6171fc1b 202 static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 203 {
shimniok 0:826c6171fc1b 204 return (uint8_t)(msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 205 }
shimniok 0:826c6171fc1b 206
shimniok 0:826c6171fc1b 207 /**
shimniok 0:826c6171fc1b 208 * @brief Get field nav_mode from hil_controls message
shimniok 0:826c6171fc1b 209 *
shimniok 0:826c6171fc1b 210 * @return Navigation mode (MAV_NAV_MODE)
shimniok 0:826c6171fc1b 211 */
shimniok 0:826c6171fc1b 212 static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 213 {
shimniok 0:826c6171fc1b 214 return (uint8_t)(msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0];
shimniok 0:826c6171fc1b 215 }
shimniok 0:826c6171fc1b 216
shimniok 0:826c6171fc1b 217 /**
shimniok 0:826c6171fc1b 218 * @brief Decode a hil_controls message into a struct
shimniok 0:826c6171fc1b 219 *
shimniok 0:826c6171fc1b 220 * @param msg The message to decode
shimniok 0:826c6171fc1b 221 * @param hil_controls C-struct to decode the message contents into
shimniok 0:826c6171fc1b 222 */
shimniok 0:826c6171fc1b 223 static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls)
shimniok 0:826c6171fc1b 224 {
shimniok 0:826c6171fc1b 225 hil_controls->time_us = mavlink_msg_hil_controls_get_time_us(msg);
shimniok 0:826c6171fc1b 226 hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg);
shimniok 0:826c6171fc1b 227 hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg);
shimniok 0:826c6171fc1b 228 hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg);
shimniok 0:826c6171fc1b 229 hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg);
shimniok 0:826c6171fc1b 230 hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg);
shimniok 0:826c6171fc1b 231 hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg);
shimniok 0:826c6171fc1b 232 }