mageshms / arducopter

Automatically exported from code.google.com/p/arducopter
0 stars 0 forks source link

APM_BinComm Errors #44

Closed GoogleCodeExporter closed 8 years ago

GoogleCodeExporter commented 8 years ago
What steps will reproduce the problem?
1. Attempt to run APM_BinComm class using boost serial class on desktop.

What is the expected output? What do you see instead?
1. Should unpack packages and display result.
2. Instead I get state machine lock ups.

What version of the product are you using? On what operating system?
Latest svn, debian lenny.

Please provide any additional information below.
Here is the patch to fix it.

Index: APM_BinComm.cpp
===================================================================
--- APM_BinComm.cpp (revision 568)
+++ APM_BinComm.cpp (working copy)
@@ -47,7 +47,9 @@
 BinComm::BinComm(const BinComm::MessageHandler *handlerTable,
                  Stream *interface) :
         _handlerTable(handlerTable),
-        _interface(interface)
+        _interface(interface),
+       _decodePhase(0),
+       _lastReceived(millis())
 {
 };

@@ -101,7 +103,10 @@
         // handle inter-byte timeouts (resync after link loss, etc.)
         //
         if ((millis() - _lastReceived) > DEC_MESSAGE_TIMEOUT)
+       {
+               _lastReceived = millis();
                 _decodePhase = DEC_WAIT_P1;
+       }

         // run the decode state machine
         //
@@ -191,6 +196,7 @@
                 if (inByte == _sumB) {
                         // if we got this far, we have a message
                         messagesReceived++;
+                       _lastReceived = millis();

                         // call any handler interested in this message
                         for (tableIndex = 0; MSG_NULL != _handlerTable[tableIndex].messageID; tableIndex++)
@@ -202,5 +208,7 @@
                 }
                 _decodePhase = DEC_WAIT_P1;
                 break;
+       default:
+               _decodePhase = DEC_WAIT_P1;
         }
 }

Original issue reported on code.google.com by james.goppert@gmail.com on 30 Sep 2010 at 3:02

GoogleCodeExporter commented 8 years ago
Is there a reason you guys haven't patched this? It will just infinetly loop at 
step 1 after the time elapsed exceeds the time out. I see that in your 
host-side test software that you implement millis() as always returning zero 
which should get it to work, although the time delay check would be disabled, 
but on the microprocessor side I don't see how it would function properly.

Original comment by james.goppert@gmail.com on 14 Oct 2010 at 2:58

GoogleCodeExporter commented 8 years ago
We haven't fixed it yet because I think we don't have a ground station to make 
sure of it yet.  Once we have that we will have a much higher motivation to fix 
it.

I wonder how you're using it at this point to be honest...happy you are of 
course...but it's not hitched up to anything yet in arduCopter code.

Original comment by rmackay...@gmail.com on 25 Oct 2010 at 12:52

GoogleCodeExporter commented 8 years ago
I'm using it here, http://code.google.com/p/ardupilotmegacomm/. Please fix it, 
it seems silly for me to maintain a fork. You can verify that it works with my 
test program.

Original comment by james.goppert@gmail.com on 27 Oct 2010 at 3:46

GoogleCodeExporter commented 8 years ago

Original comment by james.goppert@gmail.com on 9 Dec 2010 at 6:16