mirror of https://github.com/ArduPilot/ardupilot
desktop: flush all serial writes
This commit is contained in:
parent
4109374959
commit
dfef42ff48
|
@ -33,6 +33,7 @@
|
||||||
#include "FastSerial.h"
|
#include "FastSerial.h"
|
||||||
#include "WProgram.h"
|
#include "WProgram.h"
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
|
#include <pty.h>
|
||||||
|
|
||||||
#if defined(UDR3)
|
#if defined(UDR3)
|
||||||
# define FS_MAX_PORTS 4
|
# define FS_MAX_PORTS 4
|
||||||
|
@ -68,10 +69,12 @@ FastSerial::FastSerial(const uint8_t portNumber, volatile uint8_t *ubrrh, volati
|
||||||
|
|
||||||
void FastSerial::begin(long baud)
|
void FastSerial::begin(long baud)
|
||||||
{
|
{
|
||||||
|
printf("Starting serial port\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
|
void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
|
||||||
{
|
{
|
||||||
|
begin(baud);
|
||||||
}
|
}
|
||||||
|
|
||||||
void FastSerial::end()
|
void FastSerial::end()
|
||||||
|
@ -107,6 +110,7 @@ void FastSerial::flush(void)
|
||||||
void FastSerial::write(uint8_t c)
|
void FastSerial::write(uint8_t c)
|
||||||
{
|
{
|
||||||
fwrite(&c, 1, 1, stdout);
|
fwrite(&c, 1, 1, stdout);
|
||||||
|
fflush(stdout);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Buffer management ///////////////////////////////////////////////////////////
|
// Buffer management ///////////////////////////////////////////////////////////
|
||||||
|
|
Loading…
Reference in New Issue