Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

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