APM:Libraries
GCS_MAVLink.h
Go to the documentation of this file.
1 #pragma once
4 
5 #include <AP_Param/AP_Param.h>
6 
7 // we have separate helpers disabled to make it possible
8 // to select MAVLink 1.0 in the arduino GUI build
9 #define MAVLINK_SEPARATE_HELPERS
10 #define MAVLINK_NO_CONVERSION_HELPERS
11 
12 #define MAVLINK_SEND_UART_BYTES(chan, buf, len) comm_send_buffer(chan, buf, len)
13 
14 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
15 // allow extra mavlink channels in SITL for:
16 // Vicon
17 #define MAVLINK_COMM_NUM_BUFFERS 6
18 #else
19 // allow five telemetry ports
20 #define MAVLINK_COMM_NUM_BUFFERS 5
21 #endif
22 
23 /*
24  The MAVLink protocol code generator does its own alignment, so
25  alignment cast warnings can be ignored
26  */
27 #pragma GCC diagnostic push
28 #pragma GCC diagnostic ignored "-Wcast-align"
29 
30 #include "include/mavlink/v2.0/ardupilotmega/version.h"
31 
32 #define MAVLINK_MAX_PAYLOAD_LEN 255
33 
34 #include "include/mavlink/v2.0/mavlink_types.h"
35 
39 
41 extern mavlink_system_t mavlink_system;
42 
46 static inline bool valid_channel(mavlink_channel_t chan)
47 {
48 #pragma clang diagnostic push
49 #pragma clang diagnostic ignored "-Wtautological-constant-out-of-range-compare"
50  return chan < MAVLINK_COMM_NUM_BUFFERS;
51 #pragma clang diagnostic pop
52 }
53 
54 void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len);
55 
60 uint16_t comm_get_available(mavlink_channel_t chan);
61 
62 
67 uint16_t comm_get_txspace(mavlink_channel_t chan);
68 
69 #define MAVLINK_USE_CONVENIENCE_FUNCTIONS
70 #include "include/mavlink/v2.0/ardupilotmega/mavlink.h"
71 
72 // return a MAVLink variable type given a AP_Param type
73 uint8_t mav_var_type(enum ap_var_type t);
74 
75 #pragma GCC diagnostic pop
ap_var_type
Definition: AP_Param.h:124
A system for managing and storing variables that are of general interest to the system.
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8