Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- |
2 | |||
3 | /// @file GCS_MAVLink.h |
||
4 | /// @brief One size fits all header for MAVLink integration. |
||
5 | |||
6 | #ifndef GCS_MAVLink_h |
||
7 | #define GCS_MAVLink_h |
||
8 | |||
9 | #include <BetterStream.h> |
||
10 | |||
11 | // we have separate helpers disabled to make it possible |
||
12 | // to select MAVLink 1.0 in the arduino GUI build |
||
13 | //#define MAVLINK_SEPARATE_HELPERS |
||
14 | |||
15 | #ifdef MAVLINK10 |
||
16 | # include "include/mavlink/v1.0/ardupilotmega/version.h" |
||
17 | #else |
||
18 | # include "include/mavlink/v0.9/ardupilotmega/version.h" |
||
19 | #endif |
||
20 | |||
21 | // this allows us to make mavlink_message_t much smaller |
||
22 | #define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE |
||
23 | |||
24 | #define MAVLINK_COMM_NUM_BUFFERS 2 |
||
25 | #ifdef MAVLINK10 |
||
26 | # include "include/mavlink/v1.0/mavlink_types.h" |
||
27 | #else |
||
28 | # include "include/mavlink/v0.9/mavlink_types.h" |
||
29 | #endif |
||
30 | |||
31 | /// MAVLink stream used for HIL interaction |
||
32 | extern BetterStream *mavlink_comm_0_port; |
||
33 | |||
34 | /// MAVLink stream used for ground control communication |
||
35 | extern BetterStream *mavlink_comm_1_port; |
||
36 | |||
37 | /// MAVLink system definition |
||
38 | extern mavlink_system_t mavlink_system; |
||
39 | |||
40 | /// Send a byte to the nominated MAVLink channel |
||
41 | /// |
||
42 | /// @param chan Channel to send to |
||
43 | /// @param ch Byte to send |
||
44 | /// |
||
45 | static inline void comm_send_ch(mavlink_channel_t chan, uint8_t ch) |
||
46 | { |
||
47 | switch(chan) { |
||
48 | case MAVLINK_COMM_0: |
||
49 | mavlink_comm_0_port->write(ch); |
||
50 | break; |
||
51 | case MAVLINK_COMM_1: |
||
52 | mavlink_comm_1_port->write(ch); |
||
53 | break; |
||
54 | default: |
||
55 | break; |
||
56 | } |
||
57 | } |
||
58 | |||
59 | /// Read a byte from the nominated MAVLink channel |
||
60 | /// |
||
61 | /// @param chan Channel to receive on |
||
62 | /// @returns Byte read |
||
63 | /// |
||
64 | static inline uint8_t comm_receive_ch(mavlink_channel_t chan) |
||
65 | { |
||
66 | uint8_t data = 0; |
||
67 | |||
68 | switch(chan) { |
||
69 | case MAVLINK_COMM_0: |
||
70 | data = mavlink_comm_0_port->read(); |
||
71 | break; |
||
72 | case MAVLINK_COMM_1: |
||
73 | data = mavlink_comm_1_port->read(); |
||
74 | break; |
||
75 | default: |
||
76 | break; |
||
77 | } |
||
78 | return data; |
||
79 | } |
||
80 | |||
81 | /// Check for available data on the nominated MAVLink channel |
||
82 | /// |
||
83 | /// @param chan Channel to check |
||
84 | /// @returns Number of bytes available |
||
85 | static inline uint16_t comm_get_available(mavlink_channel_t chan) |
||
86 | { |
||
87 | uint16_t bytes = 0; |
||
88 | switch(chan) { |
||
89 | case MAVLINK_COMM_0: |
||
90 | bytes = mavlink_comm_0_port->available(); |
||
91 | break; |
||
92 | case MAVLINK_COMM_1: |
||
93 | bytes = mavlink_comm_1_port->available(); |
||
94 | break; |
||
95 | default: |
||
96 | break; |
||
97 | } |
||
98 | return bytes; |
||
99 | } |
||
100 | |||
101 | |||
102 | /// Check for available transmit space on the nominated MAVLink channel |
||
103 | /// |
||
104 | /// @param chan Channel to check |
||
105 | /// @returns Number of bytes available, -1 for error |
||
106 | static inline int comm_get_txspace(mavlink_channel_t chan) |
||
107 | { |
||
108 | switch(chan) { |
||
109 | case MAVLINK_COMM_0: |
||
110 | return mavlink_comm_0_port->txspace(); |
||
111 | break; |
||
112 | case MAVLINK_COMM_1: |
||
113 | return mavlink_comm_1_port->txspace(); |
||
114 | break; |
||
115 | default: |
||
116 | break; |
||
117 | } |
||
118 | return -1; |
||
119 | } |
||
120 | |||
121 | #define MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||
122 | #ifdef MAVLINK10 |
||
123 | # include "include/mavlink/v1.0/ardupilotmega/mavlink.h" |
||
124 | #else |
||
125 | # include "include/mavlink/v0.9/ardupilotmega/mavlink.h" |
||
126 | #endif |
||
127 | |||
128 | uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid); |
||
129 | |||
130 | #endif // GCS_MAVLink_h |