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 AIR_DATA PACKING
shimniok 0:a6a169de725f 2
shimniok 0:a6a169de725f 3 #define MAVLINK_MSG_ID_AIR_DATA 171
shimniok 0:a6a169de725f 4
shimniok 0:a6a169de725f 5 typedef struct __mavlink_air_data_t
shimniok 0:a6a169de725f 6 {
shimniok 0:a6a169de725f 7 float dynamicPressure; ///< Dynamic pressure (Pa)
shimniok 0:a6a169de725f 8 float staticPressure; ///< Static pressure (Pa)
shimniok 0:a6a169de725f 9 uint16_t temperature; ///< Board temperature
shimniok 0:a6a169de725f 10
shimniok 0:a6a169de725f 11 } mavlink_air_data_t;
shimniok 0:a6a169de725f 12
shimniok 0:a6a169de725f 13
shimniok 0:a6a169de725f 14
shimniok 0:a6a169de725f 15 /**
shimniok 0:a6a169de725f 16 * @brief Pack a air_data message
shimniok 0:a6a169de725f 17 * @param system_id ID of this system
shimniok 0:a6a169de725f 18 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:a6a169de725f 19 * @param msg The MAVLink message to compress the data into
shimniok 0:a6a169de725f 20 *
shimniok 0:a6a169de725f 21 * @param dynamicPressure Dynamic pressure (Pa)
shimniok 0:a6a169de725f 22 * @param staticPressure Static pressure (Pa)
shimniok 0:a6a169de725f 23 * @param temperature Board temperature
shimniok 0:a6a169de725f 24 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:a6a169de725f 25 */
shimniok 0:a6a169de725f 26 static inline uint16_t mavlink_msg_air_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float dynamicPressure, float staticPressure, uint16_t temperature)
shimniok 0:a6a169de725f 27 {
shimniok 0:a6a169de725f 28 uint16_t i = 0;
shimniok 0:a6a169de725f 29 msg->msgid = MAVLINK_MSG_ID_AIR_DATA;
shimniok 0:a6a169de725f 30
shimniok 0:a6a169de725f 31 i += put_float_by_index(dynamicPressure, i, msg->payload); // Dynamic pressure (Pa)
shimniok 0:a6a169de725f 32 i += put_float_by_index(staticPressure, i, msg->payload); // Static pressure (Pa)
shimniok 0:a6a169de725f 33 i += put_uint16_t_by_index(temperature, i, msg->payload); // Board temperature
shimniok 0:a6a169de725f 34
shimniok 0:a6a169de725f 35 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:a6a169de725f 36 }
shimniok 0:a6a169de725f 37
shimniok 0:a6a169de725f 38 /**
shimniok 0:a6a169de725f 39 * @brief Pack a air_data message
shimniok 0:a6a169de725f 40 * @param system_id ID of this system
shimniok 0:a6a169de725f 41 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:a6a169de725f 42 * @param chan The MAVLink channel this message was sent over
shimniok 0:a6a169de725f 43 * @param msg The MAVLink message to compress the data into
shimniok 0:a6a169de725f 44 * @param dynamicPressure Dynamic pressure (Pa)
shimniok 0:a6a169de725f 45 * @param staticPressure Static pressure (Pa)
shimniok 0:a6a169de725f 46 * @param temperature Board temperature
shimniok 0:a6a169de725f 47 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:a6a169de725f 48 */
shimniok 0:a6a169de725f 49 static inline uint16_t mavlink_msg_air_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float dynamicPressure, float staticPressure, uint16_t temperature)
shimniok 0:a6a169de725f 50 {
shimniok 0:a6a169de725f 51 uint16_t i = 0;
shimniok 0:a6a169de725f 52 msg->msgid = MAVLINK_MSG_ID_AIR_DATA;
shimniok 0:a6a169de725f 53
shimniok 0:a6a169de725f 54 i += put_float_by_index(dynamicPressure, i, msg->payload); // Dynamic pressure (Pa)
shimniok 0:a6a169de725f 55 i += put_float_by_index(staticPressure, i, msg->payload); // Static pressure (Pa)
shimniok 0:a6a169de725f 56 i += put_uint16_t_by_index(temperature, i, msg->payload); // Board temperature
shimniok 0:a6a169de725f 57
shimniok 0:a6a169de725f 58 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:a6a169de725f 59 }
shimniok 0:a6a169de725f 60
shimniok 0:a6a169de725f 61 /**
shimniok 0:a6a169de725f 62 * @brief Encode a air_data struct into a message
shimniok 0:a6a169de725f 63 *
shimniok 0:a6a169de725f 64 * @param system_id ID of this system
shimniok 0:a6a169de725f 65 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:a6a169de725f 66 * @param msg The MAVLink message to compress the data into
shimniok 0:a6a169de725f 67 * @param air_data C-struct to read the message contents from
shimniok 0:a6a169de725f 68 */
shimniok 0:a6a169de725f 69 static inline uint16_t mavlink_msg_air_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_air_data_t* air_data)
shimniok 0:a6a169de725f 70 {
shimniok 0:a6a169de725f 71 return mavlink_msg_air_data_pack(system_id, component_id, msg, air_data->dynamicPressure, air_data->staticPressure, air_data->temperature);
shimniok 0:a6a169de725f 72 }
shimniok 0:a6a169de725f 73
shimniok 0:a6a169de725f 74 /**
shimniok 0:a6a169de725f 75 * @brief Send a air_data message
shimniok 0:a6a169de725f 76 * @param chan MAVLink channel to send the message
shimniok 0:a6a169de725f 77 *
shimniok 0:a6a169de725f 78 * @param dynamicPressure Dynamic pressure (Pa)
shimniok 0:a6a169de725f 79 * @param staticPressure Static pressure (Pa)
shimniok 0:a6a169de725f 80 * @param temperature Board temperature
shimniok 0:a6a169de725f 81 */
shimniok 0:a6a169de725f 82 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:a6a169de725f 83
shimniok 0:a6a169de725f 84 static inline void mavlink_msg_air_data_send(mavlink_channel_t chan, float dynamicPressure, float staticPressure, uint16_t temperature)
shimniok 0:a6a169de725f 85 {
shimniok 0:a6a169de725f 86 mavlink_message_t msg;
shimniok 0:a6a169de725f 87 mavlink_msg_air_data_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, dynamicPressure, staticPressure, temperature);
shimniok 0:a6a169de725f 88 mavlink_send_uart(chan, &msg);
shimniok 0:a6a169de725f 89 }
shimniok 0:a6a169de725f 90
shimniok 0:a6a169de725f 91 #endif
shimniok 0:a6a169de725f 92 // MESSAGE AIR_DATA UNPACKING
shimniok 0:a6a169de725f 93
shimniok 0:a6a169de725f 94 /**
shimniok 0:a6a169de725f 95 * @brief Get field dynamicPressure from air_data message
shimniok 0:a6a169de725f 96 *
shimniok 0:a6a169de725f 97 * @return Dynamic pressure (Pa)
shimniok 0:a6a169de725f 98 */
shimniok 0:a6a169de725f 99 static inline float mavlink_msg_air_data_get_dynamicPressure(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 100 {
shimniok 0:a6a169de725f 101 generic_32bit r;
shimniok 0:a6a169de725f 102 r.b[3] = (msg->payload)[0];
shimniok 0:a6a169de725f 103 r.b[2] = (msg->payload)[1];
shimniok 0:a6a169de725f 104 r.b[1] = (msg->payload)[2];
shimniok 0:a6a169de725f 105 r.b[0] = (msg->payload)[3];
shimniok 0:a6a169de725f 106 return (float)r.f;
shimniok 0:a6a169de725f 107 }
shimniok 0:a6a169de725f 108
shimniok 0:a6a169de725f 109 /**
shimniok 0:a6a169de725f 110 * @brief Get field staticPressure from air_data message
shimniok 0:a6a169de725f 111 *
shimniok 0:a6a169de725f 112 * @return Static pressure (Pa)
shimniok 0:a6a169de725f 113 */
shimniok 0:a6a169de725f 114 static inline float mavlink_msg_air_data_get_staticPressure(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 115 {
shimniok 0:a6a169de725f 116 generic_32bit r;
shimniok 0:a6a169de725f 117 r.b[3] = (msg->payload+sizeof(float))[0];
shimniok 0:a6a169de725f 118 r.b[2] = (msg->payload+sizeof(float))[1];
shimniok 0:a6a169de725f 119 r.b[1] = (msg->payload+sizeof(float))[2];
shimniok 0:a6a169de725f 120 r.b[0] = (msg->payload+sizeof(float))[3];
shimniok 0:a6a169de725f 121 return (float)r.f;
shimniok 0:a6a169de725f 122 }
shimniok 0:a6a169de725f 123
shimniok 0:a6a169de725f 124 /**
shimniok 0:a6a169de725f 125 * @brief Get field temperature from air_data message
shimniok 0:a6a169de725f 126 *
shimniok 0:a6a169de725f 127 * @return Board temperature
shimniok 0:a6a169de725f 128 */
shimniok 0:a6a169de725f 129 static inline uint16_t mavlink_msg_air_data_get_temperature(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 130 {
shimniok 0:a6a169de725f 131 generic_16bit r;
shimniok 0:a6a169de725f 132 r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[0];
shimniok 0:a6a169de725f 133 r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[1];
shimniok 0:a6a169de725f 134 return (uint16_t)r.s;
shimniok 0:a6a169de725f 135 }
shimniok 0:a6a169de725f 136
shimniok 0:a6a169de725f 137 /**
shimniok 0:a6a169de725f 138 * @brief Decode a air_data message into a struct
shimniok 0:a6a169de725f 139 *
shimniok 0:a6a169de725f 140 * @param msg The message to decode
shimniok 0:a6a169de725f 141 * @param air_data C-struct to decode the message contents into
shimniok 0:a6a169de725f 142 */
shimniok 0:a6a169de725f 143 static inline void mavlink_msg_air_data_decode(const mavlink_message_t* msg, mavlink_air_data_t* air_data)
shimniok 0:a6a169de725f 144 {
shimniok 0:a6a169de725f 145 air_data->dynamicPressure = mavlink_msg_air_data_get_dynamicPressure(msg);
shimniok 0:a6a169de725f 146 air_data->staticPressure = mavlink_msg_air_data_get_staticPressure(msg);
shimniok 0:a6a169de725f 147 air_data->temperature = mavlink_msg_air_data_get_temperature(msg);
shimniok 0:a6a169de725f 148 }