Sheep Sheep

Hallo Zusammen,

heute möchte ich mit euch die neuesten Verbesserungen an der Firmware von meinem Schaf teilen.
Viele von uns haben Probleme mit der Geradeausfahrt des Mowers und dem Sonar.
Das kommt meiner Meinung nach von den Odometrie-Interrupts, sprich zuviele, insbesondere wenn die Sonar viel CPU-Zeit durch die pulsIn-Funktion beanspruchen.

Um die Odometrie-Interrupts zu minimieren habe ist mein Schaf schon längere Zeit mit der "OneWay-Odometrie" unterwegs.
Das bring aber was die Interrupts angeht nichts oder nicht viel, solange alle Hallsensoren mit dem Mega verbunden sind, werden die Interrupte noch immer ausgelöst.

Eine kleine Änderung in der mower.cpp schaft Abhilfe (siehe da, das Schaf fährt gerade):


Code:
...
 // enable interrupts
  #ifdef __AVR__
    // R/C
    PCICR |= (1<<PCIE0);
    PCMSK0 |= (1<<PCINT4);
    PCMSK0 |= (1<<PCINT5);
    PCMSK0 |= (1<<PCINT6);
    PCMSK0 |= (1<<PCINT1);  
    
    // odometry
    PCICR |= (1<<PCIE2);
    PCMSK2 |= (1<<PCINT20);
    //PCMSK2 |= (1<<PCINT21);  //do not enable this interrupt for OneWayOdometry 
    PCMSK2 |= (1<<PCINT22);
    //PCMSK2 |= (1<<PCINT23);   //do not enable this interrupt for OneWayOdometry        
    ...


Für die Sonar gibts auch eine Verbesserung, da die CPU jetzt nicht mehr so doll mit Odometrie-Interrupts belastet ist:
-> Sonar über Interrupts auswerten... am einfachsten mit einer schon existierenden Librarry: NewPing von Tim Eckel

Und plötzlich wird Sonar-auswertung bis zu 4m möglich und gut:

NewPing.jpg


Dumm nur, das die Librarry den Timer2 vom Mega verwendet.... kann man aber in der NewPing.h einfach ausschalten:

Code:
...
#define TIMER_ENABLED false      // Set to "false" to disable the timer ISR (if getting "__vector_7" compile errors set this to false). Default=true
...

Die zwei Dateien (NewPing.h und NewPing.cpp) in den Ardumower Ordner einfügen und
noch ein paar Zeilen Code ändern:
mower.cpp

Code:
....
#include "config.h"
#ifdef USE_MOWER

#include "NewPing.h"

#include <Arduino.h>
#include "mower.h"
#include "due.h"
....


Code:
...
  boolean motorMowRpmState = digitalRead(pinMotorMowRpm);
  robot.setOdometryState(timeMicros, odometryLeftState, odometryRightState, odometryLeftState2, odometryRightState2);   
  robot.setMotorMowRPMState(motorMowRpmState);  
}

// mower motor speed sensor interrupt
//void rpm_interrupt(){
//}
NewPing NewSonarLeft(pinSonarLeftTrigger, pinSonarLeftEcho, 500);
NewPing NewSonarRight(pinSonarRightTrigger, pinSonarRightEcho, 500);
NewPing NewSonarCenter(pinSonarCenterTrigger, pinSonarCenterEcho, 500);
...


Code:
...
// sonar---------------------------------------------------------------------------------------------------
    //case SEN_SONAR_CENTER: return(readURM37(pinSonarCenterTrigger, pinSonarCenterEcho)); break;  
   // case SEN_SONAR_CENTER: return(readHCSR04(pinSonarCenterTrigger, pinSonarCenterEcho)); break;
   // case SEN_SONAR_LEFT: return(readHCSR04(pinSonarLeftTrigger, pinSonarLeftEcho)); break;
   // case SEN_SONAR_RIGHT: return(readHCSR04(pinSonarRightTrigger, pinSonarRightEcho)); break;
    case SEN_SONAR_CENTER: return(NewSonarCenter.ping_cm()); break;
    case SEN_SONAR_LEFT: return(NewSonarLeft.ping_cm()); break;
    case SEN_SONAR_RIGHT: return(NewSonarRight.ping_cm()); break;
   // case SEN_LAWN_FRONT: return(measureLawnCapacity(pinLawnFrontSend, pinLawnFrontRecv)); break;    
    //case SEN_LAWN_BACK: return(measureLawnCapacity(pinLawnBackSend, pinLawnBackRecv)); break;  
...


robot.cpp

Code:
...
 if ((sonarUse) && (millis() >= nextTimeSonar)){
    static char senSonarTurn = SEN_SONAR_RIGHT;    
    nextTimeSonar = millis() + 80;
    
    switch(senSonarTurn) {
      case SEN_SONAR_RIGHT:
        if (sonarRightUse) sonarDistRight = readSensor(SEN_SONAR_RIGHT);
        senSonarTurn = SEN_SONAR_LEFT;
        break;
      case SEN_SONAR_LEFT:
        if (sonarLeftUse) sonarDistLeft = readSensor(SEN_SONAR_LEFT);
        senSonarTurn = SEN_SONAR_CENTER;
        break;
      case SEN_SONAR_CENTER:
        if (sonarCenterUse) sonarDistCenter = readSensor(SEN_SONAR_CENTER);
        senSonarTurn = SEN_SONAR_RIGHT;
        break;
      default:
        senSonarTurn = SEN_SONAR_RIGHT;
        break;
    }   
/*
    if (sonarRightUse) sonarDistRight = readSensor(SEN_SONAR_RIGHT);    
    if (sonarLeftUse) sonarDistLeft = readSensor(SEN_SONAR_LEFT);    
    if (sonarCenterUse) sonarDistCenter = readSensor(SEN_SONAR_CENTER); 
*/	
...

pfod.cpp

Code:
...
void RemoteControl::sendSonarMenu(boolean update){
  if (update) Bluetooth.print("{:"); else Bluetooth.print(F("{.Sonar`1000"));         
  Bluetooth.print(F("|d00~Use "));
  sendYesNo(robot->sonarUse);
  Bluetooth.print(F("|d04~Use left "));
  sendYesNo(robot->sonarLeftUse);
  Bluetooth.print(F("|d05~Use center "));
  sendYesNo(robot->sonarCenterUse);
  Bluetooth.print(F("|d06~Use right "));
  sendYesNo(robot->sonarRightUse);
  Bluetooth.print(F("|d01~Counter "));
  Bluetooth.print(robot->sonarDistCounter);    
  Bluetooth.println(F("|d02~Value l, c, r"));
  Bluetooth.print(robot->sonarDistLeft);
  Bluetooth.print(", ");
  Bluetooth.print(robot->sonarDistCenter);
  Bluetooth.print(", ");
  Bluetooth.print(robot->sonarDistRight);  
  sendSlider("d03", F("Trigger below"), robot->sonarTriggerBelow, "", 1, 80);       
  Bluetooth.println("}"); 
...


und schon müsste das funktionieren...
ich hoffe nichts vergessen zu haben...

Ich bin jetzt auch wieder auf 38kHz Samplerate im ADCMAN. Die paar kleinen Änderungen haben für mein schaf viel gebracht....

Gruess

Chris
Attachment: https://forum.ardumower.de/data/media/kunena/attachments/2380/NewPing.jpg/
 
Zuletzt bearbeitet von einem Moderator:
Sehr schön. Ob man das evtl gleich in die aktuelle Version mit übernehmen könnte? Also eine neue Azurit-Version erstellen kann?

Gruß,
Jem
 
Wenn wir den Software-Entwicklern mit diesem Wunsch nicht zuviel Stress machen, wäre es super, das noch in Azurit einzubringen.
 
Ich denke man sollte es erstmal ausgiebig testen bevor es in die Software intigriert wird.
Also so wie Alexander und Co es mit den anderen Softwareveränderungen auch machen bevor es eingebaut wird.
Ich werde es gerne mal versuchen und wenn ihr es auch so macht, könnten wir dann unsere Erfahrungen hier austauschen.
Den Hauptentwickler würde dies bestimmt eine menge Arbeit abnehmen.
Gruß
Stephan
 
Ich habe mal Alexander auf die Änderungen hingewiesen. Ich denke mal das er es auch gelesen hat.
Wenn ihr das testen möchtet sind wir natürlich an Rückmeldungen interessiert. Das einzige was ich nicht weiß ist wie es sich mit der Lib NewPing verhalten tut. Weil bisher alle Libs soviel ich weiß direkt von Alexander sind und ich nicht weiß welchen Einfluss das auf das Copyright des Source Codes des Mowers hat.

Gruß
Uwe
 
Hallo Zusammen,


ja , ich habe vergessen zu Erwähnen, dass die besagten Änderungen erst eine Stunde lang mit 1 Ardumower getestet wurden.... Regenwetter in der Schweiz

Meine Azurit-Version ist auch sonst nicht ganz vanilla... habe da sonst noch ein paar Änderungen hineigepackt, welche aber keine weiteren Auswirkungen auf besagte Verbesserungen haben sollten.

deshalb, ja bitte testen, wer freude am Testen hat.

Das mit der Lizenz bleibt den Authoren der Ardumower-Software überlassen... NewPing hat GNU GPL V3.
Beim Ardumowercode sehe ich dieselbe Lizenz, das wär ja dann schon mal kompatibel...


Gruess

Chris
 
Ich werde mich nachher hinsetzen und deinen Code und anschließend die 3 inzwischen entfernten Ultraschallsensoren wieder einbauen und dann mal schauen, inwieweit ich es testen kann.

Das Flashen des Mega ist ja (in Standardbestückung) umgangssprachlich mit "pain in the ass" zu sehen ...
 
oder so in der Mower.cpp

Code:
// odometry
    PCICR |= (1<<PCIE2);
    if (odometryUse==1) {                                                                           //Uwe geändert von PCMSK2 |= (1<<PCINT20);
      PCMSK2 |= (1<<PCINT20);                                                 
    }
    if (twoWayOdometrySensorUse==1){              //do not enable this interrupt for OneWayOdometry  Uwe geändert von PCMSK2 |= (1<<PCINT21);
      PCMSK2 |= (1<<PCINT21);  
    }
    if (odometryUse==1) {                                                                           //Uwe geändert von PCMSK2 |= (1<<PCINT22)
      PCMSK2 |= (1<<PCINT22);
    }
    if (twoWayOdometrySensorUse==1) {             //do not enable this interrupt for OneWayOdometry  Uwe geändert von PCMSK2 |= (1<<PCINT23);   
    PCMSK2 |= (1<<PCINT23);    
    }


konnte es noch nicht testen
es regnet wieder

gruß
Uwe
 
@Uwe:

das scheint so nicht zu Funktionieren, die Variablen odometryUse==1 und twoWayOdometrySensorUse==1 werden wohl erst nach den Interrupts initialisiert.

Habs mal mit der Azurit 1.05a getestet.


Gruess

Chris
 
habe wieder Kurvenfahrt beobachtet...
dann mal die anderen 2 Interrupts ausgeschaltet


Code:
... 
  // odometry
    PCICR |= (1<<PCIE2);
    //PCMSK2 |= (1<<PCINT20);
    PCMSK2 |= (1<<PCINT21);   
    //PCMSK2 |= (1<<PCINT22);
    PCMSK2 |= (1<<PCINT23);           
    ...


Jetzt fährts wirklich gerade! (???)

Hab ich da ein Problem mit den Pullup Widerständen der Odometrie? Muss ich bei Gelegenheit mal prüfen.
Die NewPing Librarry scheint auch mit Azurit 1.05a zu funktioniern.

Gruess

Chris
 
Hallo Zusammen,

Super, dass Uwe die NewPing lib und die Interrupt-Geschichte in die aktuelle Entwicklerversion mit aufgenommen hat.
Ich habe damit inzwischen wirklich nur gute Erfahrung gesammelt.

Von der 1.0a4 zur 1.0a5 Version haben sich in der pfod.cpp ein paar Sachen geändert. Die Komunikation wird nicht mehr mit

Code:
Bluetooth.print

aufgerufen sondern mit:

Code:
serialPort->print


Ich habe dazu einen Pullrequest gestartet.

Wie Peter habe ich nun auch Armeetelefondraht als Schleifendraht in Verwendung. Das Zeugs ist superstabil und hat einen guten Widerstand (F2E Draht: 6.9Ohm auf 100m).
Der Draht wird auch nicht heiss oder warm.
Damit konnte ich den zusäzlichen Leistungswiderstand aus meiner Perimeterschleife entfernen.


Gruess

Chris
 
Ich habe die Sache ja nur so übernommen wie sie im Forum beschrieben war.

Die Interrupt Geschichte habe ich mit Hilfe von Alexander umgesetzt und bei mir dann erst mal eine Zeitlang getestet bevor ich es eingepflegt habe.

In Sachen Programmieren bin ich noch ein blutiger Anfänger und muss immer sehr viel fragen und nachlesen. Ich hoffe das wird mit der Zeit besser. ;)

Die Ultraschallgeschichte scheint gut zu funktionieren. Ich habe ca 25 - 30cm zur Erkennung eingestellt. Ich hoffe das er noch ein paar mehr Rückmeldungen gibt.
Dann kann Alexander daraus ein neues Releases daraus.
Mit deinem Pullrequest habe ich mal Alexander darauf Aufmerksam gemacht. Leider hat er auf seinen Mäher die Sunray Software laufen und provisorisch die Verdrahtung umgeändert so das er nicht ohne weiteres zurück wechseln kann.


Könntest du mir nur mal kurz erklären wie sich der Fehler äußern tut damit ich das nachvollziehen kann.
Wenn wäre der Fehler in der Dev Version ja auch vorhanden

Gruß
Uwe
 
Hallo Uwe,

Bluetooth.print funtioniert nur mit dem Bluetooth Modul.
bei serialport->print wird je nachdem welches Komunikationsmodiul (Bluetooth/ESP8266) verwndet wird, das entsprechende verwendet.

Der zweite kleine Fehler sehe ich im Plot der Motorcontroll: MotorRpmSet (links und rechts) doppelt angezeigt: zB. 2525.xx statt 25.
das kommt daher, dass motorLeftSpeedRpmSet und motorLeftPID.w ausgegeben werden. Die beiden Werte sollten meisst identisch sein. Ist wahrscheinlich zu Debug-zwecken dazugefügt worden.
Das ist mir erstmals bei Frederic's ESP8266 branch aufgefallen, habe aber damals der Wifi-komunikation die Schuld gegeben. :(


Ich habe mein Sonar auch auf 30cm eingestellt.
Da ich im Plot nicht immer Reflexionen vom Gras sehen wollte (kommt bei mir sporadisch bei ca. 1 Meter -> ist aber wahrscheinlich von Mower zu Mower unterschiedlich, je nach Winkel und Höhe der Ultraschallsensoren) habe ich die maximale Distanz auf 80cm reduziert:


Code:
NewPing NewSonarLeft(pinSonarLeftTrigger, pinSonarLeftEcho, 80);
NewPing NewSonarRight(pinSonarRightTrigger, pinSonarRightEcho, 80);
NewPing NewSonarCenter(pinSonarCenterTrigger, pinSonarCenterEcho, 80);



Gruess

Chris
 
Nächste kleine Verbesserung:

Die Odometrie ISR braucht unnötig "lang" für die Ausführung.
Test der digitalRead funkion im Vergleich zum direkten lesen der Odometrieport Pins (PINK):

Code:
void setup() {
  // put your setup code here, to run once:
pinMode(A11, INPUT);
pinMode(A12, INPUT);
pinMode(A13, INPUT);
pinMode(A14, INPUT);
pinMode(A15, INPUT);
Serial.begin(19200);
}

void loop() {
  // put your main code here, to run repeatedly:
unsigned long timeStamp = micros();

  boolean reading = digitalRead(A11);
  reading = digitalRead(A12);
  reading = digitalRead(A13);
  reading = digitalRead(A14);
  reading = digitalRead(A15);
   


 Serial.println(micros() - timeStamp);
 delay(500);
 timeStamp = micros();


   
  reading = bitRead(PINK,3);
  reading = bitRead(PINK,4);
  reading = bitRead(PINK,5);
  reading = bitRead(PINK,6);
  reading = bitRead(PINK,7);

  Serial.println(micros() - timeStamp);
  delay(500);
}

Ergebnis: digitalRead braucht 20 Mikrosekunden für 5 Lesevorgänge, während bitRead nur 4 Mikrosekunden braucht.

-> ISR könnte mit bitRead 5x schneller fertig sein.

EDIT: einmal reading = micros() braucht auch 4 Mikrosekunden. Dann könnte die Verbesserung noch mehr Zeiteinsparung bedeuten...

EDIT: die Auflösung von micros() scheint 4us zu sein.

ein Test im Ardumower Basis 1.0a5-Azurit(alle Interrupte eingeschaltet) mit dieser ISR:

Code:
#ifdef __AVR__
ISR(PCINT2_vect, ISR_NOBLOCK){
  unsigned long timeMicros = micros();
  boolean odometryLeftState = bitRead(PINK,4);
  boolean odometryLeftState2 = bitRead(PINK,5);
  boolean odometryRightState = bitRead(PINK,6);
  boolean odometryRightState2 = bitRead(PINK,7);
  boolean motorMowRpmState = bitRead(PINK,3);
  robot.setOdometryState(timeMicros, odometryLeftState, odometryRightState, odometryLeftState2, odometryRightState2);
  robot.setMotorMowRPMState(motorMowRpmState);
#else
ISR(PCINT2_vect){
  unsigned long timeMicros = micros();
  boolean odometryLeftState = digitalRead(pinOdometryLeft);
  boolean odometryLeftState2 = digitalRead(pinOdometryLeft2);
  boolean odometryRightState = digitalRead(pinOdometryRight);  
  boolean odometryRightState2 = digitalRead(pinOdometryRight2);  
  boolean motorMowRpmState = digitalRead(pinMotorMowRpm);
  robot.setOdometryState(timeMicros, odometryLeftState, odometryRightState, odometryLeftState2, odometryRightState2);   
  robot.setMotorMowRPMState(motorMowRpmState);  
#endif
}


-> Odometrie funktioniert [strike]nicht[/strike] :-(
[strike]Könnte das an der ISR_NOBLOCK liegen?[/strike]

Test ohne ISR_NOBLOCK:

Code:
#ifdef __AVR__
ISR(PCINT2_vect){
  unsigned long timeMicros = micros();
  boolean odometryLeftState = bitRead(PINK,4);
  boolean odometryLeftState2 = bitRead(PINK,5);
  boolean odometryRightState = bitRead(PINK,6);
  boolean odometryRightState2 = bitRead(PINK,7);
  boolean motorMowRpmState = bitRead(PINK,3);
  robot.setOdometryState(timeMicros, odometryLeftState, odometryRightState, odometryLeftState2, odometryRightState2);
  robot.setMotorMowRPMState(motorMowRpmState);
#else
ISR(PCINT2_vect){
  unsigned long timeMicros = micros();
  boolean odometryLeftState = digitalRead(pinOdometryLeft);
  boolean odometryLeftState2 = digitalRead(pinOdometryLeft2);
  boolean odometryRightState = digitalRead(pinOdometryRight);  
  boolean odometryRightState2 = digitalRead(pinOdometryRight2);  
  boolean motorMowRpmState = digitalRead(pinMotorMowRpm);
  robot.setOdometryState(timeMicros, odometryLeftState, odometryRightState, odometryLeftState2, odometryRightState2);   
  robot.setMotorMowRPMState(motorMowRpmState);  
#endif
}


-> funtioniert einwandfrei mit TwoWayOdo und OneWayOdo
Das Schaf fährt geradeaus und die Perimeterauswertung ist auch kein Problem, trotz blockierendem Interrupt.
[strike]Ich habe aber noch nicht verstanden weshalb das mit dem Interrup "nested" nicht klappt. Vielleicht weiss da jemand mehr?[/strike]

funktioniert auch mit ISR_NOBLOCK !

Nächster Schritt: Testen im aktuellen Master-Branch

Gruess
Chris
 
Falls es jemand braucht.
Für den Due hatte ich damals folgende Funktionen in Interrupts verwendet:


inline void digitalWriteDirect(int pin, boolean val) {
if (val) g_APinDescription[pin].pPort -> PIO_SODR = g_APinDescription[pin].ulPin;
else g_APinDescription[pin].pPort -> PIO_CODR = g_APinDescription[pin].ulPin;
}

inline void digitalWriteDirectHigh(int pin) {
g_APinDescription[pin].pPort -> PIO_SODR = g_APinDescription[pin].ulPin;
}

inline void digitalWriteDirectLow(int pin) {
g_APinDescription[pin].pPort -> PIO_CODR = g_APinDescription[pin].ulPin;
}


inline int digitalReadDirect(int pin) {
return !!(g_APinDescription[pin].pPort -> PIO_PDSR & g_APinDescription[pin].ulPin);
}
 
Die dunkle Jahreszeit kommt... nicht für Sheep Sheep :cheer:

"if you are in china, buy some LEDs", they said. "It will be fun", they said.
Das nächste mal würde ich dann das PCB(Träger für die LEDs)auch gleich zum Verbinden der LED Streifen benutzen. Der Verkabelungsaufwand war doch beträchtlich.
Facelift:
WP_20160922_0051.jpg


[video width=425 height=344 type=youtube]vlJucej4JTo[/video]
bei 100%PWM konsumieren die LEDs 10W (bei 10V- 1A) und nerfen womöglich die Nachbarn. Habs mal etwas runtergeschraubt...
Ein weiterer Atmega328 wurde für die PWM-Steuerung der Mofets verbaut..

Gruess

Chris
Attachment: https://forum.ardumower.de/data/media/kunena/attachments/2380/WP_20160922_0051.jpg/
 
Zuletzt bearbeitet von einem Moderator:
timeMicros wird in robot.setOdometryState() scheinbar gar nicht verwendet. Da kannst du auch irgend eine Zahl übergeben und die micros() entfernen. Bitte einmal prüfen.
 
Oben