Skip to content
Snippets Groups Projects
Commit 12aaae5e authored by leon's avatar leon
Browse files
parents 25732a52 54b4d069
No related branches found
No related tags found
No related merge requests found
### DynamixelSDK
All in one SDK for ROBOTIS Dynamixel
* Protocol 1.0 / Protocol 2.0
* Windows / Linux
--------------------------------------------------------------------------
###Any questions are welcomed. Just let us know through: [ISSUES](https://github.com/ROBOTIS-GIT/DynamixelSDK/issues)
......@@ -183,7 +183,12 @@ int Protocol1PacketHandler::RxPacket(PortHandler *port, UINT8_T *rxpacket)
}
// re-calculate the exact length of the rx packet
_wait_length = rxpacket[PKT_LENGTH] + PKT_LENGTH + 1;
if(_wait_length != rxpacket[PKT_LENGTH] + PKT_LENGTH + 1)
{
_wait_length = rxpacket[PKT_LENGTH] + PKT_LENGTH + 1;
continue;
}
if(_rx_length < _wait_length)
{
// check timeout
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment