mirror of https://github.com/ArduPilot/ardupilot
Fix the idle timer.
Init a few more critical fields in the ctor. git-svn-id: https://arducopter.googlecode.com/svn/trunk@772 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
9e7876fee7
commit
aec22fc639
|
@ -46,7 +46,9 @@
|
|||
|
||||
BinComm::BinComm(const BinComm::MessageHandler *handlerTable,
|
||||
Stream *interface) :
|
||||
_handlerTable(handlerTable)
|
||||
_handlerTable(handlerTable),
|
||||
_decodePhase(DEC_WAIT_P1),
|
||||
_lastReceived(millis())
|
||||
{
|
||||
init(interface);
|
||||
};
|
||||
|
@ -108,6 +110,7 @@ BinComm::_decode(uint8_t inByte)
|
|||
//
|
||||
if ((millis() - _lastReceived) > DEC_MESSAGE_TIMEOUT)
|
||||
_decodePhase = DEC_WAIT_P1;
|
||||
_lastReceived = millis();
|
||||
|
||||
// run the decode state machine
|
||||
//
|
||||
|
@ -206,7 +209,10 @@ BinComm::_decode(uint8_t inByte)
|
|||
} else {
|
||||
badMessagesReceived++;
|
||||
}
|
||||
// FALLTHROUGH
|
||||
default:
|
||||
_decodePhase = DEC_WAIT_P1;
|
||||
break;
|
||||
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue