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 PARAM_VALUE PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_PARAM_VALUE 22
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_param_value_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 int8_t param_id[15]; ///< Onboard parameter id
shimniok 0:826c6171fc1b 8 float param_value; ///< Onboard parameter value
shimniok 0:826c6171fc1b 9 uint16_t param_count; ///< Total number of onboard parameters
shimniok 0:826c6171fc1b 10 uint16_t param_index; ///< Index of this onboard parameter
shimniok 0:826c6171fc1b 11
shimniok 0:826c6171fc1b 12 } mavlink_param_value_t;
shimniok 0:826c6171fc1b 13
shimniok 0:826c6171fc1b 14 #define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 15
shimniok 0:826c6171fc1b 15
shimniok 0:826c6171fc1b 16
shimniok 0:826c6171fc1b 17 /**
shimniok 0:826c6171fc1b 18 * @brief Pack a param_value message
shimniok 0:826c6171fc1b 19 * @param system_id ID of this system
shimniok 0:826c6171fc1b 20 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 21 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 22 *
shimniok 0:826c6171fc1b 23 * @param param_id Onboard parameter id
shimniok 0:826c6171fc1b 24 * @param param_value Onboard parameter value
shimniok 0:826c6171fc1b 25 * @param param_count Total number of onboard parameters
shimniok 0:826c6171fc1b 26 * @param param_index Index of this onboard parameter
shimniok 0:826c6171fc1b 27 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 28 */
shimniok 0:826c6171fc1b 29 static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index)
shimniok 0:826c6171fc1b 30 {
shimniok 0:826c6171fc1b 31 uint16_t i = 0;
shimniok 0:826c6171fc1b 32 msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
shimniok 0:826c6171fc1b 33
shimniok 0:826c6171fc1b 34 i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
shimniok 0:826c6171fc1b 35 i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
shimniok 0:826c6171fc1b 36 i += put_uint16_t_by_index(param_count, i, msg->payload); // Total number of onboard parameters
shimniok 0:826c6171fc1b 37 i += put_uint16_t_by_index(param_index, i, msg->payload); // Index of this onboard parameter
shimniok 0:826c6171fc1b 38
shimniok 0:826c6171fc1b 39 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:826c6171fc1b 40 }
shimniok 0:826c6171fc1b 41
shimniok 0:826c6171fc1b 42 /**
shimniok 0:826c6171fc1b 43 * @brief Pack a param_value message
shimniok 0:826c6171fc1b 44 * @param system_id ID of this system
shimniok 0:826c6171fc1b 45 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 46 * @param chan The MAVLink channel this message was sent over
shimniok 0:826c6171fc1b 47 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 48 * @param param_id Onboard parameter id
shimniok 0:826c6171fc1b 49 * @param param_value Onboard parameter value
shimniok 0:826c6171fc1b 50 * @param param_count Total number of onboard parameters
shimniok 0:826c6171fc1b 51 * @param param_index Index of this onboard parameter
shimniok 0:826c6171fc1b 52 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 53 */
shimniok 0:826c6171fc1b 54 static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index)
shimniok 0:826c6171fc1b 55 {
shimniok 0:826c6171fc1b 56 uint16_t i = 0;
shimniok 0:826c6171fc1b 57 msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
shimniok 0:826c6171fc1b 58
shimniok 0:826c6171fc1b 59 i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
shimniok 0:826c6171fc1b 60 i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
shimniok 0:826c6171fc1b 61 i += put_uint16_t_by_index(param_count, i, msg->payload); // Total number of onboard parameters
shimniok 0:826c6171fc1b 62 i += put_uint16_t_by_index(param_index, i, msg->payload); // Index of this onboard parameter
shimniok 0:826c6171fc1b 63
shimniok 0:826c6171fc1b 64 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:826c6171fc1b 65 }
shimniok 0:826c6171fc1b 66
shimniok 0:826c6171fc1b 67 /**
shimniok 0:826c6171fc1b 68 * @brief Encode a param_value struct into a message
shimniok 0:826c6171fc1b 69 *
shimniok 0:826c6171fc1b 70 * @param system_id ID of this system
shimniok 0:826c6171fc1b 71 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 72 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 73 * @param param_value C-struct to read the message contents from
shimniok 0:826c6171fc1b 74 */
shimniok 0:826c6171fc1b 75 static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value)
shimniok 0:826c6171fc1b 76 {
shimniok 0:826c6171fc1b 77 return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_count, param_value->param_index);
shimniok 0:826c6171fc1b 78 }
shimniok 0:826c6171fc1b 79
shimniok 0:826c6171fc1b 80 /**
shimniok 0:826c6171fc1b 81 * @brief Send a param_value message
shimniok 0:826c6171fc1b 82 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 83 *
shimniok 0:826c6171fc1b 84 * @param param_id Onboard parameter id
shimniok 0:826c6171fc1b 85 * @param param_value Onboard parameter value
shimniok 0:826c6171fc1b 86 * @param param_count Total number of onboard parameters
shimniok 0:826c6171fc1b 87 * @param param_index Index of this onboard parameter
shimniok 0:826c6171fc1b 88 */
shimniok 0:826c6171fc1b 89 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:826c6171fc1b 90
shimniok 0:826c6171fc1b 91 static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index)
shimniok 0:826c6171fc1b 92 {
shimniok 0:826c6171fc1b 93 mavlink_message_t msg;
shimniok 0:826c6171fc1b 94 mavlink_msg_param_value_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, param_id, param_value, param_count, param_index);
shimniok 0:826c6171fc1b 95 mavlink_send_uart(chan, &msg);
shimniok 0:826c6171fc1b 96 }
shimniok 0:826c6171fc1b 97
shimniok 0:826c6171fc1b 98 #endif
shimniok 0:826c6171fc1b 99 // MESSAGE PARAM_VALUE UNPACKING
shimniok 0:826c6171fc1b 100
shimniok 0:826c6171fc1b 101 /**
shimniok 0:826c6171fc1b 102 * @brief Get field param_id from param_value message
shimniok 0:826c6171fc1b 103 *
shimniok 0:826c6171fc1b 104 * @return Onboard parameter id
shimniok 0:826c6171fc1b 105 */
shimniok 0:826c6171fc1b 106 static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, int8_t* r_data)
shimniok 0:826c6171fc1b 107 {
shimniok 0:826c6171fc1b 108
shimniok 0:826c6171fc1b 109 memcpy(r_data, msg->payload, 15);
shimniok 0:826c6171fc1b 110 return 15;
shimniok 0:826c6171fc1b 111 }
shimniok 0:826c6171fc1b 112
shimniok 0:826c6171fc1b 113 /**
shimniok 0:826c6171fc1b 114 * @brief Get field param_value from param_value message
shimniok 0:826c6171fc1b 115 *
shimniok 0:826c6171fc1b 116 * @return Onboard parameter value
shimniok 0:826c6171fc1b 117 */
shimniok 0:826c6171fc1b 118 static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 119 {
shimniok 0:826c6171fc1b 120 generic_32bit r;
shimniok 0:826c6171fc1b 121 r.b[3] = (msg->payload+15)[0];
shimniok 0:826c6171fc1b 122 r.b[2] = (msg->payload+15)[1];
shimniok 0:826c6171fc1b 123 r.b[1] = (msg->payload+15)[2];
shimniok 0:826c6171fc1b 124 r.b[0] = (msg->payload+15)[3];
shimniok 0:826c6171fc1b 125 return (float)r.f;
shimniok 0:826c6171fc1b 126 }
shimniok 0:826c6171fc1b 127
shimniok 0:826c6171fc1b 128 /**
shimniok 0:826c6171fc1b 129 * @brief Get field param_count from param_value message
shimniok 0:826c6171fc1b 130 *
shimniok 0:826c6171fc1b 131 * @return Total number of onboard parameters
shimniok 0:826c6171fc1b 132 */
shimniok 0:826c6171fc1b 133 static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 134 {
shimniok 0:826c6171fc1b 135 generic_16bit r;
shimniok 0:826c6171fc1b 136 r.b[1] = (msg->payload+15+sizeof(float))[0];
shimniok 0:826c6171fc1b 137 r.b[0] = (msg->payload+15+sizeof(float))[1];
shimniok 0:826c6171fc1b 138 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 139 }
shimniok 0:826c6171fc1b 140
shimniok 0:826c6171fc1b 141 /**
shimniok 0:826c6171fc1b 142 * @brief Get field param_index from param_value message
shimniok 0:826c6171fc1b 143 *
shimniok 0:826c6171fc1b 144 * @return Index of this onboard parameter
shimniok 0:826c6171fc1b 145 */
shimniok 0:826c6171fc1b 146 static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 147 {
shimniok 0:826c6171fc1b 148 generic_16bit r;
shimniok 0:826c6171fc1b 149 r.b[1] = (msg->payload+15+sizeof(float)+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 150 r.b[0] = (msg->payload+15+sizeof(float)+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 151 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 152 }
shimniok 0:826c6171fc1b 153
shimniok 0:826c6171fc1b 154 /**
shimniok 0:826c6171fc1b 155 * @brief Decode a param_value message into a struct
shimniok 0:826c6171fc1b 156 *
shimniok 0:826c6171fc1b 157 * @param msg The message to decode
shimniok 0:826c6171fc1b 158 * @param param_value C-struct to decode the message contents into
shimniok 0:826c6171fc1b 159 */
shimniok 0:826c6171fc1b 160 static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value)
shimniok 0:826c6171fc1b 161 {
shimniok 0:826c6171fc1b 162 mavlink_msg_param_value_get_param_id(msg, param_value->param_id);
shimniok 0:826c6171fc1b 163 param_value->param_value = mavlink_msg_param_value_get_param_value(msg);
shimniok 0:826c6171fc1b 164 param_value->param_count = mavlink_msg_param_value_get_param_count(msg);
shimniok 0:826c6171fc1b 165 param_value->param_index = mavlink_msg_param_value_get_param_index(msg);
shimniok 0:826c6171fc1b 166 }