Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE HEARTBEAT PACKING
2
 
3
#define MAVLINK_MSG_ID_HEARTBEAT 0
4
 
5
typedef struct __mavlink_heartbeat_t
6
{
7
 uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
8
 uint8_t autopilot; ///< Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
9
 uint8_t mavlink_version; ///< MAVLink version
10
} mavlink_heartbeat_t;
11
 
12
#define MAVLINK_MSG_ID_HEARTBEAT_LEN 3
13
#define MAVLINK_MSG_ID_0_LEN 3
14
 
15
 
16
 
17
#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
18
        "HEARTBEAT", \
19
        3, \
20
        {  { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_heartbeat_t, type) }, \
21
         { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_heartbeat_t, autopilot) }, \
22
         { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
23
         } \
24
}
25
 
26
 
27
/**
28
 * @brief Pack a heartbeat 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 type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
34
 * @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
35
 * @return length of the message in bytes (excluding serial stream start sign)
36
 */
37
static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
38
                                                       uint8_t type, uint8_t autopilot)
39
{
40
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
41
        char buf[3];
42
        _mav_put_uint8_t(buf, 0, type);
43
        _mav_put_uint8_t(buf, 1, autopilot);
44
        _mav_put_uint8_t(buf, 2, 2);
45
 
46
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
47
#else
48
        mavlink_heartbeat_t packet;
49
        packet.type = type;
50
        packet.autopilot = autopilot;
51
        packet.mavlink_version = 2;
52
 
53
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
54
#endif
55
 
56
        msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
57
        return mavlink_finalize_message(msg, system_id, component_id, 3);
58
}
59
 
60
/**
61
 * @brief Pack a heartbeat message on a channel
62
 * @param system_id ID of this system
63
 * @param component_id ID of this component (e.g. 200 for IMU)
64
 * @param chan The MAVLink channel this message was sent over
65
 * @param msg The MAVLink message to compress the data into
66
 * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
67
 * @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
68
 * @return length of the message in bytes (excluding serial stream start sign)
69
 */
70
static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
71
                                                           mavlink_message_t* msg,
72
                                                           uint8_t type,uint8_t autopilot)
73
{
74
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
75
        char buf[3];
76
        _mav_put_uint8_t(buf, 0, type);
77
        _mav_put_uint8_t(buf, 1, autopilot);
78
        _mav_put_uint8_t(buf, 2, 2);
79
 
80
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
81
#else
82
        mavlink_heartbeat_t packet;
83
        packet.type = type;
84
        packet.autopilot = autopilot;
85
        packet.mavlink_version = 2;
86
 
87
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
88
#endif
89
 
90
        msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
91
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3);
92
}
93
 
94
/**
95
 * @brief Encode a heartbeat struct into a message
96
 *
97
 * @param system_id ID of this system
98
 * @param component_id ID of this component (e.g. 200 for IMU)
99
 * @param msg The MAVLink message to compress the data into
100
 * @param heartbeat C-struct to read the message contents from
101
 */
102
static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
103
{
104
        return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot);
105
}
106
 
107
/**
108
 * @brief Send a heartbeat message
109
 * @param chan MAVLink channel to send the message
110
 *
111
 * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
112
 * @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
113
 */
114
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
115
 
116
static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot)
117
{
118
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
119
        char buf[3];
120
        _mav_put_uint8_t(buf, 0, type);
121
        _mav_put_uint8_t(buf, 1, autopilot);
122
        _mav_put_uint8_t(buf, 2, 2);
123
 
124
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, 3);
125
#else
126
        mavlink_heartbeat_t packet;
127
        packet.type = type;
128
        packet.autopilot = autopilot;
129
        packet.mavlink_version = 2;
130
 
131
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, 3);
132
#endif
133
}
134
 
135
#endif
136
 
137
// MESSAGE HEARTBEAT UNPACKING
138
 
139
 
140
/**
141
 * @brief Get field type from heartbeat message
142
 *
143
 * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
144
 */
145
static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
146
{
147
        return _MAV_RETURN_uint8_t(msg,  0);
148
}
149
 
150
/**
151
 * @brief Get field autopilot from heartbeat message
152
 *
153
 * @return Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
154
 */
155
static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
156
{
157
        return _MAV_RETURN_uint8_t(msg,  1);
158
}
159
 
160
/**
161
 * @brief Get field mavlink_version from heartbeat message
162
 *
163
 * @return MAVLink version
164
 */
165
static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg)
166
{
167
        return _MAV_RETURN_uint8_t(msg,  2);
168
}
169
 
170
/**
171
 * @brief Decode a heartbeat message into a struct
172
 *
173
 * @param msg The message to decode
174
 * @param heartbeat C-struct to decode the message contents into
175
 */
176
static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat)
177
{
178
#if MAVLINK_NEED_BYTE_SWAP
179
        heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
180
        heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
181
        heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
182
#else
183
        memcpy(heartbeat, _MAV_PAYLOAD(msg), 3);
184
#endif
185
}