Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE PING PACKING
2
 
3
#define MAVLINK_MSG_ID_PING 3
4
 
5
typedef struct __mavlink_ping_t
6
{
7
 uint32_t seq; ///< PING sequence
8
 uint8_t target_system; ///< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
9
 uint8_t target_component; ///< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
10
 uint64_t time; ///< Unix timestamp in microseconds
11
} mavlink_ping_t;
12
 
13
#define MAVLINK_MSG_ID_PING_LEN 14
14
#define MAVLINK_MSG_ID_3_LEN 14
15
 
16
 
17
 
18
#define MAVLINK_MESSAGE_INFO_PING { \
19
        "PING", \
20
        4, \
21
        {  { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ping_t, seq) }, \
22
         { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_ping_t, target_system) }, \
23
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_ping_t, target_component) }, \
24
         { "time", NULL, MAVLINK_TYPE_UINT64_T, 0, 6, offsetof(mavlink_ping_t, time) }, \
25
         } \
26
}
27
 
28
 
29
/**
30
 * @brief Pack a ping 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 seq PING sequence
36
 * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
37
 * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
38
 * @param time Unix timestamp in microseconds
39
 * @return length of the message in bytes (excluding serial stream start sign)
40
 */
41
static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42
                                                       uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
43
{
44
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
45
        char buf[14];
46
        _mav_put_uint32_t(buf, 0, seq);
47
        _mav_put_uint8_t(buf, 4, target_system);
48
        _mav_put_uint8_t(buf, 5, target_component);
49
        _mav_put_uint64_t(buf, 6, time);
50
 
51
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
52
#else
53
        mavlink_ping_t packet;
54
        packet.seq = seq;
55
        packet.target_system = target_system;
56
        packet.target_component = target_component;
57
        packet.time = time;
58
 
59
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
60
#endif
61
 
62
        msg->msgid = MAVLINK_MSG_ID_PING;
63
        return mavlink_finalize_message(msg, system_id, component_id, 14);
64
}
65
 
66
/**
67
 * @brief Pack a ping message on a channel
68
 * @param system_id ID of this system
69
 * @param component_id ID of this component (e.g. 200 for IMU)
70
 * @param chan The MAVLink channel this message was sent over
71
 * @param msg The MAVLink message to compress the data into
72
 * @param seq PING sequence
73
 * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
74
 * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
75
 * @param time Unix timestamp in microseconds
76
 * @return length of the message in bytes (excluding serial stream start sign)
77
 */
78
static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
79
                                                           mavlink_message_t* msg,
80
                                                           uint32_t seq,uint8_t target_system,uint8_t target_component,uint64_t time)
81
{
82
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
83
        char buf[14];
84
        _mav_put_uint32_t(buf, 0, seq);
85
        _mav_put_uint8_t(buf, 4, target_system);
86
        _mav_put_uint8_t(buf, 5, target_component);
87
        _mav_put_uint64_t(buf, 6, time);
88
 
89
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
90
#else
91
        mavlink_ping_t packet;
92
        packet.seq = seq;
93
        packet.target_system = target_system;
94
        packet.target_component = target_component;
95
        packet.time = time;
96
 
97
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
98
#endif
99
 
100
        msg->msgid = MAVLINK_MSG_ID_PING;
101
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14);
102
}
103
 
104
/**
105
 * @brief Encode a ping struct into a message
106
 *
107
 * @param system_id ID of this system
108
 * @param component_id ID of this component (e.g. 200 for IMU)
109
 * @param msg The MAVLink message to compress the data into
110
 * @param ping C-struct to read the message contents from
111
 */
112
static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping)
113
{
114
        return mavlink_msg_ping_pack(system_id, component_id, msg, ping->seq, ping->target_system, ping->target_component, ping->time);
115
}
116
 
117
/**
118
 * @brief Send a ping message
119
 * @param chan MAVLink channel to send the message
120
 *
121
 * @param seq PING sequence
122
 * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
123
 * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
124
 * @param time Unix timestamp in microseconds
125
 */
126
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
127
 
128
static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
129
{
130
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
131
        char buf[14];
132
        _mav_put_uint32_t(buf, 0, seq);
133
        _mav_put_uint8_t(buf, 4, target_system);
134
        _mav_put_uint8_t(buf, 5, target_component);
135
        _mav_put_uint64_t(buf, 6, time);
136
 
137
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, 14);
138
#else
139
        mavlink_ping_t packet;
140
        packet.seq = seq;
141
        packet.target_system = target_system;
142
        packet.target_component = target_component;
143
        packet.time = time;
144
 
145
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, 14);
146
#endif
147
}
148
 
149
#endif
150
 
151
// MESSAGE PING UNPACKING
152
 
153
 
154
/**
155
 * @brief Get field seq from ping message
156
 *
157
 * @return PING sequence
158
 */
159
static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg)
160
{
161
        return _MAV_RETURN_uint32_t(msg,  0);
162
}
163
 
164
/**
165
 * @brief Get field target_system from ping message
166
 *
167
 * @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
168
 */
169
static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg)
170
{
171
        return _MAV_RETURN_uint8_t(msg,  4);
172
}
173
 
174
/**
175
 * @brief Get field target_component from ping message
176
 *
177
 * @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
178
 */
179
static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg)
180
{
181
        return _MAV_RETURN_uint8_t(msg,  5);
182
}
183
 
184
/**
185
 * @brief Get field time from ping message
186
 *
187
 * @return Unix timestamp in microseconds
188
 */
189
static inline uint64_t mavlink_msg_ping_get_time(const mavlink_message_t* msg)
190
{
191
        return _MAV_RETURN_uint64_t(msg,  6);
192
}
193
 
194
/**
195
 * @brief Decode a ping message into a struct
196
 *
197
 * @param msg The message to decode
198
 * @param ping C-struct to decode the message contents into
199
 */
200
static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping)
201
{
202
#if MAVLINK_NEED_BYTE_SWAP
203
        ping->seq = mavlink_msg_ping_get_seq(msg);
204
        ping->target_system = mavlink_msg_ping_get_target_system(msg);
205
        ping->target_component = mavlink_msg_ping_get_target_component(msg);
206
        ping->time = mavlink_msg_ping_get_time(msg);
207
#else
208
        memcpy(ping, _MAV_PAYLOAD(msg), 14);
209
#endif
210
}