mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: increase max mavlink connections when networking enabled
This commit is contained in:
parent
f471732aad
commit
f345d94e91
|
@ -3,6 +3,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL_Boards.h>
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
|
#include <AP_Networking/AP_Networking_Config.h>
|
||||||
|
|
||||||
// we have separate helpers disabled to make it possible
|
// we have separate helpers disabled to make it possible
|
||||||
// to select MAVLink 1.0 in the arduino GUI build
|
// to select MAVLink 1.0 in the arduino GUI build
|
||||||
|
@ -14,8 +15,13 @@
|
||||||
#define MAVLINK_START_UART_SEND(chan, size) comm_send_lock(chan, size)
|
#define MAVLINK_START_UART_SEND(chan, size) comm_send_lock(chan, size)
|
||||||
#define MAVLINK_END_UART_SEND(chan, size) comm_send_unlock(chan)
|
#define MAVLINK_END_UART_SEND(chan, size) comm_send_unlock(chan)
|
||||||
|
|
||||||
|
#if AP_NETWORKING_ENABLED
|
||||||
|
// allow 7 telemetry ports with networking
|
||||||
|
#define MAVLINK_COMM_NUM_BUFFERS 7
|
||||||
|
#else
|
||||||
// allow five telemetry ports
|
// allow five telemetry ports
|
||||||
#define MAVLINK_COMM_NUM_BUFFERS 5
|
#define MAVLINK_COMM_NUM_BUFFERS 5
|
||||||
|
#endif
|
||||||
|
|
||||||
#define MAVLINK_GET_CHANNEL_BUFFER 1
|
#define MAVLINK_GET_CHANNEL_BUFFER 1
|
||||||
#define MAVLINK_GET_CHANNEL_STATUS 1
|
#define MAVLINK_GET_CHANNEL_STATUS 1
|
||||||
|
|
Loading…
Reference in New Issue