APM:Libraries
|
#include <AP_Param/AP_Param.h>
#include "include/mavlink/v2.0/ardupilotmega/version.h"
#include "include/mavlink/v2.0/mavlink_types.h"
#include "include/mavlink/v2.0/ardupilotmega/mavlink.h"
Go to the source code of this file.
Macros | |
#define | MAVLINK_SEPARATE_HELPERS |
#define | MAVLINK_NO_CONVERSION_HELPERS |
#define | MAVLINK_SEND_UART_BYTES(chan, buf, len) comm_send_buffer(chan, buf, len) |
#define | MAVLINK_COMM_NUM_BUFFERS 6 |
#define | MAVLINK_MAX_PAYLOAD_LEN 255 |
#define | MAVLINK_USE_CONVENIENCE_FUNCTIONS |
Functions | |
static bool | valid_channel (mavlink_channel_t chan) |
void | comm_send_buffer (mavlink_channel_t chan, const uint8_t *buf, uint8_t len) |
uint16_t | comm_get_available (mavlink_channel_t chan) |
uint16_t | comm_get_txspace (mavlink_channel_t chan) |
uint8_t | mav_var_type (enum ap_var_type t) |
Variables | |
AP_HAL::UARTDriver * | mavlink_comm_port [MAVLINK_COMM_NUM_BUFFERS] |
MAVLink stream used for uartA. More... | |
bool | gcs_alternative_active [MAVLINK_COMM_NUM_BUFFERS] |
mavlink_system_t | mavlink_system |
MAVLink system definition. More... | |
#define MAVLINK_COMM_NUM_BUFFERS 6 |
Definition at line 17 of file GCS_MAVLink.h.
Referenced by valid_channel().
#define MAVLINK_MAX_PAYLOAD_LEN 255 |
Definition at line 32 of file GCS_MAVLink.h.
#define MAVLINK_NO_CONVERSION_HELPERS |
Definition at line 10 of file GCS_MAVLink.h.
#define MAVLINK_SEND_UART_BYTES | ( | chan, | |
buf, | |||
len | |||
) | comm_send_buffer(chan, buf, len) |
Definition at line 12 of file GCS_MAVLink.h.
#define MAVLINK_SEPARATE_HELPERS |
Definition at line 9 of file GCS_MAVLink.h.
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS |
Definition at line 69 of file GCS_MAVLink.h.
uint16_t comm_get_available | ( | mavlink_channel_t | chan | ) |
Check for available data on the nominated MAVLink channel
chan | Channel to check |
Definition at line 108 of file GCS_MAVLink.cpp.
Referenced by valid_channel().
uint16_t comm_get_txspace | ( | mavlink_channel_t | chan | ) |
Check for available transmit space on the nominated MAVLink channel
chan | Channel to check |
Definition at line 89 of file GCS_MAVLink.cpp.
Referenced by valid_channel().
void comm_send_buffer | ( | mavlink_channel_t | chan, |
const uint8_t * | buf, | ||
uint8_t | len | ||
) |
Definition at line 126 of file GCS_MAVLink.cpp.
Referenced by valid_channel().
uint8_t mav_var_type | ( | enum ap_var_type | t | ) |
Definition at line 69 of file GCS_MAVLink.cpp.
|
inlinestatic |
Sanity check MAVLink channel
chan | Channel to send to |
Definition at line 46 of file GCS_MAVLink.h.
Referenced by comm_get_available(), comm_get_txspace(), comm_send_buffer(), GCS_MAVLINK::init(), GCS_MAVLINK::lock_channel(), and SITL::Vicon::Vicon().
bool gcs_alternative_active[MAVLINK_COMM_NUM_BUFFERS] |
Definition at line 40 of file GCS_MAVLink.cpp.
Referenced by comm_send_buffer(), and GCS_MAVLINK::update().
AP_HAL::UARTDriver* mavlink_comm_port[MAVLINK_COMM_NUM_BUFFERS] |
MAVLink stream used for uartA.
Definition at line 39 of file GCS_MAVLink.cpp.
Referenced by GCS_MAVLINK::init(), and GCS_MAVLINK::update().
mavlink_system_t mavlink_system |
MAVLink system definition.
Definition at line 42 of file GCS_MAVLink.cpp.