1 // MESSAGE PING PACKING
3 #define MAVLINK_MSG_ID_PING 4
5 typedef struct __mavlink_ping_t
{
6 uint64_t time_usec
; ///< Unix timestamp in microseconds
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
12 #define MAVLINK_MSG_ID_PING_LEN 14
13 #define MAVLINK_MSG_ID_4_LEN 14
16 #define MAVLINK_MESSAGE_INFO_PING \
21 { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \
22 { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \
23 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \
24 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \
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
35 * @param time_usec Unix timestamp in microseconds
36 * @param seq PING sequence
37 * @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
38 * @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
39 * @return length of the message in bytes (excluding serial stream start sign)
41 static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
,
42 uint64_t time_usec
, uint32_t seq
, uint8_t target_system
, uint8_t target_component
)
44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
46 _mav_put_uint64_t(buf
, 0, time_usec
);
47 _mav_put_uint32_t(buf
, 8, seq
);
48 _mav_put_uint8_t(buf
, 12, target_system
);
49 _mav_put_uint8_t(buf
, 13, target_component
);
51 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 14);
53 mavlink_ping_t packet
;
54 packet
.time_usec
= time_usec
;
56 packet
.target_system
= target_system
;
57 packet
.target_component
= target_component
;
59 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 14);
62 msg
->msgid
= MAVLINK_MSG_ID_PING
;
63 return mavlink_finalize_message(msg
, system_id
, component_id
, 14, 237);
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 time_usec Unix timestamp in microseconds
73 * @param seq PING sequence
74 * @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
75 * @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
76 * @return length of the message in bytes (excluding serial stream start sign)
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 uint64_t time_usec
, uint32_t seq
, uint8_t target_system
, uint8_t target_component
)
82 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
84 _mav_put_uint64_t(buf
, 0, time_usec
);
85 _mav_put_uint32_t(buf
, 8, seq
);
86 _mav_put_uint8_t(buf
, 12, target_system
);
87 _mav_put_uint8_t(buf
, 13, target_component
);
89 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 14);
91 mavlink_ping_t packet
;
92 packet
.time_usec
= time_usec
;
94 packet
.target_system
= target_system
;
95 packet
.target_component
= target_component
;
97 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 14);
100 msg
->msgid
= MAVLINK_MSG_ID_PING
;
101 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, 14, 237);
105 * @brief Encode a ping struct into a message
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
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
)
114 return mavlink_msg_ping_pack(system_id
, component_id
, msg
, ping
->time_usec
, ping
->seq
, ping
->target_system
, ping
->target_component
);
118 * @brief Send a ping message
119 * @param chan MAVLink channel to send the message
121 * @param time_usec Unix timestamp in microseconds
122 * @param seq PING sequence
123 * @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
124 * @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
126 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
128 static inline void mavlink_msg_ping_send(mavlink_channel_t chan
, uint64_t time_usec
, uint32_t seq
, uint8_t target_system
, uint8_t target_component
)
130 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
132 _mav_put_uint64_t(buf
, 0, time_usec
);
133 _mav_put_uint32_t(buf
, 8, seq
);
134 _mav_put_uint8_t(buf
, 12, target_system
);
135 _mav_put_uint8_t(buf
, 13, target_component
);
137 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PING
, buf
, 14, 237);
139 mavlink_ping_t packet
;
140 packet
.time_usec
= time_usec
;
142 packet
.target_system
= target_system
;
143 packet
.target_component
= target_component
;
145 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PING
, (const char *)&packet
, 14, 237);
149 #endif // ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
151 // MESSAGE PING UNPACKING
155 * @brief Get field time_usec from ping message
157 * @return Unix timestamp in microseconds
159 static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t
*msg
)
161 return _MAV_RETURN_uint64_t(msg
, 0);
165 * @brief Get field seq from ping message
167 * @return PING sequence
169 static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t
*msg
)
171 return _MAV_RETURN_uint32_t(msg
, 8);
175 * @brief Get field target_system from ping message
177 * @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
179 static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t
*msg
)
181 return _MAV_RETURN_uint8_t(msg
, 12);
185 * @brief Get field target_component from ping message
187 * @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
189 static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t
*msg
)
191 return _MAV_RETURN_uint8_t(msg
, 13);
195 * @brief Decode a ping message into a struct
197 * @param msg The message to decode
198 * @param ping C-struct to decode the message contents into
200 static inline void mavlink_msg_ping_decode(const mavlink_message_t
*msg
, mavlink_ping_t
*ping
)
202 #if MAVLINK_NEED_BYTE_SWAP
203 ping
->time_usec
= mavlink_msg_ping_get_time_usec(msg
);
204 ping
->seq
= mavlink_msg_ping_get_seq(msg
);
205 ping
->target_system
= mavlink_msg_ping_get_target_system(msg
);
206 ping
->target_component
= mavlink_msg_ping_get_target_component(msg
);
208 memcpy(ping
, _MAV_PAYLOAD(msg
), 14);