diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 3301005773..bde15a13c1 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -218,17 +218,13 @@ const AP_Param::Info Tracker::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/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index ebc8162cf3..6d130d3aa3 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -52,17 +52,13 @@ void Tracker::init_tracker() gcs[1].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0); gcs[1].set_snoop(mavlink_snoop_static); -#if MAVLINK_COMM_NUM_BUFFERS > 2 // setup serial port for telem2 and start snooping for vehicle data gcs[2].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 1); gcs[2].set_snoop(mavlink_snoop_static); -#endif -#if MAVLINK_COMM_NUM_BUFFERS > 3 // setup serial port for fourth telemetry port (not used by default) and start snooping for vehicle data gcs[3].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 2); gcs[3].set_snoop(mavlink_snoop_static); -#endif mavlink_system.sysid = g.sysid_this_mav;