Starke Spurabweichung (Drift) nach längerer Einschaltzeit

Does "setSpeed" need to be set to my personal speed or can still be configured in the app?
Yes it's configured by the sunray app when you click on start.
But if agcm4 reboot while mowing i am not sûre that the speed and the 4 setting for Stanley are ok after the reboot,and it can explain why this only append after a long duration
Also into config.h try to Adjust stanley setting according the value you use in the sunray app:
Code:
// ---- path tracking -----------------------------------

// below this robot-to-target distance (m) a target is considered as reached
#define TARGET_REACHED_TOLERANCE 0.05

// stanley control for path tracking - determines gain how fast to correct for lateral path errors
#define STANLEY_CONTROL_P_NORMAL  1.1   // 3.0 for path tracking control (angular gain) when mowing
#define STANLEY_CONTROL_K_NORMAL  0.3   // 1.0 for path tracking control (lateral gain) when mowing

#define STANLEY_CONTROL_P_SLOW    1.1   // 3.0 for path tracking control (angular gain) when docking tracking
#define STANLEY_CONTROL_K_SLOW    0.3   // 0.1 for path tracking control (lateral gain) when docking tracking
 
Beide Änderungen mal übernommen, werde Sonntag mal einen zweiten Langzeittest machen wenn das Wetter passt, mal schauen wie er sich verhält.
 
Guten Tag! Ich besitze seit ca. 1 Jahr einen Alfred, und bin im Großen und Ganzen eigentlich zufrieden damit. Beim Kauf war mir bewußt, daß das Projekt/Produkt im Anfangsstadium ist und Verbesserungen/Erweiterungen kommen würden/sollten. Ich kann mit einem Windows PC umgehen, besitze ein iPhone, kann aber weder LINUX noch habe ich die Absicht selbst Code-Modifizierungen vorzunehmen. Deshalb hatte ich mich für den Alfred (und nicht einen Ardumower) entschieden. Ich lese hier seit geraumer Zeit passiv mit, habe mich aus aktuellem Anlaß aber nun offiziell angemeldet.

Soviel als Vorbemerkungen. Vor einigen Tagen habe ich ein Sunray Update auf dem Alfred auf 1.0.305 (von 1.0.298) gemacht. Die MCU Firmware RM18 ist Verion 1.1.15.
Vor 2 Tagen ist auch mir (durch Zufall) das in diesem Thread beschriebene Verhalten von teilweise starke Abweichungen von der berechneten Bahn aufgefallen. Am PC wurden teilweise bis zu 40 cm Abweichung in langen Bahnen angezeigt, obwohl GPS auf "fix" stand und die angezeigten Abweichungen sich normalerweise im Bereich +/- 2-4 cm bewegen. Am Ende der Bahnen manövrierte sich Alfred aber wieder ziemlich genau zum berechneten Endpunkt.

Das ist alles eigentlich noch kein großes Problem, sofern es nicht dazu führt, daß Alfred sich am Ende von Bahnen in Beeten oder Hecken festfährt. (Könnte bei mir mal passiert sein, aber da war ich noch nicht für die in diesem Thread beschriebene möglich Ursache sensibilisiert.)
Gestern scheint diese problematische Bahn-Abweichung (nach mehrstündigem Betrieb und ununterbrochener Einschaltdauer, da ich nach Mähende nicht ausschalte) aber dazu geführt zu haben, daß Alfred nicht in die Docking-Station manövrieren konnte. Die Abweichung vom Dockingpfad war so, daß er beim Einfahren in die Dockingstation ca. 10 - 15 cm zu weit rechts fuhr und gegen die Garage stieß, per Bumper ein Hindernis erkannte und es dann neu versuchte, aber einfach nicht den Weg hinein fand. An den Tagen vorher hatte das aber problemlos funktioniert.
Nach etlichen Dockingfehlversuchen, erinnerte ich mich an diesen Thread mit den unerklärlichen Bahnabweichungen und die erwähnte temporäre Problemlösung.
Ich stoppte Alfred durch einmaliges Drücken der roten Taste am Roboter, führte am PC ein "Reboot Robot" aus, dann den PC neu mit Alfred "connected" und schließlich vom PC aus den "Dock" Befehl gegeben. Und siehe da: Alfred fand sofort zielgenau beim ersten Anlauf in seine Dockingstation (und seitdem bisher auch schon 3 mal wieder).

Leider kann ich nicht sagen, ob dieser (hier beschriebene Abweichungs-)Bug schon bei Vers. 1.0.298 (vielleicht unerkannt) vorhanden war oder erst mit Vers. 1.0.305 neu kam. Kann vielleicht ein Administrator die Problematik an Alexander herantragen? Eine Codemodifizierung (analog zu einigen der hier oben beschriebenen) durch mich selbst kommt leider aus den eingangs erwähnten Gründen nicht in Frage.
Danke schon einmal für Eure Gedanken/Ideen.
 
So hat dann wegen Wetter doch was länger gedauert mit dem nächsten Test.
Eben gerade nach glaube 7 Tage Online in der Garage mein Mäher auf die Wiese gestellt und ohne vorherigen Reboot gestartet.

Tja was soll ich sagen... exakt gleiche Problem weiterhin vorhanden!
Auch Speed manuell in der App auf 0.20 zu setzen bringt keinen Unterschied, dann eiert er nur langsamer umher.

Also hier sollte echt mal eine Aussage kommen was hier los ist und warum das Auftritt bzw. ein Fix für kommen.
Das war doch damals auch nicht der Fall, das kam doch mit irgendeiner Sunray Version plötzlich rein, hab früher problemlos eine Woche mähen können ohne Reboot und jetzt ist nach ~9h schon Schluss und ohne Reboot geht nichts mehr.

@AlexanderG
Irgendein Statement dazu?
Wurde das Problem eventuell in irgendeiner Version gefixt auf die man updaten kann?

Edit: Und wenn das bei Alfred auch vorkommt kann ja der Duo dafür nicht verantwortlich sein, dann scheint das ja auch auf der anderen Platform aufzutreten?
 
Edit: Und wenn das bei Alfred auch vorkommt kann ja der Duo dafür nicht verantwortlich sein, dann scheint das ja auch auf der anderen Platform aufzutreten?
beim AGCM4 das gleiche. Und nach meinem Gefühl mit der V305 nochmals schlechter. Musste jetzt erstmals trotz booten vor dem Mähen nach 3.5h Mähen rebooten, um den Mäher auf Kurs zu halten.
 
beim AGCM4 das gleiche. Und nach meinem Gefühl mit der V305 nochmals schlechter. Musste jetzt erstmals trotz booten vor dem Mähen nach 3.5h Mähen rebooten, um den Mäher auf Kurs zu halten.
To confirm after a very long duration >12 hours test the 10 rev wheel .
Reboot and repeat the test.
I have also the issue with Teensy, so it's software.
Without success warranty Take a look at the 2 function:
void OdometryRightISR() and left one into robotdriver.
So first try to remove
#define SUPER_SPIKE_ELIMINATOR 1 // advanced spike elimination (experimental, comment out to disable)
or remove the timeout part.
Here for teensy,only the first 3 line :
Code:
void OdometryLeftISR()
{
#ifdef __IMXRT1062__ // teensy 4
  odomTicksLeft++;
  asm("dsb");
#else
  if (digitalRead(pinOdometryLeft) == LOW)
      return;
  if (millis() < motorLeftTicksTimeout)
      return; // eliminate spikes
#ifdef SUPER_SPIKE_ELIMINATOR
  unsigned long duration = millis() - motorLeftTransitionTime;
  if (duration > 5)
      duration = 0;
  motorLeftTransitionTime = millis();
  motorLeftDurationMax = 0.7 * max(motorLeftDurationMax, ((float)duration));
  motorLeftTicksTimeout = millis() + motorLeftDurationMax;
#else
  motorLeftTicksTimeout = millis() + 1;
#endif
  odomTicksLeft++;
#endif
}
 
after a closer look at the code, i cant find any problem with that. Nevertheless i disabled the "SUPER_SPIKE_ELIMINATOR".
No chance for the ticktest today, cause i had to reboot the mower several times to solve my charging-problems.
For more stability and agility i made some changes in the LineTracker.ccp and motor.ccp. I know, that they are not responsible for the problem, but i think, that the changes can help to reduce it. My tests with up to 0.7m/s (not selectable with the normal APP) were very stable and smooth. If there is any interest here, i will post the link after pushing it to github.
 
after a closer look at the code, i cant find any problem with that. Nevertheless i disabled the "SUPER_SPIKE_ELIMINATOR".
No chance for the ticktest today, cause i had to reboot the mower several times to solve my charging-problems.
For more stability and agility i made some changes in the LineTracker.ccp and motor.ccp. I know, that they are not responsible for the problem, but i think, that the changes can help to reduce it. My tests with up to 0.7m/s (not selectable with the normal APP) were very stable and smooth. If there is any interest here, i will post the link after pushing it to github.
For AGCM4 you can also use the asm("dsb"); code to free the interrupt.
Into amRobotdriver.com


Code:
void OdometryLeftISR(){             
  if (digitalRead(pinOdometryLeft) == LOW) return;
  if (millis() < motorLeftTicksTimeout) return; // eliminate spikes 
  #ifdef SUPER_SPIKE_ELIMINATOR
    unsigned long duration = millis() - motorLeftTransitionTime;
    if (duration > 5) duration = 0;
    motorLeftTransitionTime = millis();
    motorLeftDurationMax = 0.7 * max(motorLeftDurationMax, ((float)duration));
    motorLeftTicksTimeout = millis() + motorLeftDurationMax;
  #else
    motorLeftTicksTimeout = millis() + 1;
  #endif
  odomTicksLeft++; 
  asm("dsb");     
}

void OdometryRightISR(){           
  if (digitalRead(pinOdometryRight) == LOW) return; 
  if (millis() < motorRightTicksTimeout) return; // eliminate spikes
  #ifdef SUPER_SPIKE_ELIMINATOR
    unsigned long duration = millis() - motorRightTransitionTime;
    if (duration > 5) duration = 0; 
    motorRightTransitionTime = millis();
    motorRightDurationMax = 0.7 * max(motorRightDurationMax, ((float)duration)); 
    motorRightTicksTimeout = millis() + motorRightDurationMax;
  #else
    motorRightTicksTimeout = millis() + 1;
  #endif
  odomTicksRight++;
  asm("dsb");       
 
  #ifdef TEST_PIN_ODOMETRY
    testValue = !testValue;
    digitalWrite(pinKeyArea2, testValue); 
  #endif
}
 
Okay today after long switch on time I tried AT+E Test -> 13,25 revolutions
After reboot:
AT+E Test -> exactly 10 revolutions

Next I‘ll try to comment define SUPER_SPIKE_ELIMINATOR 1 line
 
Next I‘ll try to comment define SUPER_SPIKE_ELIMINATOR 1 line
i did it yesterday. After 24h without reboot no drunken pilot on the lawn. GREAT.
try asm("dsb"); at the end of the interrupt part
thats allready in the code but not on my robot, cause i wont reboot it for testing.
@bernard: I modified the code in the following way. Is that right to set asm("dsb") to all exits?
void OdometryRightISR(){
if (digitalRead(pinOdometryRight) == LOW) { asm("dsb"); return;}
if (millis() < motorRightTicksTimeout) { asm("dsb"); return;} // eliminate spikes
#ifdef SUPER_SPIKE_ELIMINATOR
unsigned long duration = millis() - motorRightTransitionTime;
if (duration > 5) duration = 0;
motorRightTransitionTime = millis();
motorRightDurationMax = 0.7 * max(motorRightDurationMax, ((float)duration));
motorRightTicksTimeout = millis() + motorRightDurationMax;
#else
motorRightTicksTimeout = millis() + 1;
#endif
odomTicksRight++;

#ifdef TEST_PIN_ODOMETRY
testValue = !testValue;
digitalWrite(pinKeyArea2, testValue);
#endif
asm("dsb");
}
 
i did it yesterday. After 24h without reboot no drunken pilot on the lawn. GREAT.

thats allready in the code but not on my robot, cause i wont reboot it for testing.
@bernard: I modified the code in the following way. Is that right to set asm("dsb") to all exits?
Yes i am wrong in my yesterday post you really need asm before each return.
But maybe you can test to simplify everything like i did for teensy.
Again not tested.

Code:
void OdometryLeftISR(){             
    odomTicksLeft++;
    asm("dsb");     
}

void OdometryRightISR(){           
  odomTicksRight++;
  #ifdef TEST_PIN_ODOMETRY
    testValue = !testValue;
    digitalWrite(pinKeyArea2, testValue);
  #endif
  asm("dsb");     
}
 
Take care on the 10 rev test.
It's actually limited to 50 secondes without error message and the slow down at the end is very low.
Here the code to solve this.
Code:
void Motor::test() {
  CONSOLE.println("motor test - 10 revolutions");
  motorLeftTicks = 0;
  motorRightTicks = 0;
  unsigned long nextInfoTime = 0;
  int seconds = 0;
  int pwmLeft = 200;
  int pwmRight = 200;
  bool slowdown = true;
  unsigned long stopTicks = ticksPerRevolution * 10;
  unsigned long nextControlTime = 0;
  while (motorLeftTicks < stopTicks || motorRightTicks < stopTicks) {
    if (millis() > nextControlTime) {
      nextControlTime = millis() + 20;
      if ((slowdown) && ((motorLeftTicks + ticksPerRevolution  > stopTicks) || (motorRightTicks + ticksPerRevolution > stopTicks))) { //Letzte halbe drehung verlangsamen
        pwmLeft = pwmRight = 80;
        slowdown = false;
        CONSOLE.println("Slow down for the last rev");
      }
      if (millis() > nextInfoTime) {
        nextInfoTime = millis() + 1000;
        if (seconds > 120)
        {
          CONSOLE.println("Error can't reach the 10 rev in less than 2 minutes");
          break;
        }
        dumpOdoTicks(seconds);
        seconds++;
      }
      if (motorLeftTicks >= stopTicks)
      {
        pwmLeft = 0;
      }
      if (motorRightTicks >= stopTicks)
      {
        pwmRight = 0;
      }

      speedPWM(pwmLeft, pwmRight, 0);
      sense();
      //delay(50);
      watchdogReset();
      robotDriver.run();
    }
  }
  speedPWM(0, 0, 0);
  CONSOLE.println("motor 10 rev done - please ignore any IMU/GPS errors");
  CONSOLE.println("ADJUST TICKS_PER_REVOLUTION into config.h is not OK");
}
 
thank you for sharing. For me, 100 as normal PWM and 40 at the end is fine. I am woundering, why asm double the ticks. Do you know the reason?
 
Zuletzt bearbeitet:
why asm double the ticks.
Not sure if it's the double, but adding it help me a lot in the teensyber soft ,now need to see if it's the same with AGCM4 and sunray.
And i can't tell why :ROFLMAO: :ROFLMAO: because i don't understand it.

In the 10 rev test check always that you have a normal end at 10*ticksPerRevolution and not the 50 secondes trigger, in my case i see sometime the end of the test without the slow speed and it's the reason i search to understand what's append and add the error message.
 
I can agree. Commenting super_spike_elemimator makes the difference, asm("dsb") not. Since I commented the super_spike_elemimator, there are no more problems with drunken pilot on the lawn. I'm very happy with this improvement.
 
Oben