diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 844e781040..06bff18226 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -44,7 +44,7 @@ void Rover::init_ardupilot() serial_manager.init(); // setup first port early to allow BoardConfig to report errors - gcs().chan(0).setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0); + gcs().chan(0).setup_uart(AP_SerialManager::SerialProtocol_MAVLink, 0); // Register mavlink_delay_cb, which will run anytime you have // more than 5ms remaining in your call to hal.scheduler->delay @@ -81,7 +81,7 @@ void Rover::init_ardupilot() barometer.init(); // setup telem slots with serial ports - gcs().setup_uarts(serial_manager); + gcs().setup_uarts(); #if OSD_ENABLED == ENABLED osd.init();