Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE NAMED_VALUE_INT PACKING
2
 
3
#define MAVLINK_MSG_ID_NAMED_VALUE_INT 252
4
 
5
typedef struct __mavlink_named_value_int_t
6
{
7
 uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
8
 int32_t value; ///< Signed integer value
9
 char name[10]; ///< Name of the debug variable
10
} mavlink_named_value_int_t;
11
 
12
#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18
13
#define MAVLINK_MSG_ID_252_LEN 18
14
 
15
#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10
16
 
17
#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \
18
        "NAMED_VALUE_INT", \
19
        3, \
20
        {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \
21
         { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \
22
         { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \
23
         } \
24
}
25
 
26
 
27
/**
28
 * @brief Pack a named_value_int message
29
 * @param system_id ID of this system
30
 * @param component_id ID of this component (e.g. 200 for IMU)
31
 * @param msg The MAVLink message to compress the data into
32
 *
33
 * @param time_boot_ms Timestamp (milliseconds since system boot)
34
 * @param name Name of the debug variable
35
 * @param value Signed integer value
36
 * @return length of the message in bytes (excluding serial stream start sign)
37
 */
38
static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
39
                                                       uint32_t time_boot_ms, const char *name, int32_t value)
40
{
41
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
42
        char buf[18];
43
        _mav_put_uint32_t(buf, 0, time_boot_ms);
44
        _mav_put_int32_t(buf, 4, value);
45
        _mav_put_char_array(buf, 8, name, 10);
46
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
47
#else
48
        mavlink_named_value_int_t packet;
49
        packet.time_boot_ms = time_boot_ms;
50
        packet.value = value;
51
        mav_array_memcpy(packet.name, name, sizeof(char)*10);
52
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
53
#endif
54
 
55
        msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
56
        return mavlink_finalize_message(msg, system_id, component_id, 18, 44);
57
}
58
 
59
/**
60
 * @brief Pack a named_value_int message on a channel
61
 * @param system_id ID of this system
62
 * @param component_id ID of this component (e.g. 200 for IMU)
63
 * @param chan The MAVLink channel this message was sent over
64
 * @param msg The MAVLink message to compress the data into
65
 * @param time_boot_ms Timestamp (milliseconds since system boot)
66
 * @param name Name of the debug variable
67
 * @param value Signed integer value
68
 * @return length of the message in bytes (excluding serial stream start sign)
69
 */
70
static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
71
                                                           mavlink_message_t* msg,
72
                                                           uint32_t time_boot_ms,const char *name,int32_t value)
73
{
74
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
75
        char buf[18];
76
        _mav_put_uint32_t(buf, 0, time_boot_ms);
77
        _mav_put_int32_t(buf, 4, value);
78
        _mav_put_char_array(buf, 8, name, 10);
79
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
80
#else
81
        mavlink_named_value_int_t packet;
82
        packet.time_boot_ms = time_boot_ms;
83
        packet.value = value;
84
        mav_array_memcpy(packet.name, name, sizeof(char)*10);
85
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
86
#endif
87
 
88
        msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
89
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 44);
90
}
91
 
92
/**
93
 * @brief Encode a named_value_int struct into a message
94
 *
95
 * @param system_id ID of this system
96
 * @param component_id ID of this component (e.g. 200 for IMU)
97
 * @param msg The MAVLink message to compress the data into
98
 * @param named_value_int C-struct to read the message contents from
99
 */
100
static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int)
101
{
102
        return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value);
103
}
104
 
105
/**
106
 * @brief Send a named_value_int message
107
 * @param chan MAVLink channel to send the message
108
 *
109
 * @param time_boot_ms Timestamp (milliseconds since system boot)
110
 * @param name Name of the debug variable
111
 * @param value Signed integer value
112
 */
113
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
114
 
115
static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value)
116
{
117
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
118
        char buf[18];
119
        _mav_put_uint32_t(buf, 0, time_boot_ms);
120
        _mav_put_int32_t(buf, 4, value);
121
        _mav_put_char_array(buf, 8, name, 10);
122
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, 18, 44);
123
#else
124
        mavlink_named_value_int_t packet;
125
        packet.time_boot_ms = time_boot_ms;
126
        packet.value = value;
127
        mav_array_memcpy(packet.name, name, sizeof(char)*10);
128
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, 18, 44);
129
#endif
130
}
131
 
132
#endif
133
 
134
// MESSAGE NAMED_VALUE_INT UNPACKING
135
 
136
 
137
/**
138
 * @brief Get field time_boot_ms from named_value_int message
139
 *
140
 * @return Timestamp (milliseconds since system boot)
141
 */
142
static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlink_message_t* msg)
143
{
144
        return _MAV_RETURN_uint32_t(msg,  0);
145
}
146
 
147
/**
148
 * @brief Get field name from named_value_int message
149
 *
150
 * @return Name of the debug variable
151
 */
152
static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char *name)
153
{
154
        return _MAV_RETURN_char_array(msg, name, 10,  8);
155
}
156
 
157
/**
158
 * @brief Get field value from named_value_int message
159
 *
160
 * @return Signed integer value
161
 */
162
static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg)
163
{
164
        return _MAV_RETURN_int32_t(msg,  4);
165
}
166
 
167
/**
168
 * @brief Decode a named_value_int message into a struct
169
 *
170
 * @param msg The message to decode
171
 * @param named_value_int C-struct to decode the message contents into
172
 */
173
static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int)
174
{
175
#if MAVLINK_NEED_BYTE_SWAP
176
        named_value_int->time_boot_ms = mavlink_msg_named_value_int_get_time_boot_ms(msg);
177
        named_value_int->value = mavlink_msg_named_value_int_get_value(msg);
178
        mavlink_msg_named_value_int_get_name(msg, named_value_int->name);
179
#else
180
        memcpy(named_value_int, _MAV_PAYLOAD(msg), 18);
181
#endif
182
}