Robot Control Library
mavlink_udp.h
Go to the documentation of this file.
1/**
2 * <mavlink_udp.h>
3 *
4 * @brief Communicate with mavlink over UDP networking.
5 *
6 * Uses common mavlink v2 packets generated from official mavlink source
7 * (https://github.com/mavlink/mavlink). Also see mavlink_udp_helpers.h for
8 * additional helper functions for most commonly used packets.
9 *
10 * The base mavlink headers are also included with this file to expose all
11 * standard mavlink definitions, macros, and functions.
12 *
13 * @author James Strawson & Henry Gaudet
14 * @date 1/24/2018
15 *
16 * @addtogroup Mavlink_UDP
17 * @ingroup Mavlink
18 * @{
19 */
20
21#ifndef RC_MAVLINK_UDP_H
22#define RC_MAVLINK_UDP_H
23
24#ifdef __cplusplus
25extern "C" {
26#endif
27
28
29#include <stdint.h> // for specific integer types
30// these are directly from the mavlink source
31#include <rc/mavlink/common/mavlink.h>
32#include <rc/mavlink/mavlink_types.h>
34
35#define RC_MAV_DEFAULT_UDP_PORT 14551
36#define RC_MAV_DEFAULT_CONNECTION_TIMEOUT_US 2000000
37
38
39/**
40 * Connection state based on receipt of heartbeat packets. Retrieve the current
41 * state with rc_mav_get_connection_state
42 */
48
49
50/**
51 * @brief Initialize a UDP port for sending and receiving.
52 *
53 * Initialize a UDP port for sending and receiving. Additionally starts a
54 * listening thread that handles incomming packets and makes them available with
55 * the remaining functions in this API.
56 *
57 * @param[in] system_id The system id of this device tagged in
58 * outgoing packets
59 * @param[in] dest_ip The destination ip, can be changed later
60 * with rc_mav_set_dest_ip
61 * @param[in] port Port to listen on and send to
62 * @param[in] connection_timeout_us microseconds since last received packet to
63 * consider connection lost, after which point rc_mav_connection_state will
64 * change to MAV_CONNECTION_LOST and the connection-lost callback will be called
65 * if set. Should be >=200000
66 *
67 * @return 0 on success, -1 on failure
68 */
69int rc_mav_init(uint8_t system_id, const char* dest_ip, uint16_t port, uint64_t connection_timeout_us);
70
71/**
72 * @brief Sets the destination ip address for sent packets.
73 *
74 * @param[in] dest_ip The destination ip
75 *
76 * @return 0 on success, -1 on failure
77 */
78int rc_mav_set_dest_ip(const char* dest_ip);
79
80/**
81 * @brief Sets the system identifier
82 *
83 * The system_id is included with every mavlink packet sent so that the receiver
84 * can identitfy what sent the current packet. We suggest every mavlink device
85 * in a network to have a unique id. The system_id is set during rc_mav_init but
86 * can be changed afterwards with this function.
87 *
88 * @param[in] system_id The system identifier
89 *
90 * @return 0 on success, -1 on failure
91 */
92int rc_mav_set_system_id(uint8_t system_id);
93
94
95/**
96 * @brief Closes UDP port and stops network port listening thread
97 *
98 * This is a blocking function call that returns after the network port
99 * listening thread has exited and the UDP port has closed. If the thread fails
100 * to exit before timeout a warning message is displayed and the function
101 * returns -1 to indicate there was an issue. This should be called before your
102 * program exits.
103 *
104 * @return 0 on success, -1 on failure
105 */
107
108
109/**
110 * @brief Sends any user-packed mavlink message
111 *
112 * To construct your own mavlink_message_t from the packet definitions in
113 * include/rc/mavlink/common/, follow this example snippet and substitute in the
114 * functions for packing the packet you wish to send. rc/mavlink_udp_helpers.h
115 * provides many helper functions to pack and send the most common mavlink
116 * packets so that you do not need to use this function always.
117 *
118 * @code{.c}
119 * mavlink_message_t msg;
120 * mavlink_msg_heartbeat_pack(system_id, MAV_COMP_ID_ALL, &msg, 0, 0, 0, 0, 0);
121 * rc_mav_send_msg(msg)){
122 * @endcode
123 *
124 * @param[in] msg The message to be sent
125 *
126 * @return 0 on success, -1 on failure
127 */
128int rc_mav_send_msg(mavlink_message_t msg);
129
130
131/**
132 * @brief Inidcates if a particular message type has been received by not
133 * read by the user yet.
134 *
135 * @param[in] msg_id The message identifier to check
136 *
137 * @return 1 if new message is available, otherwise 0
138 */
139int rc_mav_is_new_msg(int msg_id);
140
141
142/**
143 * @brief Fetches the last received message of type msg_id
144 *
145 * @param[in] msg_id The message identifier to fetch
146 * @param[out] msg place to write to message struct to
147 *
148 * @return returns 0 on success. Returns -1 on failure, for example if no
149 * message of type msg_id has been received.
150 */
151int rc_mav_get_msg(int msg_id, mavlink_message_t* msg);
152
153
154/**
155 * @brief assign a callback function to be called when a particular message
156 * is received.
157 *
158 * If a general callback function has been set with rc_mav_set_callback_all,
159 * this message-specific callback will be called after the general callback.
160 *
161 * @param[in] msg_id The message identifier
162 * @param[in] func The callabck function pointer
163 *
164 * @return 0 on success, -1 on failure
165 */
166int rc_mav_set_callback(int msg_id, void (*func)(void));
167
168
169/**
170 * @brief Sets a callback function which is called when any packet arrives.
171 *
172 * If a message-specific callback function has been set with
173 * rc_mav_set_callback(), this general callback will be called before the
174 * message-specific callback.
175 *
176 * @param[in] func The callback function
177 *
178 * @return 0 on success, -1 on failure
179 */
180int rc_mav_set_callback_all(void (*func)(void));
181
182
183/**
184 * @brief Sets a callback function to be called when connection_timeout has
185 * been reached without receiving any messages.
186 *
187 * connection_timeout is set with rc_mav_init
188 *
189 * @param[in] func The callback function
190 *
191 * @return 0 on success, -1 on failure
192 */
194
195
196/**
197 * @brief Gets the connection state as determined by received heartbeat
198 * packets.
199 *
200 * See rc_mav_connection_state_t
201 *
202 * @return Returns current connection state.
203 */
205
206
207/**
208 * @brief Fetches the system ID of the sender of the last received message.
209 * of type msg_id
210 *
211 * @param[in] msg_id The message identifier of the packet type to check
212 *
213 * @return Returns the system ID on success. Returns -1 on failure, for
214 * example if no message of type msg_id has been received of type msg_id.
215 */
217
218
219/**
220 * @brief Fetches the system ID of the sender of the last received message.
221 *
222 * @return Returns the system ID on success. Returns -1 on failure, for
223 * example if no message has been received.
224 */
226
227/**
228 * @brief Fetches the number of nanoseconds since the last message of type
229 * msg_id has been received.
230 *
231 * @param[in] msg_id The message identifier of the packet type to check
232 *
233 * @return Returns the number of nanoseconds since the last message of type
234 * msg_id has been received. Returns -1 on failure, for example if no message
235 * has been received of type msg_id.
236 */
237int64_t rc_mav_ns_since_last_msg(int msg_id);
238
239/**
240 * @brief Fetches the number of nanoseconds since any packet has been
241 * received.
242 *
243 * @return Returns the number of nanoseconds since any message has been
244 * received. Returns -1 on failure, for example if no message has been received.
245 */
247
248/**
249 * @brief Returns the msg_id of the last received packet.
250 *
251 * @return Returns the msg_id of the last received packet. Returns -1 on
252 * failure, for example if no message has been received.
253 */
255
256/**
257 * @brief Prints to stdout a human-readable name for a message type.
258 *
259 * @param[in] msg_id The message identifier to print
260 *
261 * @return Returns 0 on success, or -1 on failure such as if msg_id is
262 * invalid.
263 */
264int rc_mav_print_msg_name(int msg_id);
265
266
267
268#ifdef __cplusplus
269}
270#endif
271
272#endif // RC_MAVLINK_UDP_H
273
274///@} end group Mavlink
275
276