Code for autonomous rover for Sparkfun AVC. DataBus won 3rd in 2012 and the same code was used on Troubled Child, a 1986 Jeep Grand Wagoneer to win 1st in 2014.

Dependencies:   mbed Watchdog SDFileSystem DigoleSerialDisp

Committer:
shimniok
Date:
Fri Nov 30 16:11:53 2018 +0000
Revision:
25:bb5356402687
Parent:
0:a6a169de725f
Initial publish of revised version.

Who changed what in which revision?

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