Added buffersize member to BinComm.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@824 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
james.goppert 2010-11-11 02:42:43 +00:00
parent d8b3dd9aa1
commit afb134b915
2 changed files with 13 additions and 5 deletions

View File

@ -45,10 +45,11 @@
#define DEC_MESSAGE_TIMEOUT 1000
BinComm::BinComm(const BinComm::MessageHandler *handlerTable,
Stream *interface) :
uint16_t rxBufferSize, Stream *interface) :
_handlerTable(handlerTable),
_decodePhase(DEC_WAIT_P1),
_lastReceived(millis())
_lastReceived(millis()),
_rxBufferSize(rxBufferSize)
{
init(interface);
};
@ -98,10 +99,10 @@ BinComm::update(void)
// XXX we might want to further constrain this count
count = _interface->available();
if (count >= 128)
if (count >= _rxBufferSize)
{
char text[50];
strncpy(text,"buffer overflow",50);
strncpy(text,"<bincomm> buffer overflow",50);
send_msg_status_text(SEVERITY_LOW,text);
}

View File

@ -69,9 +69,14 @@ public:
///
/// @param interface The stream that will be used
/// for telemetry communications.
///
/// @param rxBuffSize Size of receive buffer allocated by interface.
/// This is used to warn for buffer overflow.
///
///
BinComm(const MessageHandler *handlerTable,
Stream *interface = NULL);
uint16_t rxBufferSize, Stream *interface = NULL);
///
/// Optional initialiser.
@ -100,6 +105,8 @@ private:
uint8_t payload[256];
} _decodeBuf;
uint16_t _rxBufferSize;
/// Outgoing header/packet buffer
/// XXX we could make this smaller
struct {