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 NAMED_VALUE_FLOAT PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 252
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_named_value_float_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 char name[10]; ///< Name of the debug variable
shimniok 0:826c6171fc1b 8 float value; ///< Floating point value
shimniok 0:826c6171fc1b 9
shimniok 0:826c6171fc1b 10 } mavlink_named_value_float_t;
shimniok 0:826c6171fc1b 11
shimniok 0:826c6171fc1b 12 #define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10
shimniok 0:826c6171fc1b 13
shimniok 0:826c6171fc1b 14
shimniok 0:826c6171fc1b 15 /**
shimniok 0:826c6171fc1b 16 * @brief Pack a named_value_float 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 name Name of the debug variable
shimniok 0:826c6171fc1b 22 * @param value Floating point value
shimniok 0:826c6171fc1b 23 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 24 */
shimniok 0:826c6171fc1b 25 static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* name, float value)
shimniok 0:826c6171fc1b 26 {
shimniok 0:826c6171fc1b 27 uint16_t i = 0;
shimniok 0:826c6171fc1b 28 msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
shimniok 0:826c6171fc1b 29
shimniok 0:826c6171fc1b 30 i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable
shimniok 0:826c6171fc1b 31 i += put_float_by_index(value, i, msg->payload); // Floating point value
shimniok 0:826c6171fc1b 32
shimniok 0:826c6171fc1b 33 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:826c6171fc1b 34 }
shimniok 0:826c6171fc1b 35
shimniok 0:826c6171fc1b 36 /**
shimniok 0:826c6171fc1b 37 * @brief Pack a named_value_float message
shimniok 0:826c6171fc1b 38 * @param system_id ID of this system
shimniok 0:826c6171fc1b 39 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 40 * @param chan The MAVLink channel this message was sent over
shimniok 0:826c6171fc1b 41 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 42 * @param name Name of the debug variable
shimniok 0:826c6171fc1b 43 * @param value Floating point value
shimniok 0:826c6171fc1b 44 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 45 */
shimniok 0:826c6171fc1b 46 static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* name, float value)
shimniok 0:826c6171fc1b 47 {
shimniok 0:826c6171fc1b 48 uint16_t i = 0;
shimniok 0:826c6171fc1b 49 msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
shimniok 0:826c6171fc1b 50
shimniok 0:826c6171fc1b 51 i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable
shimniok 0:826c6171fc1b 52 i += put_float_by_index(value, i, msg->payload); // Floating point value
shimniok 0:826c6171fc1b 53
shimniok 0:826c6171fc1b 54 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:826c6171fc1b 55 }
shimniok 0:826c6171fc1b 56
shimniok 0:826c6171fc1b 57 /**
shimniok 0:826c6171fc1b 58 * @brief Encode a named_value_float struct into a message
shimniok 0:826c6171fc1b 59 *
shimniok 0:826c6171fc1b 60 * @param system_id ID of this system
shimniok 0:826c6171fc1b 61 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 62 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 63 * @param named_value_float C-struct to read the message contents from
shimniok 0:826c6171fc1b 64 */
shimniok 0:826c6171fc1b 65 static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float)
shimniok 0:826c6171fc1b 66 {
shimniok 0:826c6171fc1b 67 return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->name, named_value_float->value);
shimniok 0:826c6171fc1b 68 }
shimniok 0:826c6171fc1b 69
shimniok 0:826c6171fc1b 70 /**
shimniok 0:826c6171fc1b 71 * @brief Send a named_value_float message
shimniok 0:826c6171fc1b 72 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 73 *
shimniok 0:826c6171fc1b 74 * @param name Name of the debug variable
shimniok 0:826c6171fc1b 75 * @param value Floating point value
shimniok 0:826c6171fc1b 76 */
shimniok 0:826c6171fc1b 77 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:826c6171fc1b 78
shimniok 0:826c6171fc1b 79 static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, const char* name, float value)
shimniok 0:826c6171fc1b 80 {
shimniok 0:826c6171fc1b 81 mavlink_message_t msg;
shimniok 0:826c6171fc1b 82 mavlink_msg_named_value_float_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, name, value);
shimniok 0:826c6171fc1b 83 mavlink_send_uart(chan, &msg);
shimniok 0:826c6171fc1b 84 }
shimniok 0:826c6171fc1b 85
shimniok 0:826c6171fc1b 86 #endif
shimniok 0:826c6171fc1b 87 // MESSAGE NAMED_VALUE_FLOAT UNPACKING
shimniok 0:826c6171fc1b 88
shimniok 0:826c6171fc1b 89 /**
shimniok 0:826c6171fc1b 90 * @brief Get field name from named_value_float message
shimniok 0:826c6171fc1b 91 *
shimniok 0:826c6171fc1b 92 * @return Name of the debug variable
shimniok 0:826c6171fc1b 93 */
shimniok 0:826c6171fc1b 94 static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char* r_data)
shimniok 0:826c6171fc1b 95 {
shimniok 0:826c6171fc1b 96
shimniok 0:826c6171fc1b 97 memcpy(r_data, msg->payload, sizeof(char)*10);
shimniok 0:826c6171fc1b 98 return sizeof(char)*10;
shimniok 0:826c6171fc1b 99 }
shimniok 0:826c6171fc1b 100
shimniok 0:826c6171fc1b 101 /**
shimniok 0:826c6171fc1b 102 * @brief Get field value from named_value_float message
shimniok 0:826c6171fc1b 103 *
shimniok 0:826c6171fc1b 104 * @return Floating point value
shimniok 0:826c6171fc1b 105 */
shimniok 0:826c6171fc1b 106 static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 107 {
shimniok 0:826c6171fc1b 108 generic_32bit r;
shimniok 0:826c6171fc1b 109 r.b[3] = (msg->payload+sizeof(char)*10)[0];
shimniok 0:826c6171fc1b 110 r.b[2] = (msg->payload+sizeof(char)*10)[1];
shimniok 0:826c6171fc1b 111 r.b[1] = (msg->payload+sizeof(char)*10)[2];
shimniok 0:826c6171fc1b 112 r.b[0] = (msg->payload+sizeof(char)*10)[3];
shimniok 0:826c6171fc1b 113 return (float)r.f;
shimniok 0:826c6171fc1b 114 }
shimniok 0:826c6171fc1b 115
shimniok 0:826c6171fc1b 116 /**
shimniok 0:826c6171fc1b 117 * @brief Decode a named_value_float message into a struct
shimniok 0:826c6171fc1b 118 *
shimniok 0:826c6171fc1b 119 * @param msg The message to decode
shimniok 0:826c6171fc1b 120 * @param named_value_float C-struct to decode the message contents into
shimniok 0:826c6171fc1b 121 */
shimniok 0:826c6171fc1b 122 static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float)
shimniok 0:826c6171fc1b 123 {
shimniok 0:826c6171fc1b 124 mavlink_msg_named_value_float_get_name(msg, named_value_float->name);
shimniok 0:826c6171fc1b 125 named_value_float->value = mavlink_msg_named_value_float_get_value(msg);
shimniok 0:826c6171fc1b 126 }