Odometrie drin - Mower randaliert

marcello

New member
Guten Abend!

Heute habe ich meinem Robotor Odometrie im Rahmen meiner Möglichkeiten gegönnt. D.h. auf den Achsen der Räder sitzen Schlitzscheiben mit Gabellichtschranken, die pro Umdrehung 49 Ticks liefern.

ardu_2_2017-06-16.jpeg


[ul]
[li]Der Odometrietest läuft problemlos.[/li]
[li]Die Pausen (Mower muss wenden, weil Bumper an Hindernis) bei Richtungsänderungen gibt es nicht mehr.[/li]
[li]Problematisch ist, dass es jetzt (wenn überhaupt) keine schnelle Reaktion mehr auf Bumpersignale mehr gibt. Die Räder drehen sich lange weiter, reissen Furchen, fast Gräben in meinen zarten Rasen.[/li]
[li]Es gibt ab und an Odometriefehler, wenn das passiert, tut der Mower das was er zuletzt getan hat (er dreht sich, oder fährt ohne Rücksicht auf Verluste und Sensoren piepsend weiter). Dann sind Kommandos über Bluetooth genauso wirkunkslos wie der Taster - es hilft nur noch Strom aus.[/li]
[/ul]

Ich habe folgende Fragen:
Gibt es Tipps, wie man den totalen Kontrollverlust im Fehlerfall vermeiden kann?
Wie muss ich die Motoren parametrieren, dass trotz Odometrie zeitnah auf Sensoren reagiert wird?


Code:
Mower::Mower(){
  name = "Robbie";
  // ------- wheel motors -----------------------------
  motorAccel       = 1000;  // motor wheel acceleration - only functional when odometry is not in use (warning: do not set too low)
  motorSpeedMaxRpm       = 20;   // motor wheel max RPM (WARNING: do not set too high, so there's still speed control when battery is low!)
  motorSpeedMaxPwm    = 255;  // motor wheel max Pwm  (8-bit PWM=255, 10-bit PWM=1023)
  motorPowerMax     = 100;    // motor wheel max power (Watt)
  motorSenseRightScale = 15.3; // motor right sense scale (mA=(ADC-zero)/scale)
  motorSenseLeftScale = 15.3; // motor left sense scale  (mA=(ADC-zero)/scale)
  motorPowerIgnoreTime = 1000; // time to ignore motor power (ms)
  motorZeroSettleTime   = 3000 ; // how long (ms) to wait for motors to settle at zero speed
  motorRollTimeMax    = 5000;  // max. roll time (ms)
  motorRollTimeMin    = 3000; //min. roll time (ms) should be smaller than motorRollTimeMax
  motorReverseTime    = 2000;  // max. reverse time (ms)
  motorForwTimeMax   = 80000; // max. forward time (ms) / timeout
  motorBiDirSpeedRatio1 = 0.3;   // bidir mow pattern speed ratio 1
  motorBiDirSpeedRatio2 = 0.92;   // bidir mow pattern speed ratio 2
  // ---- normal control ---
  motorLeftPID.Kp       = 1.5;    // motor wheel PID controller
  motorLeftPID.Ki       = 0.29;
  motorLeftPID.Kd       = 0.25;
  /*// ---- fast control ---
  motorLeftPID.Kp       = 1.76;    // motor wheel PID controller
  motorLeftPID.Ki       = 0.87;
  motorLeftPID.Kd       = 0.4;*/
  
  motorRightSwapDir     = 0;    // inverse right motor direction? 
  motorLeftSwapDir      = 0;    // inverse left motor direction?
  // ------ mower motor -------------------------------
  motorMowAccel       = 2000;  // motor mower acceleration (warning: do not set too low) 2000 seems to fit best considerating start time and power consumption 
  motorMowSpeedMaxPwm   = 255;    // motor mower max PWM
  motorMowPowerMax = 75.0;     // motor mower max power (Watt)
  motorMowModulate  = 0;      // motor mower cutter modulation?
  motorMowRPMSet        = 3300;   // motor mower RPM (only for cutter modulation)
  motorMowSenseScale = 15.3; // motor mower sense scale (mA=(ADC-zero)/scale)
  motorMowPID.Kp = 0.005;    // motor mower RPM PID controller
  motorMowPID.Ki = 0.01;
  motorMowPID.Kd = 0.01;
  //  ------ bumper -----------------------------------
  bumperUse         = 1;      // has bumpers?
  //  ------ drop -----------------------------------
  dropUse          = 0;     // has drops?                                                                                              Dropsensor - Absturzsensor vorhanden ?
  dropcontact      = 1;     //contact 0-openers 1-closers                                                                              Dropsensor - Kontakt 0-Öffner - 1-Schließer betätigt gegen GND
  // ------ rain ------------------------------------
  rainUse          = 0;      // use rain sensor?
  // ------ sonar ------------------------------------
  sonarUse          = 1;      // use ultra sonic sensor? (WARNING: robot will slow down, if enabled but not connected!)
  sonarLeftUse      = 1;
  sonarRightUse     = 1;
  sonarCenterUse    = 1;
  sonarTriggerBelow = 30;    // ultrasonic sensor trigger distance
  // ------ perimeter ---------------------------------
  perimeterUse       = 0;      // use perimeter?    
  perimeterTriggerTimeout = 0;      // perimeter trigger timeout when escaping from inside (ms)  
  perimeterOutRollTimeMax  = 2000;   // roll time max after perimeter out (ms)
  perimeterOutRollTimeMin = 750;    // roll time min after perimeter out (ms)
  perimeterOutRevTime   = 2200;   // reverse time after perimeter out (ms)
  perimeterTrackRollTime = 1500; //roll time during perimeter tracking
  perimeterTrackRevTime = 2200;  // reverse time during perimeter tracking
  perimeterPID.Kp    = 51.0;  // perimeter PID controller
  perimeterPID.Ki    = 12.5;
  perimeterPID.Kd    = 0.8;  
  trackingPerimeterTransitionTimeOut = 2000;
  trackingErrorTimeOut = 10000;
  trackingBlockInnerWheelWhilePerimeterStruggling = 1;
  // ------ lawn sensor --------------------------------
  lawnSensorUse     = 0;       // use capacitive Sensor
  // ------  IMU (compass/accel/gyro) ----------------------
  imuUse            = 0;       // use IMU?
  imuCorrectDir     = 0;       // correct direction by compass?
  imuDirPID.Kp      = 5.0;     // direction PID controller
  imuDirPID.Ki      = 1.0;
  imuDirPID.Kd      = 1.0;    
  imuRollPID.Kp     = 0.8;   // roll PID controller
  imuRollPID.Ki     = 21;
  imuRollPID.Kd     = 0;  
  // ------ model R/C ------------------------------------
  remoteUse         = 1;       // use model remote control (R/C)?
  // ------ battery -------------------------------------
  batMonitor = 1;              // monitor battery and charge voltage?
  batGoHomeIfBelow = 11.4;     // drive home voltage (Volt)
  batSwitchOffIfBelow = 10.1;  // switch off battery if below voltage (Volt)
  batSwitchOffIfIdle = 1;      // switch off battery if idle (minutes)
  batFactor       = 0.495;      // battery conversion factor  / 10 due to arduremote bug, can be removed after fixing (look in robot.cpp)
  batChgFactor    = 0.495;      // battery conversion factor  / 10 due to arduremote bug, can be removed after fixing (look in robot.cpp)
  batFull          =14.4;      // battery reference Voltage (fully charged) PLEASE ADJUST IF USING A DIFFERENT BATTERY VOLTAGE! FOR a 12V SYSTEM TO 14.4V
  batChargingCurrentMax =1.6;  // maximum current your charger can devliver
  batFullCurrent  = 0.3;      // current flowing when battery is fully charged
  startChargingIfBelow = 11.5; // start charging if battery Voltage is below
  chargingTimeout = 12600000; // safety timer for charging (ms) 12600000 = 3.5hrs
  // Sensorausgabe Konsole      (chgSelection =0)
  // Einstellungen ACS712 5A    (chgSelection =1   /   chgSenseZero ~ 511    /    chgFactor = 39    /    chgSense =185.0    /    chgChange = 0 oder 1    (je nach  Stromrichtung)   /   chgNull  = 2)
  // Einstellungen INA169 board (chgSelection =2)
  chgSelection    = 2;
  chgSenseZero    = 511;        // charge current sense zero point
  chgFactor       = 39;         // charge current conversion factor   - Empfindlichkeit nimmt mit ca. 39/V Vcc ab
  chgSense        = 185.0;      // mV/A empfindlichkeit des Ladestromsensors in mV/A (Für ACS712 5A = 185)
  chgChange       = 0;          // Messwertumkehr von - nach +         1 oder 0
  chgNull         = 2;          // Nullduchgang abziehen (1 oder 2)
  // ------  charging station ---------------------------
  stationRevTime     = 1800;    // charge station reverse time (ms)
  stationRollTime    = 1000;    // charge station roll time (ms)
  stationForwTime    = 1500;    // charge station forward time (ms)
  stationCheckTime   = 1700;    // charge station reverse check time (ms)
  // ------ odometry ------------------------------------
  odometryUse       = 1;       // use odometry?
  twoWayOdometrySensorUse = 0; // use optional two-wire odometry sensor?
  odometryTicksPerRevolution = 49;   // encoder ticks per one full resolution
  odometryTicksPerCm = 0.65;  // encoder ticks per cm
  odometryWheelBaseCm = 24;    // wheel-to-wheel distance (cm)
  odometryRightSwapDir = 0;       // inverse right encoder direction?
  odometryLeftSwapDir  = 0;       // inverse left encoder direction?
  // ----- GPS -------------------------------------------
  gpsUse            = 0;       // use GPS?
  stuckIfGpsSpeedBelow = 0.2; // if Gps speed is below given value the mower is stuck
  gpsSpeedIgnoreTime = 5000; // how long gpsSpeed is ignored when robot switches into a new STATE (in ms)

  // ----- other -----------------------------------------
  buttonUse         = 1;       // has digital ON/OFF button?
  // ----- user-defined switch ---------------------------
  userSwitch1       = 0;       // user-defined switch 1 (default value)
  userSwitch2       = 0;       // user-defined switch 2 (default value)
  userSwitch3       = 0;       // user-defined switch 3 (default value)
  // ----- timer -----------------------------------------
  timerUse          = 0;       // use RTC and timer?
  // ----- bluetooth -------------------------------------
  bluetoothUse      = 1;       // use Bluetooth module?
  // ----- esp8266 ---------------------------------------
  esp8266Use        = 0;       // use ESP8266 Wifi module?
  esp8266ConfigString = "123test321";
  // ------ mower stats-------------------------------------------  
  statsOverride = false; // if set to true mower stats are overwritten - be careful
  statsMowTimeMinutesTotal = 300;
  statsBatteryChargingCounterTotal = 11;
  statsBatteryChargingCapacityTotal = 30000;
  // -----------configuration end-------------------------------------
}


Vielen Dank im Voraus
Marcello
 
EIn weiteres neues "Feature" habe ich entdeckt: Der Mäher ist auf "OFF" und hat Strom. Wenn ich jetzt leicht an einem Rad drehe, ist ein leichtes Summen zu hören, dann setzen sich die Räder in Bewegung. Zuerst in entgegengesetzte Richtungen, kurz darauf in die gleiche Richtung. Nach ca. 3 Minuten hören die Räder auf sich zu drehen.
Das finde ich ziemlich ungewöhnlich und durchaus bedenklich, da in dieser Phase des "Schlafwandelns" Hindernisse nachhaltig ignoriert werden.
 
Du beschreibst haargenau mein Fehlerbild, an dem ich schon fast ein Jahr dran kämpfe (bisher ohne Lösung).
Das mit der Trägheit kannst du mit den Reglungs PIDs in den Griff bekommen. Die Standard Einstellung ist für wesentlich mehr Ticks ausgelegt.
Das Problem mit den Total Ausfall ist mir noch ein Rätsel.

Mittlerweile habe ich sehr günstig einen defekten Automower und repariert. Der verrichtet nun seinen Dienst im Garten.
iSheep ist dabei aufs Abstellgleis geraden. Er steht nun zum Verkauf.
 
So, ich habe jetzt an den PIDs geschraubt und mit

Code:
motorLeftPID.Kp       = 1.5;    // motor wheel PID controller
motorLeftPID.Ki       = 0.01;
motorLeftPID.Kd       = 0.01;


fährt er wieder vernünftig.

Leider gibt es immer noch Odometriefehler. Diese treten in Abständen von 10 Sek. bis 5 Min auf und betreffen immer nur eine Seite, die Seite ist aber nicht konstant.
Mir ist auch aufgefallen, dass die Odometriefehler immer nur beim Geradeausfahren aufreten.

Was könnte denn diese Fehler auslösen?
Wäre es möglich, diese Fehler bis zu einem gewissen Maß zu ignorieren und was wären die Risiken dabei?

Danke

LGM
 
Hallo Marcello,

an dieser Stelle wird die Odometrie überprüft:

robot.cpp

Code:
// check for odometry sensor faults    
void Robot::checkOdometryFaults(){
  if (!odometryUse)  return;
  bool leftErr = false;
  bool rightErr = false;
  if ((stateCurr == STATE_FORWARD) &&  (millis()-stateStartTime>8000) ) {
    // just check if odometry sensors may not be working at all
    if ( (motorLeftPWMCurr > 100) && (abs(motorLeftRpmCurr) < 1)  )  leftErr = true;
    if ( (motorRightPWMCurr > 100) && (abs(motorRightRpmCurr) < 1)  ) rightErr = true;
  }  
  if ((stateCurr == STATE_ROLL) &&  (millis()-stateStartTime>1000) ) {
    // just check if odometry sensors may be turning in the wrong direction
    if ( ((motorLeftPWMCurr > 100) && (motorLeftRpmCurr < -3)) || ((motorLeftPWMCurr < -100) && (motorLeftRpmCurr > 3)) ) leftErr = true;
    if ( ((motorRightPWMCurr > 100) && (motorRightRpmCurr < -3)) || ((motorRightPWMCurr < -100) && (motorRightRpmCurr > 3)) ) rightErr = true;
  }  
  if (leftErr){
    Console.print("Left odometry error: PWM=");
    Console.print(motorLeftPWMCurr);
    Console.print("tRPM=");
    Console.println(motorLeftRpmCurr);
    addErrorCounter(ERR_ODOMETRY_LEFT);
    setNextState(STATE_ERROR, 0);
  }
  if (rightErr){
    Console.print("Right odometry error: PWM=");
    Console.print(motorRightPWMCurr);
    Console.print("tRPM=");
    Console.println(motorRightRpmCurr);
    addErrorCounter(ERR_ODOMETRY_RIGHT);
    setNextState(STATE_ERROR, 0);
  }
}


Du kannst ja mal testweise den Inhalt der Funktion auskommentieren. Vielleicht hängt das bei Dir mit der geringen Anzahl an Impulsen pro Umdrehung zusammen.
Ist nur eine Vermutung.

VG
Reiner
 
Hallo Allerseits!

Ich habe jetzt

Code:
if ((stateCurr == STATE_FORWARD) &&  (millis()-stateStartTime>8000) ) {
    // just check if odometry sensors may not be working at all
    if ( (motorLeftPWMCurr > 100) && (abs(motorLeftRpmCurr) < 1)  )  leftErr = true;
    if ( (motorRightPWMCurr > 100) && (abs(motorRightRpmCurr) < 1)  ) rightErr = true;
  }

auskommentiert und bin vorerst hochzufrieden. Er mäht wie er soll.
Das Symptom ist behoben, die Ursache leider noch nicht.

LGM
 
Hallo LGM,
falls Du einem Arduino Mega die Steuerung überlässt: nimm mal in der mower.cpp(Odo-Interrupt routine) die ISR_NOBLOCK raus. Dann sollten die sporadischen Odo-fehler und Zuckungen behoben sein.


Code:
//ISR(PCINT2_vect, ISR_NOBLOCK)
  ISR(PCINT2_vect)


Gruess

Chris
 
marcello schrieb:
Ich habe folgende Fragen:
Gibt es Tipps, wie man den totalen Kontrollverlust im Fehlerfall vermeiden kann?
Wie muss ich die Motoren parametrieren, dass trotz Odometrie zeitnah auf Sensoren reagiert wird?
Marcello

Hardware Watchdog... (MAX705 z.B.... kann man sich aber auch aufn Arduino Nano selber programmieren.)
Habe es auch schon mit dem Watchdog des Mega selbst probiert, habe vermutlich aber noch eine fehlerhafte Bootloaderversion drauf...)
Meiner Meinung nach gibt es zu viele Interrupts, was dazu führt, dass das normale "Programm" keine Chance mehr hat, ausgeführt zu werden. (Zombieverhalten)
 
Zuletzt bearbeitet von einem Moderator:
- man sollte die "loopsPerSec" (bzw. den gleitenden Durchschnitt davon) überwachen - ist der zu gering ( in Fehler gehen - bei meinen PCB 1.3 Tests ist genau das sporadisch aufgetreten - Ursache war eine fehlerhafte (bzw. zu lange) I2C Leitung, dadurch ging der "loopsPerSec" (teilweise erst nach einigen Stunden) in die Knie und damit beginnt der Kontrollverlust über den Roboter - ich habe das gerade in den Developer Code eingebaut (Github Master Zweig)
- WatchDog am Mega/Due: hier ist ein Testprogramm welches die WatchDog-Idee umsetzt: https://github.com/Ardumower/ardumower/tree/master/code/tests/watchdog - PCB 1.3 benutzt einen Hardware-Teiler (DIV/2) um die Interrupts der Standard-Motoren zu minimieren
- Azurit 1.0a7 benutzt nur noch einen Odometrie-Kanal um die Interrupts zu minimieren (https://github.com/Ardumower/ardumower/releases) - desweiteren wurde der Interrupt-Code auf ein Minimum reduziert
 
Hallo !
Ich habe gerade massiv probleme mit der Odometrie.. im Prinzip kan mein mower nur die Schleife abfahren oder im Mode 'Rand' ohne odometrie rödeln lassen.
biDir und Lane geht garnicht. Imu und Gps läuft...
Ist es normal beim Kompass test, das er wie auf der perimeterschleife (wedelnd) Nord/süd abfährt ? (Himmelsrichtungen stimmen)

Beim pcb1,3 habe ich die Lötbrücken für odo gem. Video angelegt. Auch ich nutze Lichtschranke und Fächerscheibe.
Aufgefallen ist mir noch, das die RPM (im Odo-setup) nicht dauerhaft angezeigt wird, sondern alle 2sec kurz eingeblendet wird. D.h. der wert wird mit 0.00 angegeben, zeigt kurz 16.t rpm und springt zurück auf 0.00... ich das bei den anderen Motoren (die von Shop) auch so ?
Ich überlege schon die motoren aus dem Shop zu nehmen da diese scheinbar laufen.. erstmal den code wie o.g. übernehmem
 
Ich habe die änderungen vorgenommen und es läuft nichts .

Im lane oder birdir -modus fahrt er über die peri-schleife und bleib stehen (Error ausserhalb peri) nur im ' rand' modus rödelt er ein bisschen un den ecken herum..

Alles in allem SCHEISSE
 
Hallo Uwe,
Ja habe ich..ich bekomme auch keine odometriefehler mehr angezeigt, dennoch bleibt er am perimeterkabel stehen..er bräuchte nur bissel zurückfahren, drehen und weiterfahren, das würde mir reichen. Er bleibt nach dem überfahren 20 cm weiter stehen und fängt nach ca. 20 sek an Error wegen Peri-Outside.
Ich hab die genauen werte eingestellt (Rad vermessen, klicks gezählt) diese werte nach unten und oben korrigiert.. nix

Mit den Shopmotoren läuft er einwandfrei ?

Beim bumperkontakt bleibt er auch stehen..erst wenn ich den bumper (taster) öffne (also robby vom baum wegziehe) kann er wieder fahren.

Nach den Einstellungen läuft er im 'Rand' modus auch nicht mehr... Nur das perimeterkabel kann er sehr zufriedenstellend abfahren.

LG Aleks
 
Hallo Alex,

hast Du kürzlich die Softwareversionen getauscht? Parameter auf Werkseinstellungen? Da sind bei mir schon die merkwürdigsten Dinge passiert.
Ich mache das inzwischen so:
1. In der Konsole Parameter ausgeben lassen
2. Parameterliste im Fenster markieren und mit Strg-C kopieren
3. Neue Textdatei öffnen und Parameter dort einfügen.

So hast Du immer alle deine eigenen Einstellungen gesichert.
Wenn alles soweit läuft kannst du diese Parameter auch als Werksparameter in Deine mower.cpp eintragen ( Im Konstruktor für das Mower Objekt hinter Mower::Mower() ).

VG
Reiner

*** EDIT ***
Bumper ist glaube ich für Bumperduino vorgesehen. Der gibt nur einen Impuls aus, auch wenn der noch igendwo am Baum hängt.
Ich habe da bei mir eine Flankenauswertung eingebaut. Wenn Du da Hilfe brauchst bitte melden.
 
Beim pcb1,3 habe ich die Lötbrücken für odo gem. Video angelegt. Auch ich nutze Lichtschranke und Fächerscheibe.

Wieviel ticks bekommst du pro 100ms?
Bei dieser Konfiguration liefert der Standardmotor ca. 265 ticks/sek bei voller Drehzahl 33U/min.
Das bedeutet, wenn das Signal alle 100ms ausgewertet wird hast du ca. 27ticks/100ms. Wenn du 50% Geschwindigkeit fahren willst, musst du ca. 16ticks/100ms regeln. Das bedeutet, das du 27 Geschwindigkeiten regeln kannst.
Hintergrund:
Ich vermute, dass dein Encoder zu wenig ticks zur Verfügung stellt. Wenn dein Encoder jetzt z.B. nur 6ticks pro 100ms zur Verfügung stellt, kannst du eigentlich nicht viel regeln. Die Sunray Software wertet alle 200ms aus. Die ms bei Azurit weiss aktuell nicht aus dem Kopf..
Wenn tatsächlich so wenig Ticks vorhanden sind, ist es womöglich besser die Zeitabstände der Flanken zu Messen und als Geschwindigkeitswert zu nehmen.
Ist aber aktuell nur eine Vermutung.
 
Hi all.
Again Roland describe pefectly the problem.
In the soft azurit use the calcodometry to know the current motor rpm each 100ms
With a low ticks per rev the current rpm is never accurate the Pid return in motorcontrol is false and the mower can t stop correctly because the pid take a lot of time to compute the currentrpm value=0.
If you want the odometry to go in straight line with low ticksperrev you need a lot of change in the azurit code.
The approch is to record the odo value left and right at the begin of the forward state and use the difference between then to run the pid motor and use 0 as cible.
By this way you are sure that after 10 secondes for example the 2 wheel have turn exactly the same ticks count

In a lot of post i read problem with odometry but note that actualy the use of odometry AND imu in Azurit with Mega is for me not possible and maybe the odo error are solve if you desactivate the IMU.
With the due the loopspersec is 130000 with odo only and fall to 1300 when activate the Imu so with the MEGA .......
So please choose one or the other solution to go in straight line and never the two at the same time.

If you have PCB1.3 change the mega by a Due .

By.
 
Danke..wie soll es anders sein, Ihr hab den richtigen Riecher !

Ich habe heute (gestern vorgestern) meine motoren und Odometrie umgebaut.
Dabei habe ich den IR sensor ins gehäuse verbaut, wo jetzt eher 3000 rpm' s (statt 15) angeboten werden. Zack.. der Robby läuft.
(Macht die Dauer der Unterbrechung wohl was aus ? Der eine motor unterbricht jetzt eine 1/2 umdrehung , der andere ca. 1/⁴ ... Aber ticks/sek sind ja gleich...
IMG_20170819_202141.jpg


IMG_20170819_201850.jpg


IMG_20170819_155825.jpg


Ich habe heute eigentlich nur noch kurz testen wollen.. aber er ist direkt in den Dienst eingetreten :cheer:

Also besser gleich die Shopmotoren nehmen. Ich habe diese Valeo 701.023 motoren genommen, diese müssen recht aufwendig umgebaut werden. Der Motorkörper muss aufgebohrt werden um Überhizung zu vermeiden, kerko's eingebaut werden sonst stören die gewaltig.
Und letztlich fehlt die odometrie ! Womit das projekt zum scheitern verurteilt sein kann. Ohne akkurate odometrie braucht man erst garnicht anfangen. Da gibt es auch keine Umwege, wie es tlw. Im Forum geschrieben wird. Odometrie ist Pflicht beim aktuellen Code.

Danke das Ihr mir den entscheidenen Tip geben konntet.

LG Alex
Attachment: https://forum.ardumower.de/data/media/kunena/attachments/4154/IMG_20170819_202141.jpg/
 
Zuletzt bearbeitet von einem Moderator:
Hi Alex.
Yes you need a lot of change in this kind of motor tu put odometry on it becauce the motor axes are into the body.
Maybe encoder disc from old printer directly on the wheel.

In all case the odometry is actualy use to go in straight line, but the imu can also do this, without odometry.
Never tested in azurit but maybe it's work ?
Tianchen l2700 use only imu (no odo on the motor) and go in perfect straight line so it's possible for me to use your motor without odometry and with imu in random mowing mode.

Depend only of what you want ?

By.
 
Letztendlich ist alles eine Sache der Regelung in der Software. Für die Wegstrecke kann man die gezählten Ticks nehmen. Für die Geschwindigkeitsregelung die Zeitabstände der Flanken messen und über einen Tiefpass schicken. So habe ich das zumindest in meiner ersten Robbiversion 2013 umgesetzt. Der hatte pro Radumdrehung nur 6 Ticks. Musst du allerdings in die Software programmieren.
 
Oben