Subversion Repositories Projects

Rev

Go to most recent revision | Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE MEMORY_VECT PACKING
2
 
3
#define MAVLINK_MSG_ID_MEMORY_VECT 249
4
 
5
typedef struct __mavlink_memory_vect_t
6
{
7
 uint16_t address; ///< Starting address of the debug variables
8
 uint8_t ver; ///< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
9
 uint8_t type; ///< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
10
 int8_t value[32]; ///< Memory contents at specified address
11
} mavlink_memory_vect_t;
12
 
13
#define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36
14
#define MAVLINK_MSG_ID_249_LEN 36
15
 
16
#define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN 32
17
 
18
#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \
19
        "MEMORY_VECT", \
20
        4, \
21
        {  { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \
22
         { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \
23
         { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \
24
         { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \
25
         } \
26
}
27
 
28
 
29
/**
30
 * @brief Pack a memory_vect message
31
 * @param system_id ID of this system
32
 * @param component_id ID of this component (e.g. 200 for IMU)
33
 * @param msg The MAVLink message to compress the data into
34
 *
35
 * @param address Starting address of the debug variables
36
 * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
37
 * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
38
 * @param value Memory contents at specified address
39
 * @return length of the message in bytes (excluding serial stream start sign)
40
 */
41
static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42
                                                       uint16_t address, uint8_t ver, uint8_t type, const int8_t *value)
43
{
44
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
45
        char buf[36];
46
        _mav_put_uint16_t(buf, 0, address);
47
        _mav_put_uint8_t(buf, 2, ver);
48
        _mav_put_uint8_t(buf, 3, type);
49
        _mav_put_int8_t_array(buf, 4, value, 32);
50
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
51
#else
52
        mavlink_memory_vect_t packet;
53
        packet.address = address;
54
        packet.ver = ver;
55
        packet.type = type;
56
        mav_array_memcpy(packet.value, value, sizeof(int8_t)*32);
57
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
58
#endif
59
 
60
        msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT;
61
        return mavlink_finalize_message(msg, system_id, component_id, 36, 204);
62
}
63
 
64
/**
65
 * @brief Pack a memory_vect message on a channel
66
 * @param system_id ID of this system
67
 * @param component_id ID of this component (e.g. 200 for IMU)
68
 * @param chan The MAVLink channel this message was sent over
69
 * @param msg The MAVLink message to compress the data into
70
 * @param address Starting address of the debug variables
71
 * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
72
 * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
73
 * @param value Memory contents at specified address
74
 * @return length of the message in bytes (excluding serial stream start sign)
75
 */
76
static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
77
                                                           mavlink_message_t* msg,
78
                                                           uint16_t address,uint8_t ver,uint8_t type,const int8_t *value)
79
{
80
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
81
        char buf[36];
82
        _mav_put_uint16_t(buf, 0, address);
83
        _mav_put_uint8_t(buf, 2, ver);
84
        _mav_put_uint8_t(buf, 3, type);
85
        _mav_put_int8_t_array(buf, 4, value, 32);
86
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
87
#else
88
        mavlink_memory_vect_t packet;
89
        packet.address = address;
90
        packet.ver = ver;
91
        packet.type = type;
92
        mav_array_memcpy(packet.value, value, sizeof(int8_t)*32);
93
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
94
#endif
95
 
96
        msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT;
97
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 204);
98
}
99
 
100
/**
101
 * @brief Encode a memory_vect struct into a message
102
 *
103
 * @param system_id ID of this system
104
 * @param component_id ID of this component (e.g. 200 for IMU)
105
 * @param msg The MAVLink message to compress the data into
106
 * @param memory_vect C-struct to read the message contents from
107
 */
108
static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect)
109
{
110
        return mavlink_msg_memory_vect_pack(system_id, component_id, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value);
111
}
112
 
113
/**
114
 * @brief Send a memory_vect message
115
 * @param chan MAVLink channel to send the message
116
 *
117
 * @param address Starting address of the debug variables
118
 * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
119
 * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
120
 * @param value Memory contents at specified address
121
 */
122
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
123
 
124
static inline void mavlink_msg_memory_vect_send(mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value)
125
{
126
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
127
        char buf[36];
128
        _mav_put_uint16_t(buf, 0, address);
129
        _mav_put_uint8_t(buf, 2, ver);
130
        _mav_put_uint8_t(buf, 3, type);
131
        _mav_put_int8_t_array(buf, 4, value, 32);
132
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, 36, 204);
133
#else
134
        mavlink_memory_vect_t packet;
135
        packet.address = address;
136
        packet.ver = ver;
137
        packet.type = type;
138
        mav_array_memcpy(packet.value, value, sizeof(int8_t)*32);
139
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, 36, 204);
140
#endif
141
}
142
 
143
#endif
144
 
145
// MESSAGE MEMORY_VECT UNPACKING
146
 
147
 
148
/**
149
 * @brief Get field address from memory_vect message
150
 *
151
 * @return Starting address of the debug variables
152
 */
153
static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t* msg)
154
{
155
        return _MAV_RETURN_uint16_t(msg,  0);
156
}
157
 
158
/**
159
 * @brief Get field ver from memory_vect message
160
 *
161
 * @return Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
162
 */
163
static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* msg)
164
{
165
        return _MAV_RETURN_uint8_t(msg,  2);
166
}
167
 
168
/**
169
 * @brief Get field type from memory_vect message
170
 *
171
 * @return Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
172
 */
173
static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* msg)
174
{
175
        return _MAV_RETURN_uint8_t(msg,  3);
176
}
177
 
178
/**
179
 * @brief Get field value from memory_vect message
180
 *
181
 * @return Memory contents at specified address
182
 */
183
static inline uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t* msg, int8_t *value)
184
{
185
        return _MAV_RETURN_int8_t_array(msg, value, 32,  4);
186
}
187
 
188
/**
189
 * @brief Decode a memory_vect message into a struct
190
 *
191
 * @param msg The message to decode
192
 * @param memory_vect C-struct to decode the message contents into
193
 */
194
static inline void mavlink_msg_memory_vect_decode(const mavlink_message_t* msg, mavlink_memory_vect_t* memory_vect)
195
{
196
#if MAVLINK_NEED_BYTE_SWAP
197
        memory_vect->address = mavlink_msg_memory_vect_get_address(msg);
198
        memory_vect->ver = mavlink_msg_memory_vect_get_ver(msg);
199
        memory_vect->type = mavlink_msg_memory_vect_get_type(msg);
200
        mavlink_msg_memory_vect_get_value(msg, memory_vect->value);
201
#else
202
        memcpy(memory_vect, _MAV_PAYLOAD(msg), 36);
203
#endif
204
}