APM: allow serial buffer size to be configured

very useful for packet forwarding setups
This commit is contained in:
Andrew Tridgell 2012-08-31 17:40:35 +10:00
parent 2e7939cbf4
commit 88f4a3bc4a
3 changed files with 8 additions and 4 deletions

View File

@ -44,10 +44,10 @@ etags:
cd .. && etags -f ArduPlane/TAGS --langmap=C++:.pde.cpp.h $$(git ls-files ArduPlane libraries)
obc:
make -f Makefile EXTRAFLAGS="-DCONFIG_APM_HARDWARE=APM_HARDWARE_APM2 -DOBC_FAILSAFE=ENABLED -DTELEMETRY_UART2=ENABLED"
make -f Makefile EXTRAFLAGS="-DCONFIG_APM_HARDWARE=APM_HARDWARE_APM2 -DOBC_FAILSAFE=ENABLED -DTELEMETRY_UART2=ENABLED -DSERIAL_BUFSIZE=512"
obc-sitl:
make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DOBC_FAILSAFE=ENABLED"
make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DOBC_FAILSAFE=ENABLED -DSERIAL_BUFSIZE=512"
sitl-newcontrollers:
make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DAPM_CONTROL=ENABLED"

View File

@ -849,3 +849,7 @@
#ifndef APM_CONTROL
# define APM_CONTROL DISABLED
#endif
#ifndef SERIAL_BUFSIZE
# define SERIAL_BUFSIZE 256
#endif

View File

@ -81,7 +81,7 @@ static void init_ardupilot()
// The console port buffers are defined to be sufficiently large to support
// the MAVLink protocol efficiently
//
Serial.begin(SERIAL0_BAUD, 128, 256);
Serial.begin(SERIAL0_BAUD, 128, SERIAL_BUFSIZE);
// GPS serial port.
//
@ -137,7 +137,7 @@ static void init_ardupilot()
}
#else
// we have a 2nd serial port for telemetry
Serial3.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 256);
Serial3.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, SERIAL_BUFSIZE);
gcs3.init(&Serial3);
#endif