APMrover2: remove check for MAVLINK_COMM_NUM_BUFFERS

This commit is contained in:
Lucas De Marchi 2015-11-03 11:59:04 -02:00 committed by Andrew Tridgell
parent 2b37906f0d
commit 91dbfce5f9
2 changed files with 0 additions and 8 deletions

View File

@ -450,17 +450,13 @@ const AP_Param::Info Rover::var_info[] = {
// @Path: GCS_Mavlink.cpp
GOBJECTN(gcs[1], gcs1, "SR1_", GCS_MAVLINK),
#if MAVLINK_COMM_NUM_BUFFERS > 2
// @Group: SR2_
// @Path: GCS_Mavlink.cpp
GOBJECTN(gcs[2], gcs2, "SR2_", GCS_MAVLINK),
#endif
#if MAVLINK_COMM_NUM_BUFFERS > 3
// @Group: SR3_
// @Path: GCS_Mavlink.cpp
GOBJECTN(gcs[3], gcs3, "SR3_", GCS_MAVLINK),
#endif
// @Group: SERIAL
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp

View File

@ -118,15 +118,11 @@ void Rover::init_ardupilot()
// setup serial port for telem1
gcs[1].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
#if MAVLINK_COMM_NUM_BUFFERS > 2
// setup serial port for telem2
gcs[2].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 1);
#endif
#if MAVLINK_COMM_NUM_BUFFERS > 3
// setup serial port for fourth telemetry port (not used by default)
gcs[3].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 2);
#endif
// setup frsky telemetry
#if FRSKY_TELEM_ENABLED == ENABLED