|
|
# Group 5
|
|
|
|
|
|
## Lab Notebook Lesson 10 - Localization Part 1
|
|
|
|
|
|
**Date:** 25/5 2015, 28/5 2015, 01/6-2015
|
|
|
|
|
|
**Group members participating:** Mikkel Brun Jakobsen, Josephine Raun Thomsen, Daniel Vestergaard og Christoffer Skovgaard
|
|
|
|
|
|
**Activity duration:** 7 hours, 1 hour,
|
|
|
|
|
|
## Goal
|
|
|
Som præsenteret til Lecture 10 er navigation en fundamental evne for en autonom robot. De primære funktioner for navigation er: Localization (Hvor er jeg?), Map Making (Hvor har jeg været?), Mission Planning (Hvor skal jeg hen?) samt Path Planning (Hvad er den bedste rute?) [1]. I denne Lesson beskæftiger vi os udelukkende med Localization - altså hvorledes robotten kan lokalisere sig selv. Det overordnede mål med denne øvelsesgang er at undersøge hvorledes *odometry* og NXT motorens tacho counter kan benyttes til at holde styr på LEGO-bilens position. Vi benytter os af leJOS-klasserne DifferentialPilot samt OdometryPoseProvider til at implementere navigationen. I arbejdet hermed ønsker vi at bestemme nøjagtigheden, samt kalibrere de faktorer der medvirker højere nøjagtighed.
|
|
|
|
|
|
|
|
|
## Plan
|
|
|
Vores plan er at følge guide for Lesson 10 [2]. Derudover har vi benyttet Borenstein et al. [3] som udgangspunkt for hvordan *dead reckoning* (der ud over bilens motorer også benytter bilens retning) implementeres, hvilket er den måde, som vi ønsker vores Lego bil i sidste ende skal kunne navigere på.
|
|
|
|
|
|
## Results
|
|
|
|
|
|
### Odometry
|
|
|
Borenstein et al. beskriver, hvordan dead reckoning kan benyttes af en differential drevet bil (en bil, hvor de to motorer styrer bilen uafhængigt af hinanden), ved at benytte simple geometriske ligninger til at udregne den momentvise position af bilen i forhold til en kendt startposition. Klasserne DifferentialPilot og OdometryPoseProvider benytter sig af disse ligninger, og implementerer derudover metoder til at bevæge bilen og holde styr på bilens position og retning, hvilket betegnes som bilens *Pose*.
|
|
|
|
|
|
I figur 1 nedenfor beskrives de fundamentale ligninger indenfor odometry - det er også disse der benyttes i DifferentialPilot og OdometryPoseProvider.
|
|
|
|
|
|
*Figur 1: Fundamentale odometry-ligninger.*
|
|
|
|
|
|
![Skærmbillede 2015-05-25 kl. 10.00.25](http://gitlab.au.dk/uploads/group-5/group-5-lesson-10/7a493b6681/Sk%C3%A6rmbillede_2015-05-25_kl._10.00.25.png)
|
|
|
|
|
|
Programmet PilotSquare.java benytter metoderne travel() og rotate(). Disse metoder bruges til at få bilen til at bevæge sig i en firkant. For at undersøge nøjagtigheden af programmet (om bilen returnerer til sit udgangspunkt) byggede vi en LEGO-bil, baseret på Express-bot, [4] med et påsat pointer tool, hvorefter vi fik bilen til at afvikle programmet med startopstilling som vist på Billede 1.
|
|
|
|
|
|
*Billede 1: LEGO-bil med pointer tool med start i midten af cirkel.*
|
|
|
|
|
|
![Skærmbillede 2015-06-01 kl. 10.44.46](http://gitlab.au.dk/uploads/group-5/group-5-lesson-10/364784d35a/Sk%C3%A6rmbillede_2015-06-01_kl._10.44.46.png)
|
|
|
|
|
|
Video 1 [9] nedenfor viser en afvikling af SquarePilot uden nogen form for kalibrering.
|
|
|
|
|
|
*Video 1: Afvikling af SquarePilot uden kalibrering.*
|
|
|
|
|
|
[![image alt text](https://img.youtube.com/vi/-gGn66aagvY /0.jpg)](https://www.youtube.com/watch?v=-gGn66aagvY)
|
|
|
|
|
|
Som det ses af videoen afviger robotten med ca. 4 mm fra startpunktet. Videoen viser at bilen er meget præcis i sin udførsel af rotate, da den ender lige på stregen igen. Den afvigelse blev kun forøget ved at vi satte længden på ruten op. Vores indledende forsøg tydede derfor på at det især var travel, der var årsag til afvigelse.
|
|
|
|
|
|
### Calibrate the wheel diameter and the track width
|
|
|
|
|
|
|
|
|
Vores næste opgave er at kalibrere parametrene wheelDiameter og trackWidth for at give LEGO-bilen en højere præcision i udførslen af SquarePilot. Vores fremgangsmåde består i at afprøve hver enkelt ændring i konstanterne 3 gange førend vi ændre dem igen, for at minimere fejlkilder såsom en upræcis startposition. Desuden ændrer vi kun én konstant af gangen, for at kunne danne os et klart billede af hvorledes ændringer manifesterer sig.
|
|
|
|
|
|
Som vist i video 1 ovenfor stemmer programmet ikke nødvendigvis overens med de bevægelser bilen faktisk udfører, og dette resulterer i en afvigelse fra startpositionen på ca. 1 cm på både X- og Y-aksen. Videoen vidner således om fejl i bestemmelsen af bilens position. I undersøgelsen af disse fejlkilder, er det vigtigt at skelne mellem *systematiske fejl* og *ikke-systematiske fejl*. Systematiske fejl kan f.eks. opstå som resultat af forskellig hjuldiameter, afstand mellem hjulene, samt hjulenes tykkelse. Ikke-systematiske fejl kan f.eks. opstå som resultat af uregelmæssigheder i overfladen. Ifølge Borenstein og Feng [5] kan systematiske fejl reduceres væsentligt ved at justere på rutens længde, samt variablerne der fortæller hjulenes diameter og hjulenes indbyrdes afstand. I leJOS DifferentialPilot er det ligeledes muligt at reducere systematiske fejl ved at justere på to parametre: wheelDiameter (hjuldiameter) og trackWidth (indbyrdes afstand mellem hjulene).
|
|
|
|
|
|
#### Justering af wheelDiameter ved rute på 50 cm.
|
|
|
|
|
|
*Video 2: Justering af wheelDiameter - værdi: 5.5*
|
|
|
|
|
|
[![image alt text](https://img.youtube.com/vi/HrLMg_VwLXQ /0.jpg)](https://www.youtube.com/watch?v=HrLMg_VwLXQ)
|
|
|
|
|
|
I justeringen af parametret wheelDiameter, fik vi bilen til at køre på en rute på 50 cm, og justerede parameteren indtil bilen kørte så tæt på præcist 50 cm som muligt. Som tidligere nævnt gennemførte vi hvert forsøg 3 gange, for at korrigere for ikke-systematiske fejl, hvor Video 2 [10] ovenfor viser en demonstration af en kørsel med en wheelDiameter-værdi på 5.5. Foruden værdien på 5.5, gennemførte vi justeringen af wheelDiameter med følgende værdier: 5.55, 5.575 og 5.5765, hvor sidstnævnte værdi fik bilen meget tæt på de 50 cm.
|
|
|
|
|
|
#### Justering af trackWidth ved 180 graders rotering af bilen.
|
|
|
|
|
|
*Video 3: Justering af trackWidth - værdi: 16.1*
|
|
|
|
|
|
[![image alt text](https://img.youtube.com/vi/K4O4xlD5vqw/0.jpg)](https://www.youtube.com/watch?v=K4O4xlD5vqw)
|
|
|
|
|
|
Ligeledes gennemførte vi en justering af parametret trackWidth, hvor bilen skulle udføre en rotation, tættest muligt på 180 grader. Med hvert forsøg gennemført 3 gange, udførte vi justeringen med følgende værdier for trackWidth: 16.0, 16.05, 16.075 og 16.1, hvor sidstnævnte værdi viste sig at give det mest præcise resultat, hvilket ses i ovenstående Video 3 [11].
|
|
|
|
|
|
I [6] beskrives det, hvordan den rette justering af disse parametre kan holde afvigelse i afstand og rotationsvinkel under 2%. For at udfordre bilen, med dens justerede parameterværdier, valgte vi at udvide firkanten til det dobbelte - altså 40 cm på hver længde.
|
|
|
|
|
|
#### Firkant med længere afstand (40 cm*40 cm)
|
|
|
|
|
|
*Video 4: SquarePilot i 40 cm*40 cm firkant, før kalibrering*
|
|
|
|
|
|
[![image alt text](https://img.youtube.com/vi/IRzelG65Dkw /0.jpg)](https://www.youtube.com/watch?v=IRzelG65Dkw)
|
|
|
|
|
|
I ovenstående Video 4 [12] ses det at bilens afvigelse holder sig under en afvigelse på 2 %, da den med sine 160 cm kørt, havde en endelig afvigelse på 2 cm afvigelse i X-aksen og 3 cm afvigelse i Y-aksen (dvs. en afvigelse på 1.57 %). Det observeres yderligere at afvigelsen skyldes at bilen ikke drejede tilstrækkeligt, hvilket vi forsøgte at kompensere for, ved at forøge trackWidth. Ved en justering af TrackWidth, med følgende parameterværdier: 16.1, 16.15, 16.175, 16.255, 16.275, 16.65, 16.625 og 16.6025, opnåede vi resultatet der ses i nedenstående Video 5 [13], med den sidstnævnte værdi.
|
|
|
|
|
|
*Video 5: Kørsel af kalibreret SquarePilot program*
|
|
|
|
|
|
[![image alt text](https://img.youtube.com/vi/vkMlNL2mvr0/0.jpg)](https://www.youtube.com/watch?v=vkMlNL2mvr0)
|
|
|
|
|
|
Med disse ændringer formåede vi med dobbelt afstand at få en fejlmargin på 2,5 mm. Dvs. slutpositionen afviger med ca. 0,15% - dvs. vi befinder os relativt meget under de af [6] foreslåede 2% afvigelse.
|
|
|
|
|
|
Da vi efterfølgende kørte testprogrammet der drejede bilen 180 grader, drejede bilen mere end 180 grader. Dette kan skyldes at bilen drifter til en af siderne mens den kører ligeud, hvilket vi kompenserede for, ved at forøge TrackWidth.
|
|
|
|
|
|
Efter kalibrering af de systematiske fejl gennem justering på hhv. wheelDiameter og trackWidth kunne vi dernæst snakke om at odometry-fejl næsten udelukkende ville skyldes ikke-systematiske fejl. I næste afsnit kigger vi på, hvordan ikke-systematiske fejl kan estimeres.
|
|
|
|
|
|
### Position tracking by means of particle filters
|
|
|
|
|
|
Til at vurdere den indflydelse som de ikke-systematiske fejl har på bilens position benytter vi os af Monte Carlo Localization [8] (også kendt som partikelfilter lokalisering). Som beskrevet i [1] benytter algoritmen *“a particle filter to represent the distribution of likely states, with each particle representing a possible state, i.e. a hypothesis of where the robot is.”*. Detaljer i algoritmen, som baserer sig på en skokastisk bevægelses model, kan ses i [7] . Algortimen resulterer i en partikel sky for en non-sensing robot kan ses af figur 2.
|
|
|
|
|
|
*Figur 2: Figur over distribuering af mulige positioner over flere skridt for en non-sensing robot i to dimensioner*
|
|
|
|
|
|
![Particle2dmotion.svg](http://gitlab.au.dk/uploads/group-5/group-5-lesson-10/a2573be8e8/Particle2dmotion.svg.png)
|
|
|
|
|
|
Programmet PilotMonitor.java implementerer position tracking ved brug af partikefilter, mens den montorerer bilens bevægelser. Bilen afvikler programmet PilotRoute.java, der får bilen til at køre en rute over flere skridt (se figur 3).
|
|
|
|
|
|
*Figur 3: Distribution over mulige positioner ved ruten: travel(100), rotate(90), travel(100), rotate(-90), travel(100).
|
|
|
|
|
|
![Skærmbillede 2015-05-25 kl. 11.36.27](http://gitlab.au.dk/uploads/group-5/group-5-lesson-10/976fc924d0/Sk%C3%A6rmbillede_2015-05-25_kl._11.36.27.png)
|
|
|
|
|
|
|
|
|
PilotMonitor- programmet benytter klassen Particle (se nedenstående figur x), hvilket er den samme som bruges i leJOS MCLParticle, hvor distanceNoiseFactor = 0.05 og angleNoiseFactor = 2.
|
|
|
|
|
|
*Figur 4: Uddrag fra Particle-klassen, som bruges i PilotMonitor.*
|
|
|
|
|
|
![Skærmbillede 2015-05-25 kl. 11.40.11](http://gitlab.au.dk/uploads/group-5/group-5-lesson-10/842c49fe42/Sk%C3%A6rmbillede_2015-05-25_kl._11.40.11.png)
|
|
|
|
|
|
#### Estimering af noise gennem faktorerne distanceNoiseFactor og angleNoiseFactor.
|
|
|
|
|
|
Vi undersøger de to faktorer, ved at lade bilen køre en lille del af ruten. Mere specifikt lader vi den henholdsvist rejse 50 cm og rotere 180 cm. Vi gentager afstands- og roteringsforsøgene hver især 5 gange. Resultaterne for disse eksperimenter kan ses af nedenstående tabeller.
|
|
|
|
|
|
##### Måling af afvigelse af afstand - Standard hjulsætning
|
|
|
|
|
|
*Tabel 1: Resultater over afvigelse af afstand - standard hjulsætning.*
|
|
|
|
|
|
| Forsøg # | X-afvigelse | Y-afvigelse |
|
|
|
| --------------- | ----------- |:-------------: |
|
|
|
| 1 | 1.7 cm | 0.3 cm |
|
|
|
| 2 | 1.8 cm | 0.1 cm |
|
|
|
| 3 | 2.5 cm | 0.05 cm |
|
|
|
| 4 | 1.7 cm | 0.2 cm |
|
|
|
| 5 | 1.7 cm | 0.1 cm |
|
|
|
|
|
|
Da vi vurderede at afvigelsen på X-aksen var systematisk relativt stor, valgte vi at gentage eksperimentet, hvor vi byttede rundt på de to hjul, for at determinere om afvigelsen skyldes en forskel i hjulene.
|
|
|
|
|
|
##### Måling af afvigelse af afstand - Ombytning af venstre og højre hjul
|
|
|
|
|
|
*Tabel 2: Resultater over afvigelse af afstand - Ombyttet hjulsætning.*
|
|
|
|
|
|
| Forsøg # | X-afvigelse | Y-afvigelse | Afvigelse
|
|
|
| --------------------------- | ----------- |:----------: |:----------:|
|
|
|
| 1 | 0.6 cm | 0.2 cm | 0.632455532
|
|
|
| 2 | -0.1 cm | 0.2 cm | 0.2236067977
|
|
|
| 3 | -0.6 cm | 0.4 cm | 0.7211102551
|
|
|
| 4 | -1.0 cm | 0.2 cm | 1.019803903
|
|
|
| 5 | -0.5 cm | 0.4 cm | 0.6403124237
|
|
|
| Gennemsnit | -0.32 cm | 0.28 cm | 0.6474577823
|
|
|
| Faktor (division med 50 cm) | -0.0064 | 0.0056 | 0.0129491556
|
|
|
|
|
|
|
|
|
##### Måling af afvigelse i rotering
|
|
|
|
|
|
*Tabel 3: Resultater over afvigelse af rotering.*
|
|
|
|
|
|
| Forsøg # | Afvigelse |
|
|
|
| ----------------------------------- |:-------------: |
|
|
|
| 1 | 4 grader |
|
|
|
| 2 | 5 grader |
|
|
|
| 3 | 3 grader |
|
|
|
| 4 | 5 grader |
|
|
|
| 5 | 4 grader |
|
|
|
| Gennemsnit | 4.2 grader |
|
|
|
| Faktor (division med 180 grader) | 0.2333 |
|
|
|
| Faktor (korrigeret mht. støttehjul) | 0.02333 |
|
|
|
|
|
|
Bemærk: For at få nedenstående resultater til i højere grad at stemme overens med bilens faktiske bevægelse, gangede vi en faktor 0.1 på angleNoiseFactor. På trods af at bilen konsekvent drejer lidt for langt, vil støttehjulets påvirkelse af kørslen få bilen til at “rette op” igen når den efterfølgende bevæger sig fremad.
|
|
|
|
|
|
#### Eksperimentation med applyMove
|
|
|
|
|
|
Til en eksperimentering med modellen som ses i applyMove (se figur 4) søger vi inspiration i motion modellen som ses i [7].
|
|
|
|
|
|
Vi benytter faktor-værdierne fra ovenstående eksperimenter. Da vi har en faktorværdi for både x-aksen og y-aksen for afvigelse i afstand, beregner vi denne faktor som længden af den manglende side i en trekant, hvor x-aksen og y-aksen udgør de to andre sider.
|
|
|
|
|
|
Udregning af distanceNoiseFactor = (-0.0064)2 + (0.0056)2
|
|
|
angleNoiseFactor = 0.02333
|
|
|
|
|
|
Hvis bilen starter på position (0, 0) med retningsvektor <1, 0> og afvikler følgende:
|
|
|
|
|
|
*Java-kode 1: Bilens rute - applyMove eksperimentering.*
|
|
|
|
|
|
``` Java
|
|
|
for(int i = 0; i < 15; i++) {
|
|
|
travel(10);
|
|
|
rotate(90);
|
|
|
travel(10);
|
|
|
rotate(-90);
|
|
|
}
|
|
|
```
|
|
|
|
|
|
bør den ende op på position (150, 150).
|
|
|
|
|
|
For at undersøge dette opstillede vi et koordinatsystem vha. 4 udleverede A0 ark med påtrykte mål. Vi kunne derfor opsætte en bane, der var 200 cm på y-aksen og 175 cm på x-aksen (se Billede 2 nedenfor).
|
|
|
|
|
|
*Billede 2: Opsætning af bilen i fysisk koordinatsystem
|
|
|
|
|
|
![Skærmbillede 2015-05-25 kl. 14.47.33](http://gitlab.au.dk/uploads/group-5/group-5-lesson-10/dadf3a7bd9/Sk%C3%A6rmbillede_2015-05-25_kl._14.47.33.png)
|
|
|
|
|
|
*Video 6: Eksperiment med applyMove*
|
|
|
|
|
|
[![image alt text](https://img.youtube.com/vi/US80dFA5HsM/0.jpg)](https://www.youtube.com/watch?v=US80dFA5HsM)
|
|
|
Video 6 ovenfor [14] viser en afvikling af den oprindelige motion model (se figur 4).
|
|
|
Denne afvikling producerede følgende mulige partikel positioner for bilen (10 positioner) som vist i Billede 3 nedenfor.
|
|
|
|
|
|
|
|
|
*Billede 3 - Screenshot af PilotMonitor - oprindelig motion model.*
|
|
|
|
|
|
![Originale model](http://gitlab.au.dk/uploads/group-5/group-5-lesson-10/d6a845b7d5/Originale_model.png)
|
|
|
|
|
|
*Billede 4: Bilens endelige placering - afstand fra x-akse og y-akse referencer.
|
|
|
|
|
|
![Skærmbillede 2015-05-25 kl. 13.41.43](http://gitlab.au.dk/uploads/group-5/group-5-lesson-10/97a4eabe9d/Sk%C3%A6rmbillede_2015-05-25_kl._13.41.43.png)
|
|
|
|
|
|
Billede 4 viser bilens endelige position efter afvikling af den oprindelige motion model. Vi benyttede reference stregerne med mål på koordinatsystemet til at aflæse og udregne bilens endelige position. Bilens endelig position blev: (164.6 , 127.6). Positionen afviger derfor en del på både x-aksen (+14.6) og y-aksen (-22.4).
|
|
|
|
|
|
Den oprindelige motion model er ikke specielt virkelighedstro. F.eks. vil der blive lagt forskellige mængder støj på henholdsvis x- og y-aksen alt efter hvad bilens heading er. Vi har lavet om på modellen (inspireret jvf. [7]) og er i stedet kommet frem til følgende nye motion model (se Java-kode 2 nedenfor). Modellen er essentielt set den samme som [7], men undladt de absolutte støj faktorer.
|
|
|
|
|
|
*Java-kode 2: Modificeret motion model.*
|
|
|
|
|
|
``` Java
|
|
|
public void applyMove(Move move, float distanceNoiseFactor, float angleNoiseFactor) {
|
|
|
float theta = pose.getHeading() +
|
|
|
move.getAngleTurned() +
|
|
|
move.getAngleTurned() * angleNoiseFactor * (float) rand.nextGaussian();
|
|
|
|
|
|
float dx = move.getDistanceTraveled() * (float) Math.cos(Math.toRadians(theta)) +
|
|
|
move.getDistanceTraveled() * distanceNoiseFactor * (float) rand.nextGaussian();
|
|
|
|
|
|
float dy = move.getDistanceTraveled() * (float) Math.sin(Math.toRadians(theta)) +
|
|
|
move.getDistanceTraveled() * distanceNoiseFactor * (float) rand.nextGaussian();
|
|
|
|
|
|
pose.setLocation(pose.getX() + dx, pose.getY() + dy);
|
|
|
pose.setHeading(theta);
|
|
|
}
|
|
|
```
|
|
|
|
|
|
Kørslen af PilotMonitor producerer nu følgende resultat (se Billede 5 nedenfor):
|
|
|
|
|
|
*Billede 5: Screenshots af PilotMonitor - Modificeret model*
|
|
|
|
|
|
![Skærmbillede 2015-05-28 kl. 14.46.19](http://gitlab.au.dk/uploads/group-5/group-5-lesson-10/d74a6690c8/Sk%C3%A6rmbillede_2015-05-28_kl._14.46.19.png)
|
|
|
|
|
|
Dette resultat stemmer meget mere overens med hvordan vi observerede at bilen bevægede sig, hvilket altså beretter om en mere nøjagtig model.
|
|
|
|
|
|
### Position tracking while avoiding objects
|
|
|
|
|
|
|
|
|
Som non-sensing vil LEGO-bilen ikke være i stand til at undvige forhindringer på dens rute. Hvis LEGO-bilen derfor skal være i stand til at bevæge sig på en fikseret rute bestående af afstande og roteringer og *samtidigt* være i stand til at undgå kollisioner med fremmede objekter, er vi nødt til at gøre LEGO-bilen sansende. Vi påmonterede derfor en afstandssensor, som er i stand til at detektere objekter foran bilen. Nedenstående Billede 6 viser den konstruktion vi benyttede til at den form for positionering.
|
|
|
|
|
|
*Billede 6: Påmonteret afstandssensor.*
|
|
|
|
|
|
![IMG_1446](http://gitlab.au.dk/uploads/group-5/group-5-lesson-10/fb0f558449/IMG_1446.JPG)
|
|
|
|
|
|
Vi lavede en ny klasse “AvoidPilot” hvis ansvar er at følge en liste af waypoints mens den holder styr på hvor i verden den er, samtidig med at den kan undgå små objekter der bliver sat i vejen. Vi realiserede dette ved brug af DifferentialPilot klassens travel og rotate metoder (hvor immediateReturn er sat til true). Hvis ultralydssensoren midt under et travel mener at der er en forhindring i vejen forsøger bilen at bevæge sig uden om denne ved hjælp af en open-loop subprocedure (der ligeledes bruger DifferentialPilot). Idéen er illustreret vha. Figur 5 nedenfor:
|
|
|
|
|
|
Figur 5: Illustration af bilens faktiske rute i forhold til den tiltænkte rute ved forhindring.
|
|
|
|
|
|
![Skærmbillede 2015-05-25 kl. 14.56.31](http://gitlab.au.dk/uploads/group-5/group-5-lesson-10/8d4c5c0a00/Sk%C3%A6rmbillede_2015-05-25_kl._14.56.31.png)
|
|
|
|
|
|
*Video 7: Demonstration af undvigelse af objekt*
|
|
|
|
|
|
[![image alt text](https://img.youtube.com/vi/kc7WWqFOf2g/0.jpg)](https://www.youtube.com/watch?v=kc7WWqFOf2g)
|
|
|
|
|
|
Som set i Video 7 [15] ovenfor er bilen i stand til at undvige det danske flag som står midt på bilens planlagte bane. Bilen er programmeret til at undvige ved følgende fremgangsmåde: Detektér en forhindring → Roter 90 grader → Kør ligefrem 20 cm → Roter -90 grader → Kør ligefrem 40 cm → Roter -90 grader → Kør ligefrem 20 cm → Roter 90 grader → Genoptag ruten. Bilens nuværende programmering kan dog ikke foretage undvigemanøvren hvis der ikke er tilstrækkelig afstand inden den skal dreje (se figur 5), dvs. mindst 40 cm førend svinget. Ligeledes, som set i videoen, rammer bilens bagende ind i forhindringen - hvorved der tydeligvis er mulighed for optimering af undvigemanøvren.
|
|
|
|
|
|
AvoidPilot klassen kan findes i vores [repository](https://gitlab.au.dk/group-5/group-5-lesson-10/blob/b62b7e1f98050c5ad707bd544278359948ad53bf/Lesson%20A%20-%20Localization/src/PilotAvoid.java).
|
|
|
|
|
|
Hvis vores bil havde kendt til den eksakte position af diverse forhindringer på dens route, vil den kunne bruge disse til at præcisere sit gæt om hvor i verden den er.
|
|
|
|
|
|
## Conclusion
|
|
|
|
|
|
|
|
|
Vi har i denne lesson arbejdet med anvendelse af odometry på en LEGO bil for at give bilen en bevidsthed om hvor den befinder sig: Localization. I forbindelse hermed justerede vi på to parametre: bilens hjuldiameter og den indbyrdes afstand mellem hjulene, for at reducere de systematiske fejl, og dermed opnå bedst mulig resultat med dead reckoning positionering. For at kunne ræsonnere omkring ikke-systematiske fejl har vi ligeledes eksperimenteret med partikelfiltre. Den udleverede partikel filter model, som benyttes i PilotMonitor, havde nogle mangler som vi har forsøgt at rette op på i vores egen motion model, som er inspireret af Wikipedia’s Monte Carlo Localization motion model.
|
|
|
Som sidste led i denne lesson arbejde vi med hvorledes vi kunne undgå forhindringer på bilens bane - her implementerede vi en funktionalitet baseret på en ultralydssensor som var i stand til køre udenomkring eventuelle forhindringer. Her erfarede vi at der i vores nuværende undvigelsefunktionalitet opstår begrænsninger i bilens evne til at navigere gennem en prædefineret rute, og at vi bør arbejde videre på at optimere dette.
|
|
|
|
|
|
|
|
|
## References
|
|
|
|
|
|
[1] Caprani, Ole. Lecture 10, 21/05-2015.
|
|
|
|
|
|
[2] Lesson 10 - http://legolab.cs.au.dk/DigitalControl.dir/NXT/Lesson10.dir/Lesson.html.
|
|
|
|
|
|
[3] Borenstein, Everett and Feng, Where am I? Sensors and Methods for Mobile Robot Positioning, University of Michigan, 1996.
|
|
|
|
|
|
[4] Express-bot instructions: http://nxtprograms.com/9797/express-bot/index.html
|
|
|
|
|
|
[5] Borenstein and Feng, Measurement and correction of systematic odometry errors in mobile robots, Robotics and Automation, IEEE Transactions on (Volume:12 , Issue: 6 ), 1995.
|
|
|
|
|
|
[6] leJOS Tutorial: Controlling Wheeled Vehicles: http://www.lejos.org/nxt/nxj/tutorial/WheeledVehicles/WheeledVehicles.html
|
|
|
|
|
|
[7] Monte Carlo Localization, Particle2Dmotion, Wikipedia: http://commons.wikimedia.org/wiki/File:Particle2dmotion.svg
|
|
|
|
|
|
[8] Monte Carlo lokalisering, Wikipedia: http://en.wikipedia.org/wiki/Monte_Carlo_localization
|
|
|
|
|
|
[9] Video 1 - https://www.youtube.com/watch?v=-gGn66aagvY
|
|
|
|
|
|
[10] Video 2 - https://www.youtube.com/watch?v=HrLMg_VwLXQ
|
|
|
|
|
|
[11] Video 3 - https://www.youtube.com/watch?v=K4O4xlD5vqw
|
|
|
|
|
|
[12] Video 4 - https://www.youtube.com/watch?v=IRzelG65Dkw
|
|
|
|
|
|
[13] Video 5 - https://www.youtube.com/watch?v=vkMlNL2mvr0
|
|
|
|
|
|
[14] Video 6 - https://www.youtube.com/watch?v=US80dFA5HsM
|
|
|
|
|
|
[15] Video 7 - https://www.youtube.com/watch?v=kc7WWqFOf2g
|
|
|
|
|
|
[16] Repository:
|
|
|
https://gitlab.au.dk/group-5/group-5-lesson-10/tree/master |