mavlink_msg_param_set.h
Go to the documentation of this file.
00001 // MESSAGE PARAM_SET PACKING
00002 
00003 #define MAVLINK_MSG_ID_PARAM_SET 23
00004 
00005 typedef struct __mavlink_param_set_t
00006 {
00007  float param_value; /*< Onboard parameter value*/
00008  uint8_t target_system; /*< System ID*/
00009  uint8_t target_component; /*< Component ID*/
00010  char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/
00011  uint8_t param_type; /*< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.*/
00012 } mavlink_param_set_t;
00013 
00014 #define MAVLINK_MSG_ID_PARAM_SET_LEN 23
00015 #define MAVLINK_MSG_ID_23_LEN 23
00016 
00017 #define MAVLINK_MSG_ID_PARAM_SET_CRC 168
00018 #define MAVLINK_MSG_ID_23_CRC 168
00019 
00020 #define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16
00021 
00022 #define MAVLINK_MESSAGE_INFO_PARAM_SET { \
00023         "PARAM_SET", \
00024         5, \
00025         {  { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \
00026          { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \
00027          { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \
00028          { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \
00029          { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \
00030          } \
00031 }
00032 
00033 
00047 static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00048                                                        uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type)
00049 {
00050 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00051         char buf[MAVLINK_MSG_ID_PARAM_SET_LEN];
00052         _mav_put_float(buf, 0, param_value);
00053         _mav_put_uint8_t(buf, 4, target_system);
00054         _mav_put_uint8_t(buf, 5, target_component);
00055         _mav_put_uint8_t(buf, 22, param_type);
00056         _mav_put_char_array(buf, 6, param_id, 16);
00057         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN);
00058 #else
00059         mavlink_param_set_t packet;
00060         packet.param_value = param_value;
00061         packet.target_system = target_system;
00062         packet.target_component = target_component;
00063         packet.param_type = param_type;
00064         mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
00065         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN);
00066 #endif
00067 
00068         msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
00069 #if MAVLINK_CRC_EXTRA
00070     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
00071 #else
00072     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN);
00073 #endif
00074 }
00075 
00089 static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00090                                                            mavlink_message_t* msg,
00091                                                            uint8_t target_system,uint8_t target_component,const char *param_id,float param_value,uint8_t param_type)
00092 {
00093 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00094         char buf[MAVLINK_MSG_ID_PARAM_SET_LEN];
00095         _mav_put_float(buf, 0, param_value);
00096         _mav_put_uint8_t(buf, 4, target_system);
00097         _mav_put_uint8_t(buf, 5, target_component);
00098         _mav_put_uint8_t(buf, 22, param_type);
00099         _mav_put_char_array(buf, 6, param_id, 16);
00100         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN);
00101 #else
00102         mavlink_param_set_t packet;
00103         packet.param_value = param_value;
00104         packet.target_system = target_system;
00105         packet.target_component = target_component;
00106         packet.param_type = param_type;
00107         mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
00108         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN);
00109 #endif
00110 
00111         msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
00112 #if MAVLINK_CRC_EXTRA
00113     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
00114 #else
00115     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN);
00116 #endif
00117 }
00118 
00127 static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set)
00128 {
00129         return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type);
00130 }
00131 
00141 static inline uint16_t mavlink_msg_param_set_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_set_t* param_set)
00142 {
00143         return mavlink_msg_param_set_pack_chan(system_id, component_id, chan, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type);
00144 }
00145 
00156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00157 
00158 static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type)
00159 {
00160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00161         char buf[MAVLINK_MSG_ID_PARAM_SET_LEN];
00162         _mav_put_float(buf, 0, param_value);
00163         _mav_put_uint8_t(buf, 4, target_system);
00164         _mav_put_uint8_t(buf, 5, target_component);
00165         _mav_put_uint8_t(buf, 22, param_type);
00166         _mav_put_char_array(buf, 6, param_id, 16);
00167 #if MAVLINK_CRC_EXTRA
00168     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
00169 #else
00170     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN);
00171 #endif
00172 #else
00173         mavlink_param_set_t packet;
00174         packet.param_value = param_value;
00175         packet.target_system = target_system;
00176         packet.target_component = target_component;
00177         packet.param_type = param_type;
00178         mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
00179 #if MAVLINK_CRC_EXTRA
00180     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
00181 #else
00182     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN);
00183 #endif
00184 #endif
00185 }
00186 
00187 #if MAVLINK_MSG_ID_PARAM_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00188 /*
00189   This varient of _send() can be used to save stack space by re-using
00190   memory from the receive buffer.  The caller provides a
00191   mavlink_message_t which is the size of a full mavlink message. This
00192   is usually the receive buffer for the channel, and allows a reply to an
00193   incoming message with minimum stack space usage.
00194  */
00195 static inline void mavlink_msg_param_set_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type)
00196 {
00197 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00198         char *buf = (char *)msgbuf;
00199         _mav_put_float(buf, 0, param_value);
00200         _mav_put_uint8_t(buf, 4, target_system);
00201         _mav_put_uint8_t(buf, 5, target_component);
00202         _mav_put_uint8_t(buf, 22, param_type);
00203         _mav_put_char_array(buf, 6, param_id, 16);
00204 #if MAVLINK_CRC_EXTRA
00205     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
00206 #else
00207     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN);
00208 #endif
00209 #else
00210         mavlink_param_set_t *packet = (mavlink_param_set_t *)msgbuf;
00211         packet->param_value = param_value;
00212         packet->target_system = target_system;
00213         packet->target_component = target_component;
00214         packet->param_type = param_type;
00215         mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16);
00216 #if MAVLINK_CRC_EXTRA
00217     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
00218 #else
00219     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN);
00220 #endif
00221 #endif
00222 }
00223 #endif
00224 
00225 #endif
00226 
00227 // MESSAGE PARAM_SET UNPACKING
00228 
00229 
00235 static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg)
00236 {
00237         return _MAV_RETURN_uint8_t(msg,  4);
00238 }
00239 
00245 static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg)
00246 {
00247         return _MAV_RETURN_uint8_t(msg,  5);
00248 }
00249 
00255 static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char *param_id)
00256 {
00257         return _MAV_RETURN_char_array(msg, param_id, 16,  6);
00258 }
00259 
00265 static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg)
00266 {
00267         return _MAV_RETURN_float(msg,  0);
00268 }
00269 
00275 static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg)
00276 {
00277         return _MAV_RETURN_uint8_t(msg,  22);
00278 }
00279 
00286 static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set)
00287 {
00288 #if MAVLINK_NEED_BYTE_SWAP
00289         param_set->param_value = mavlink_msg_param_set_get_param_value(msg);
00290         param_set->target_system = mavlink_msg_param_set_get_target_system(msg);
00291         param_set->target_component = mavlink_msg_param_set_get_target_component(msg);
00292         mavlink_msg_param_set_get_param_id(msg, param_set->param_id);
00293         param_set->param_type = mavlink_msg_param_set_get_param_type(msg);
00294 #else
00295         memcpy(param_set, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_SET_LEN);
00296 #endif
00297 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:35