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