Browse Source

APM: allow serial buffer size to be configured

very useful for packet forwarding setups
master
Andrew Tridgell 13 years ago
parent
commit
a446a7a9ed
  1. 4
      ArduPlane/Makefile
  2. 4
      ArduPlane/config.h
  3. 4
      ArduPlane/system.pde

4
ArduPlane/Makefile

@ -44,10 +44,10 @@ etags: @@ -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"

4
ArduPlane/config.h

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

4
ArduPlane/system.pde

@ -81,7 +81,7 @@ static void init_ardupilot() @@ -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() @@ -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

Loading…
Cancel
Save