2010-11-25 00:04:30 -04:00
// MESSAGE PING PACKING
# define MAVLINK_MSG_ID_PING 3
2011-08-31 02:23:18 -03:00
typedef struct __mavlink_ping_t
2010-11-25 00:04:30 -04:00
{
2011-08-31 02:23:18 -03:00
uint32_t seq ; ///< PING sequence
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
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
uint64_t time ; ///< Unix timestamp in microseconds
2010-11-25 00:04:30 -04:00
} mavlink_ping_t ;
2011-08-31 02:23:18 -03:00
# define MAVLINK_MSG_ID_PING_LEN 14
# define MAVLINK_MSG_ID_3_LEN 14
# define MAVLINK_MESSAGE_INFO_PING { \
" PING " , \
4 , \
2011-09-04 05:50:24 -03:00
{ { " seq " , NULL , MAVLINK_TYPE_UINT32_T , 0 , 0 , offsetof ( mavlink_ping_t , seq ) } , \
{ " target_system " , NULL , MAVLINK_TYPE_UINT8_T , 0 , 4 , offsetof ( mavlink_ping_t , target_system ) } , \
{ " target_component " , NULL , MAVLINK_TYPE_UINT8_T , 0 , 5 , offsetof ( mavlink_ping_t , target_component ) } , \
{ " time " , NULL , MAVLINK_TYPE_UINT64_T , 0 , 6 , offsetof ( mavlink_ping_t , time ) } , \
2011-08-31 02:23:18 -03:00
} \
}
2010-11-25 00:04:30 -04:00
/**
2011-01-12 04:57:54 -04:00
* @ brief Pack a ping message
* @ param system_id ID of this system
* @ param component_id ID of this component ( e . g . 200 for IMU )
* @ param msg The MAVLink message to compress the data into
2010-11-25 00:04:30 -04:00
*
* @ param seq PING sequence
* @ 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
* @ 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
* @ param time Unix timestamp in microseconds
* @ return length of the message in bytes ( excluding serial stream start sign )
*/
2011-08-31 02:23:18 -03:00
static inline uint16_t mavlink_msg_ping_pack ( uint8_t system_id , uint8_t component_id , mavlink_message_t * msg ,
uint32_t seq , uint8_t target_system , uint8_t target_component , uint64_t time )
2010-11-25 00:04:30 -04:00
{
2011-08-31 02:23:18 -03:00
# if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf [ 14 ] ;
_mav_put_uint32_t ( buf , 0 , seq ) ;
_mav_put_uint8_t ( buf , 4 , target_system ) ;
_mav_put_uint8_t ( buf , 5 , target_component ) ;
_mav_put_uint64_t ( buf , 6 , time ) ;
memcpy ( _MAV_PAYLOAD ( msg ) , buf , 14 ) ;
# else
mavlink_ping_t packet ;
packet . seq = seq ;
packet . target_system = target_system ;
packet . target_component = target_component ;
packet . time = time ;
memcpy ( _MAV_PAYLOAD ( msg ) , & packet , 14 ) ;
# endif
2010-11-25 00:04:30 -04:00
2011-08-31 02:23:18 -03:00
msg - > msgid = MAVLINK_MSG_ID_PING ;
return mavlink_finalize_message ( msg , system_id , component_id , 14 ) ;
2010-11-25 00:04:30 -04:00
}
2011-01-12 04:57:54 -04:00
/**
2011-08-31 02:23:18 -03:00
* @ brief Pack a ping message on a channel
2011-01-12 04:57:54 -04:00
* @ param system_id ID of this system
* @ param component_id ID of this component ( e . g . 200 for IMU )
* @ param chan The MAVLink channel this message was sent over
* @ param msg The MAVLink message to compress the data into
* @ param seq PING sequence
* @ 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
* @ 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
* @ param time Unix timestamp in microseconds
* @ return length of the message in bytes ( excluding serial stream start sign )
*/
2011-08-31 02:23:18 -03:00
static inline uint16_t mavlink_msg_ping_pack_chan ( uint8_t system_id , uint8_t component_id , uint8_t chan ,
mavlink_message_t * msg ,
uint32_t seq , uint8_t target_system , uint8_t target_component , uint64_t time )
2010-12-04 20:49:04 -04:00
{
2011-08-31 02:23:18 -03:00
# if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf [ 14 ] ;
_mav_put_uint32_t ( buf , 0 , seq ) ;
_mav_put_uint8_t ( buf , 4 , target_system ) ;
_mav_put_uint8_t ( buf , 5 , target_component ) ;
_mav_put_uint64_t ( buf , 6 , time ) ;
memcpy ( _MAV_PAYLOAD ( msg ) , buf , 14 ) ;
# else
mavlink_ping_t packet ;
packet . seq = seq ;
packet . target_system = target_system ;
packet . target_component = target_component ;
packet . time = time ;
memcpy ( _MAV_PAYLOAD ( msg ) , & packet , 14 ) ;
# endif
2010-12-04 20:49:04 -04:00
2011-08-31 02:23:18 -03:00
msg - > msgid = MAVLINK_MSG_ID_PING ;
return mavlink_finalize_message_chan ( msg , system_id , component_id , chan , 14 ) ;
2010-12-04 20:49:04 -04:00
}
2011-01-12 04:57:54 -04:00
/**
* @ brief Encode a ping struct into a message
*
* @ param system_id ID of this system
* @ param component_id ID of this component ( e . g . 200 for IMU )
* @ param msg The MAVLink message to compress the data into
* @ param ping C - struct to read the message contents from
*/
2010-11-25 00:04:30 -04:00
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 )
{
return mavlink_msg_ping_pack ( system_id , component_id , msg , ping - > seq , ping - > target_system , ping - > target_component , ping - > time ) ;
}
2011-01-12 04:57:54 -04:00
/**
* @ brief Send a ping message
* @ param chan MAVLink channel to send the message
*
* @ param seq PING sequence
* @ 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
* @ 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
* @ param time Unix timestamp in microseconds
*/
2010-11-25 00:04:30 -04:00
# ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
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 )
{
2011-08-31 02:23:18 -03:00
# if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf [ 14 ] ;
_mav_put_uint32_t ( buf , 0 , seq ) ;
_mav_put_uint8_t ( buf , 4 , target_system ) ;
_mav_put_uint8_t ( buf , 5 , target_component ) ;
_mav_put_uint64_t ( buf , 6 , time ) ;
_mav_finalize_message_chan_send ( chan , MAVLINK_MSG_ID_PING , buf , 14 ) ;
# else
mavlink_ping_t packet ;
packet . seq = seq ;
packet . target_system = target_system ;
packet . target_component = target_component ;
packet . time = time ;
_mav_finalize_message_chan_send ( chan , MAVLINK_MSG_ID_PING , ( const char * ) & packet , 14 ) ;
# endif
2010-11-25 00:04:30 -04:00
}
# endif
2011-08-31 02:23:18 -03:00
2010-11-25 00:04:30 -04:00
// MESSAGE PING UNPACKING
2011-08-31 02:23:18 -03:00
2010-11-25 00:04:30 -04:00
/**
* @ brief Get field seq from ping message
*
* @ return PING sequence
*/
static inline uint32_t mavlink_msg_ping_get_seq ( const mavlink_message_t * msg )
{
2011-08-31 02:23:18 -03:00
return _MAV_RETURN_uint32_t ( msg , 0 ) ;
2010-11-25 00:04:30 -04:00
}
/**
* @ brief Get field target_system from ping message
*
* @ 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
*/
static inline uint8_t mavlink_msg_ping_get_target_system ( const mavlink_message_t * msg )
{
2011-08-31 02:23:18 -03:00
return _MAV_RETURN_uint8_t ( msg , 4 ) ;
2010-11-25 00:04:30 -04:00
}
/**
* @ brief Get field target_component from ping message
*
* @ 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
*/
static inline uint8_t mavlink_msg_ping_get_target_component ( const mavlink_message_t * msg )
{
2011-08-31 02:23:18 -03:00
return _MAV_RETURN_uint8_t ( msg , 5 ) ;
2010-11-25 00:04:30 -04:00
}
/**
* @ brief Get field time from ping message
*
* @ return Unix timestamp in microseconds
*/
static inline uint64_t mavlink_msg_ping_get_time ( const mavlink_message_t * msg )
{
2011-08-31 02:23:18 -03:00
return _MAV_RETURN_uint64_t ( msg , 6 ) ;
2010-11-25 00:04:30 -04:00
}
2011-01-12 04:57:54 -04:00
/**
* @ brief Decode a ping message into a struct
*
* @ param msg The message to decode
* @ param ping C - struct to decode the message contents into
*/
2010-11-25 00:04:30 -04:00
static inline void mavlink_msg_ping_decode ( const mavlink_message_t * msg , mavlink_ping_t * ping )
{
2011-08-31 02:23:18 -03:00
# if MAVLINK_NEED_BYTE_SWAP
2010-11-25 00:04:30 -04:00
ping - > seq = mavlink_msg_ping_get_seq ( msg ) ;
ping - > target_system = mavlink_msg_ping_get_target_system ( msg ) ;
ping - > target_component = mavlink_msg_ping_get_target_component ( msg ) ;
ping - > time = mavlink_msg_ping_get_time ( msg ) ;
2011-08-31 02:23:18 -03:00
# else
memcpy ( ping , _MAV_PAYLOAD ( msg ) , 14 ) ;
# endif
2010-11-25 00:04:30 -04:00
}