mavlink_msg_param_request_read.h
Go to the documentation of this file.
00001 // MESSAGE PARAM_REQUEST_READ PACKING
00002 
00003 #define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20
00004 
00005 typedef struct __mavlink_param_request_read_t
00006 {
00007  int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)*/
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 } mavlink_param_request_read_t;
00012 
00013 #define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20
00014 #define MAVLINK_MSG_ID_20_LEN 20
00015 
00016 #define MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC 214
00017 #define MAVLINK_MSG_ID_20_CRC 214
00018 
00019 #define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 16
00020 
00021 #define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \
00022         "PARAM_REQUEST_READ", \
00023         4, \
00024         {  { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \
00025          { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \
00026          { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \
00027          { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \
00028          } \
00029 }
00030 
00031 
00044 static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00045                                                        uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index)
00046 {
00047 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00048         char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN];
00049         _mav_put_int16_t(buf, 0, param_index);
00050         _mav_put_uint8_t(buf, 2, target_system);
00051         _mav_put_uint8_t(buf, 3, target_component);
00052         _mav_put_char_array(buf, 4, param_id, 16);
00053         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
00054 #else
00055         mavlink_param_request_read_t packet;
00056         packet.param_index = param_index;
00057         packet.target_system = target_system;
00058         packet.target_component = target_component;
00059         mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
00060         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
00061 #endif
00062 
00063         msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
00064 #if MAVLINK_CRC_EXTRA
00065     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
00066 #else
00067     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
00068 #endif
00069 }
00070 
00083 static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00084                                                            mavlink_message_t* msg,
00085                                                            uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index)
00086 {
00087 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00088         char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN];
00089         _mav_put_int16_t(buf, 0, param_index);
00090         _mav_put_uint8_t(buf, 2, target_system);
00091         _mav_put_uint8_t(buf, 3, target_component);
00092         _mav_put_char_array(buf, 4, param_id, 16);
00093         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
00094 #else
00095         mavlink_param_request_read_t packet;
00096         packet.param_index = param_index;
00097         packet.target_system = target_system;
00098         packet.target_component = target_component;
00099         mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
00100         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
00101 #endif
00102 
00103         msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
00104 #if MAVLINK_CRC_EXTRA
00105     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
00106 #else
00107     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
00108 #endif
00109 }
00110 
00119 static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read)
00120 {
00121         return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index);
00122 }
00123 
00133 static inline uint16_t mavlink_msg_param_request_read_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read)
00134 {
00135         return mavlink_msg_param_request_read_pack_chan(system_id, component_id, chan, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index);
00136 }
00137 
00147 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00148 
00149 static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index)
00150 {
00151 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00152         char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN];
00153         _mav_put_int16_t(buf, 0, param_index);
00154         _mav_put_uint8_t(buf, 2, target_system);
00155         _mav_put_uint8_t(buf, 3, target_component);
00156         _mav_put_char_array(buf, 4, param_id, 16);
00157 #if MAVLINK_CRC_EXTRA
00158     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
00159 #else
00160     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
00161 #endif
00162 #else
00163         mavlink_param_request_read_t packet;
00164         packet.param_index = param_index;
00165         packet.target_system = target_system;
00166         packet.target_component = target_component;
00167         mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
00168 #if MAVLINK_CRC_EXTRA
00169     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
00170 #else
00171     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
00172 #endif
00173 #endif
00174 }
00175 
00176 #if MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00177 /*
00178   This varient of _send() can be used to save stack space by re-using
00179   memory from the receive buffer.  The caller provides a
00180   mavlink_message_t which is the size of a full mavlink message. This
00181   is usually the receive buffer for the channel, and allows a reply to an
00182   incoming message with minimum stack space usage.
00183  */
00184 static inline void mavlink_msg_param_request_read_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index)
00185 {
00186 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00187         char *buf = (char *)msgbuf;
00188         _mav_put_int16_t(buf, 0, param_index);
00189         _mav_put_uint8_t(buf, 2, target_system);
00190         _mav_put_uint8_t(buf, 3, target_component);
00191         _mav_put_char_array(buf, 4, param_id, 16);
00192 #if MAVLINK_CRC_EXTRA
00193     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
00194 #else
00195     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
00196 #endif
00197 #else
00198         mavlink_param_request_read_t *packet = (mavlink_param_request_read_t *)msgbuf;
00199         packet->param_index = param_index;
00200         packet->target_system = target_system;
00201         packet->target_component = target_component;
00202         mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16);
00203 #if MAVLINK_CRC_EXTRA
00204     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
00205 #else
00206     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
00207 #endif
00208 #endif
00209 }
00210 #endif
00211 
00212 #endif
00213 
00214 // MESSAGE PARAM_REQUEST_READ UNPACKING
00215 
00216 
00222 static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg)
00223 {
00224         return _MAV_RETURN_uint8_t(msg,  2);
00225 }
00226 
00232 static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg)
00233 {
00234         return _MAV_RETURN_uint8_t(msg,  3);
00235 }
00236 
00242 static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char *param_id)
00243 {
00244         return _MAV_RETURN_char_array(msg, param_id, 16,  4);
00245 }
00246 
00252 static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg)
00253 {
00254         return _MAV_RETURN_int16_t(msg,  0);
00255 }
00256 
00263 static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read)
00264 {
00265 #if MAVLINK_NEED_BYTE_SWAP
00266         param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg);
00267         param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg);
00268         param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg);
00269         mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id);
00270 #else
00271         memcpy(param_request_read, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
00272 #endif
00273 }


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