Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers mavlink_msg_param_value.h Source File

mavlink_msg_param_value.h

00001 // MESSAGE PARAM_VALUE PACKING
00002 
00003 #define MAVLINK_MSG_ID_PARAM_VALUE 22
00004 
00005 typedef struct __mavlink_param_value_t 
00006 {
00007     int8_t param_id[15]; ///< Onboard parameter id
00008     float param_value; ///< Onboard parameter value
00009     uint16_t param_count; ///< Total number of onboard parameters
00010     uint16_t param_index; ///< Index of this onboard parameter
00011 
00012 } mavlink_param_value_t;
00013 
00014 #define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 15
00015 
00016 
00017 /**
00018  * @brief Pack a param_value message
00019  * @param system_id ID of this system
00020  * @param component_id ID of this component (e.g. 200 for IMU)
00021  * @param msg The MAVLink message to compress the data into
00022  *
00023  * @param param_id Onboard parameter id
00024  * @param param_value Onboard parameter value
00025  * @param param_count Total number of onboard parameters
00026  * @param param_index Index of this onboard parameter
00027  * @return length of the message in bytes (excluding serial stream start sign)
00028  */
00029 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)
00030 {
00031     uint16_t i = 0;
00032     msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
00033 
00034     i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
00035     i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
00036     i += put_uint16_t_by_index(param_count, i, msg->payload); // Total number of onboard parameters
00037     i += put_uint16_t_by_index(param_index, i, msg->payload); // Index of this onboard parameter
00038 
00039     return mavlink_finalize_message(msg, system_id, component_id, i);
00040 }
00041 
00042 /**
00043  * @brief Pack a param_value message
00044  * @param system_id ID of this system
00045  * @param component_id ID of this component (e.g. 200 for IMU)
00046  * @param chan The MAVLink channel this message was sent over
00047  * @param msg The MAVLink message to compress the data into
00048  * @param param_id Onboard parameter id
00049  * @param param_value Onboard parameter value
00050  * @param param_count Total number of onboard parameters
00051  * @param param_index Index of this onboard parameter
00052  * @return length of the message in bytes (excluding serial stream start sign)
00053  */
00054 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)
00055 {
00056     uint16_t i = 0;
00057     msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
00058 
00059     i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
00060     i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
00061     i += put_uint16_t_by_index(param_count, i, msg->payload); // Total number of onboard parameters
00062     i += put_uint16_t_by_index(param_index, i, msg->payload); // Index of this onboard parameter
00063 
00064     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00065 }
00066 
00067 /**
00068  * @brief Encode a param_value struct into a message
00069  *
00070  * @param system_id ID of this system
00071  * @param component_id ID of this component (e.g. 200 for IMU)
00072  * @param msg The MAVLink message to compress the data into
00073  * @param param_value C-struct to read the message contents from
00074  */
00075 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)
00076 {
00077     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);
00078 }
00079 
00080 /**
00081  * @brief Send a param_value message
00082  * @param chan MAVLink channel to send the message
00083  *
00084  * @param param_id Onboard parameter id
00085  * @param param_value Onboard parameter value
00086  * @param param_count Total number of onboard parameters
00087  * @param param_index Index of this onboard parameter
00088  */
00089 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00090 
00091 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)
00092 {
00093     mavlink_message_t msg;
00094     mavlink_msg_param_value_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, param_id, param_value, param_count, param_index);
00095     mavlink_send_uart(chan, &msg);
00096 }
00097 
00098 #endif
00099 // MESSAGE PARAM_VALUE UNPACKING
00100 
00101 /**
00102  * @brief Get field param_id from param_value message
00103  *
00104  * @return Onboard parameter id
00105  */
00106 static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, int8_t* r_data)
00107 {
00108 
00109     memcpy(r_data, msg->payload, 15);
00110     return 15;
00111 }
00112 
00113 /**
00114  * @brief Get field param_value from param_value message
00115  *
00116  * @return Onboard parameter value
00117  */
00118 static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg)
00119 {
00120     generic_32bit r;
00121     r.b[3] = (msg->payload+15)[0];
00122     r.b[2] = (msg->payload+15)[1];
00123     r.b[1] = (msg->payload+15)[2];
00124     r.b[0] = (msg->payload+15)[3];
00125     return (float)r.f;
00126 }
00127 
00128 /**
00129  * @brief Get field param_count from param_value message
00130  *
00131  * @return Total number of onboard parameters
00132  */
00133 static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg)
00134 {
00135     generic_16bit r;
00136     r.b[1] = (msg->payload+15+sizeof(float))[0];
00137     r.b[0] = (msg->payload+15+sizeof(float))[1];
00138     return (uint16_t)r.s;
00139 }
00140 
00141 /**
00142  * @brief Get field param_index from param_value message
00143  *
00144  * @return Index of this onboard parameter
00145  */
00146 static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg)
00147 {
00148     generic_16bit r;
00149     r.b[1] = (msg->payload+15+sizeof(float)+sizeof(uint16_t))[0];
00150     r.b[0] = (msg->payload+15+sizeof(float)+sizeof(uint16_t))[1];
00151     return (uint16_t)r.s;
00152 }
00153 
00154 /**
00155  * @brief Decode a param_value message into a struct
00156  *
00157  * @param msg The message to decode
00158  * @param param_value C-struct to decode the message contents into
00159  */
00160 static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value)
00161 {
00162     mavlink_msg_param_value_get_param_id(msg, param_value->param_id);
00163     param_value->param_value = mavlink_msg_param_value_get_param_value(msg);
00164     param_value->param_count = mavlink_msg_param_value_get_param_count(msg);
00165     param_value->param_index = mavlink_msg_param_value_get_param_index(msg);
00166 }