diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 409e935e47..9487661b8b 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1120,17 +1120,13 @@ const AP_Param::Info Plane::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: INS_ // @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 5749f95318..742aa472e2 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -145,15 +145,11 @@ void Plane::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 #if FRSKY_TELEM_ENABLED == ENABLED