GCS_MAVLink: added support for 3 UARTs

support 3 UARTs on non-AVR platforms
This commit is contained in:
Andrew Tridgell 2013-11-22 19:17:34 +11:00
parent 0b25ff0a16
commit ac24ff0b1e
2 changed files with 40 additions and 3 deletions

View File

@ -32,6 +32,9 @@ This provides some support code and variables for MAVLink enabled sketches
AP_HAL::BetterStream *mavlink_comm_0_port;
AP_HAL::BetterStream *mavlink_comm_1_port;
#if MAVLINK_COMM_NUM_BUFFERS > 2
AP_HAL::BetterStream *mavlink_comm_2_port;
#endif
mavlink_system_t mavlink_system = {7,1,0,0};
@ -73,6 +76,11 @@ void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
case MAVLINK_COMM_1:
mavlink_comm_1_port->write(buf, len);
break;
#if MAVLINK_COMM_NUM_BUFFERS > 2
case MAVLINK_COMM_2:
mavlink_comm_2_port->write(buf, len);
break;
#endif
default:
break;
}

View File

@ -23,6 +23,11 @@
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
#include <util/crc16.h>
#define HAVE_CRC_ACCUMULATE
// only two telemetry ports on APM1/APM2
#define MAVLINK_COMM_NUM_BUFFERS 2
#else
// allow three telemetry ports on other boards
#define MAVLINK_COMM_NUM_BUFFERS 3
#endif
#include "include/mavlink/v1.0/ardupilotmega/version.h"
@ -32,15 +37,19 @@
// those for APM
#define MAVLINK_MAX_PAYLOAD_LEN 104
#define MAVLINK_COMM_NUM_BUFFERS 2
#include "include/mavlink/v1.0/mavlink_types.h"
/// MAVLink stream used for HIL interaction
/// MAVLink stream used for uartA
extern AP_HAL::BetterStream *mavlink_comm_0_port;
/// MAVLink stream used for ground control communication
/// MAVLink stream used for uartC
extern AP_HAL::BetterStream *mavlink_comm_1_port;
#if MAVLINK_COMM_NUM_BUFFERS > 2
/// MAVLink stream used for uartD
extern AP_HAL::BetterStream *mavlink_comm_2_port;
#endif
/// MAVLink system definition
extern mavlink_system_t mavlink_system;
@ -58,6 +67,11 @@ static inline void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
case MAVLINK_COMM_1:
mavlink_comm_1_port->write(ch);
break;
#if MAVLINK_COMM_NUM_BUFFERS > 2
case MAVLINK_COMM_2:
mavlink_comm_2_port->write(ch);
break;
#endif
default:
break;
}
@ -81,6 +95,11 @@ static inline uint8_t comm_receive_ch(mavlink_channel_t chan)
case MAVLINK_COMM_1:
data = mavlink_comm_1_port->read();
break;
#if MAVLINK_COMM_NUM_BUFFERS > 2
case MAVLINK_COMM_2:
data = mavlink_comm_2_port->read();
break;
#endif
default:
break;
}
@ -101,6 +120,11 @@ static inline uint16_t comm_get_available(mavlink_channel_t chan)
case MAVLINK_COMM_1:
bytes = mavlink_comm_1_port->available();
break;
#if MAVLINK_COMM_NUM_BUFFERS > 2
case MAVLINK_COMM_2:
bytes = mavlink_comm_2_port->available();
break;
#endif
default:
break;
}
@ -125,6 +149,11 @@ static inline uint16_t comm_get_txspace(mavlink_channel_t chan)
case MAVLINK_COMM_1:
ret = mavlink_comm_1_port->txspace();
break;
#if MAVLINK_COMM_NUM_BUFFERS > 2
case MAVLINK_COMM_2:
ret = mavlink_comm_2_port->txspace();
break;
#endif
default:
break;
}