diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 1debcdef96bef3d101103734e5abc47ac2500c60..273384606d939df8312d85a2954c5281a3f1cc4a 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -76,25 +76,12 @@ static void init_ardupilot() // Console serial port // // The console port buffers are defined to be sufficiently large to support - // the console's use as a logging device, optionally as the GPS port when - // GPS_PROTOCOL_IMU is selected, and as the telemetry port. - // - // XXX This could be optimised to reduce the buffer sizes in the cases - // where they are not otherwise required. - // - Serial.begin(SERIAL0_BAUD, 128, 128); + // the MAVLink protocol efficiently + // + Serial.begin(SERIAL0_BAUD, 128, 256); // GPS serial port. // - // Not used if the IMU/X-Plane GPS is in use. - // - // XXX currently the EM406 (SiRF receiver) is nominally configured - // at 57600, however it's not been supported to date. We should - // probably standardise on 38400. - // - // XXX the 128 byte receive buffer may be too small for NMEA, depending - // on the message set configured. - // #if GPS_PROTOCOL != GPS_PROTOCOL_IMU Serial1.begin(38400, 128, 16); #endif @@ -169,11 +156,11 @@ static void init_ardupilot() if (!usb_connected) { // we are not connected via USB, re-init UART0 with right // baud rate - Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128); + Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD)); } #else // we have a 2nd serial port for telemetry - Serial3.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128); + Serial3.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 256); gcs3.init(&Serial3); #endif @@ -620,9 +607,9 @@ static void check_usb_mux(void) // the user has switched to/from the telemetry port usb_connected = usb_check; if (usb_connected) { - Serial.begin(SERIAL0_BAUD, 128, 128); + Serial.begin(SERIAL0_BAUD); } else { - Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128); + Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD)); } } #endif diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index 72584598fa8edad71e59fae4dfc8bef4a281ee4a..cb34a528b093c6a14efaf42fdaee27e3da2a2ab7 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -79,23 +79,12 @@ static void init_ardupilot() // Console serial port // // The console port buffers are defined to be sufficiently large to support - // the console's use as a logging device, optionally as the GPS port when - // GPS_PROTOCOL_IMU is selected, and as the telemetry port. + // the MAVLink protocol efficiently // - // XXX This could be optimised to reduce the buffer sizes in the cases - // where they are not otherwise required. - // - Serial.begin(SERIAL0_BAUD, 128, 128); + Serial.begin(SERIAL0_BAUD, 128, 256); // GPS serial port. // - // XXX currently the EM406 (SiRF receiver) is nominally configured - // at 57600, however it's not been supported to date. We should - // probably standardise on 38400. - // - // XXX the 128 byte receive buffer may be too small for NMEA, depending - // on the message set configured. - // // standard gps running Serial1.begin(38400, 128, 16); @@ -145,11 +134,11 @@ static void init_ardupilot() if (!usb_connected) { // we are not connected via USB, re-init UART0 with right // baud rate - Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128); + Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD)); } #else // we have a 2nd serial port for telemetry - Serial3.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128); + Serial3.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 256); gcs3.init(&Serial3); #endif @@ -556,9 +545,9 @@ static void check_usb_mux(void) // the user has switched to/from the telemetry port usb_connected = usb_check; if (usb_connected) { - Serial.begin(SERIAL0_BAUD, 128, 128); + Serial.begin(SERIAL0_BAUD); } else { - Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128); + Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD)); } } #endif