2005:185 civ master's thesis laser guided vehicle

46
2005:185 CIV MASTER'S THESIS Laser Guided Vehicle Java and MATLAB for Control Bengt Gunnarsson Luleå University of Technology MSc Programmes in Engineering Department of Computer Science and Electrical Engineering Division of Robotics and Automation 2005:185 CIV - ISSN: 1402-1617 - ISRN: LTU-EX--05/185--SE

Upload: others

Post on 24-Dec-2021

4 views

Category:

Documents


0 download

TRANSCRIPT

Page 1: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

2005:185 CIV

M A S T E R ' S T H E S I S

Laser Guided VehicleJava and MATLAB for Control

Bengt Gunnarsson

Luleå University of Technology

MSc Programmes in Engineering

Department of Computer Science and Electrical EngineeringDivision of Robotics and Automation

2005:185 CIV - ISSN: 1402-1617 - ISRN: LTU-EX--05/185--SE

Page 2: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

Laser Guided Vehicle;

Java and MATLAB for Control

Bengt Gunnarsson

Page 3: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

Abstract

This study addresses the generic problem of navigating a robot betweenobstacles. The experimental case tested here is driving through doorways,which can be seen as a special case of a junction between corridors. Therobot used was the MICA wheelchair. On-board there is a scanning lasertilted downwards, a fiber optic gyro and odometric encoders. From the laserscan walls and the door are found using the Hough/Radon transform. Theresults with the control law used gave a standard deviation of 1.4 cm forthe lateral error and 2.2 degrees in angle. This can be improved by tuningof control law. The programming was mainly done in Java. Java methodscan be integrated in a MATLAB script. MATLAB and Java together wasfound to be an excellent test-bed for designing and testing algorithms. Allcomputations was done in real-time. A long term goal in robotics is to fusetogether many sensors into one platform and make a multipurpose vehicle.

Keywords: Java, MATLAB, Tilted scanning laser, Hough transform, Corri-dor junctions, Doorway, Real-time control.

Page 4: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

Contents

1 Introduction 11.1 Background . . . . . . . . . . . . . . . . . . . . . . . . . . . . 11.2 Some Goals . . . . . . . . . . . . . . . . . . . . . . . . . . . . 11.3 Notations . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 2

2 The MICA Wheelchair 32.1 The Mobile Robot . . . . . . . . . . . . . . . . . . . . . . . . 32.2 The Scanning Laser . . . . . . . . . . . . . . . . . . . . . . . . 42.3 The Implementation Languages . . . . . . . . . . . . . . . . . 52.4 Computer and Communication . . . . . . . . . . . . . . . . . 52.5 Transformation and Rotation . . . . . . . . . . . . . . . . . . 5

3 Extracting Geometric Parameters from the Laser Scan 93.1 The Hough/Radon Transform . . . . . . . . . . . . . . . . . . 93.2 Zooming in the Hough/Radon Transform . . . . . . . . . . . . 103.3 Extracting Valuable Information from the Hough/Radon Trans-

form . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 12

4 Geometry, Object Labeling and Control; A Prestudy 144.1 Geometry and Object Labeling . . . . . . . . . . . . . . . . . 144.2 Kinematic Motion Models . . . . . . . . . . . . . . . . . . . . 154.3 Control Law . . . . . . . . . . . . . . . . . . . . . . . . . . . . 16

5 Navigating Through Junctions 185.1 The Kalman Filter . . . . . . . . . . . . . . . . . . . . . . . . 185.2 Extensions to Junctions . . . . . . . . . . . . . . . . . . . . . 205.3 Control Law . . . . . . . . . . . . . . . . . . . . . . . . . . . . 22

6 Navigating Through Doors 246.1 Laser Measurements . . . . . . . . . . . . . . . . . . . . . . . 246.2 The Innovation Process . . . . . . . . . . . . . . . . . . . . . . 24

i

Page 5: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

6.3 Time Analysis . . . . . . . . . . . . . . . . . . . . . . . . . . . 266.4 Error when Driving Through Doors . . . . . . . . . . . . . . . 28

7 Evaluation and Discussion 337.1 Evaluation . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 337.2 Discussion . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 337.3 Future work . . . . . . . . . . . . . . . . . . . . . . . . . . . . 33

A Appendix: Tolerances for Passing Between Two Obstacles 35A.1 Representation of the Door . . . . . . . . . . . . . . . . . . . . 35A.2 Cylinder . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 35A.3 Wall . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 37A.4 One wall, One Cylinder . . . . . . . . . . . . . . . . . . . . . . 37

ii

Page 6: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

Chapter 1

Introduction

1.1 Background

A lot of work has been put into improving the system on the MICA (MobileInternet Connected Assistant) wheelchair work the past few years. One sys-tem is fully implemented and developed, the LazerwayTM. The new systemhas the SICK LMS200 laser on-board. The real test has now been to makeevery component on the robot work together. Not only just work together,but improve the performance aswell. One of the challenges is to make allsensors act together with good synchronization and a small time delay.

A lot of the focus has been on making sensors work independently of eachother on the robot, and a system for retrieving the data. Then of course thetesting phase, to make sure that each sensor works properly.

The things left to do is to test all sensors together and make a completealgorithm for navigating with the sensors. The most intuitive starting pointis to make the robot go through corridors, and through doorways.

1.2 Some Goals

One long term goal behind this MSc. thesis is modeling of system integrationwhen lasers is the key sensors. Topics listed at the start was

• Drive through a corridor.• Be able to drive through a doorway.• Analyze the repeatability of the trajectory.• Drive around a corner in the corridor, or junctions of multiple corners.

Page 7: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

1. Introduction 2

• Another goal is to get the robot to be able to avoid driving into crap inthe corridor.• Analyze Laser alignment error.• Error analyze, compare test and modeling.• Time error behavior. Time synchronization and time delay.• Measuring errors and calibration errors.• Scene interpretation error.• Dead reckoning error.

1.3 Notations

Symbols and abbreviations.

MICA Mobile Internet Connected Assistant.W-LAN Wireless Local Area Network.GPS Global Positioning System.

αtilt Angle which the SICK laser is tilted towards the floorθR Angle from the Hough transform representing

the right walls angular position relative the robot.θL Same as θR but derived from the left wall.γL,γR Angle of robot relative to the corridor.dR Distance to the right wall, derived from the Hough transform.dL Same as dR, but for the left wall.α Angle of the steering wheel.v Velocity of the robot.vs Velocity of the robots steer wheel.vR,vL Velocity of right respectively left drive wheel.ω Angular velocity of the robot.L Length to the steer wheel from the center of rotation.l Distance between two drive wheels.X State vector.Xp Predicted state vector.C Covariance matrix.Rp Predicted covariance.F System matrix.U Input vector.

Page 8: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

Chapter 2

The MICA Wheelchair

A short introduction of the MICA wheelchair follows; The robot is built onan ordinary wheelchair chassis of make Boden Rehab. The communicationsbetween the encoders, gyro and control unit is built on a CAN-bus. TheSICK LMS200 laser communicates on a serial interface. The communicationbetween the robot and the user is based on W-LAN, IEEE 802.11b. A PC104-computer on the robot handles the communications with the sensors. ThePC104 is an ordinary computer but has a aluminium frame and has a smallerformat than an ordinary PC. It is built to be used in the industry where thedemands for durability is much higher. The operating system used is LinuxRed Hat 7.2.

2.1 The Mobile Robot

The robot used is the MICA wheelchair see figure 2.1. The MICA wheelchairshould here be seen as a test-bed for various equipment. The sensors used inthis study is

• SICK LMS200 range scanning laser.• The original odometric wheel encoders.• KVH-ECORE 1000 fiber optic rate gyro.

The position data updating frequency is 20 Hz. The position update rateis faster than the laser updating. The position can be calculated seperatelywith dead reckoning. However, every 0.2 s the position estimate should geta correction based on the laser data.

Page 9: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

2. The MICA Wheelchair 4

Figure 2.1: The MICA Wheelchair.

2.2 The Scanning Laser

The SICK LMS200 is a range scanning laser. It is possible to change a num-ber of parameters in the laser, dependig of the application. The maximummeasured range is limited to 80 meters, the possible settings are 8 or 80 me-ters. It can use a angular resolution of 0.5◦ over 180◦ or 0.25◦ over 100◦. Thesetting used in this work is 0.5◦ over 180◦.

The update interval of the laser is 5 Hz. The laser gives a new scan every0.2 s. A good starting point would be to use every laser scan, this meansthat every loop with calculations, updating the position should not take morethan 0.2 s.

Page 10: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

2. The MICA Wheelchair 5

2.3 The Implementation Languages

The implementation is done in Mathworks MATLAB 6.5.1. Matlab has sup-port for Java. The parts that are computationally expensive could withbenefit be made in Java. Matlab is also a great tool for matrix calculations.It also gives great possibilities for plotting data, for making graphs in bothtwo and three dimensions etc.

The server software on the PC104 on the wheelchair is written in C++.The server communicates with Matlab through Java methods. New Javamethods are easily implemented. To make a new module that is based on anew algorithm is easy to do.

One of the disadvantages with Matlab is that it is slow since it is interpretingthe code, especially when using plot functions. To speed up calculations it ispossible make the algorithms in Java. If that is not sufficient there is possibleto go another step and compile the java code to machine code. If this still isnot enough there is something wrong/inefficient with the algorithm or morecomputer power would be necessary.

2.4 Computer and Communication

The computer on the MICA wheelchair is a PC104 with a 266 MHz Pentiumprocessor. It has 64 Mb RAM and has three gigabyte of harddisk space.

The encoders, gyro and control unit are connected by CAN-bus. The SICKLMS200 laser is connected on a serial interface.

The PC104 has a PCMCIA slot where a standard IEEE 802.11b WLANcard is attached. The processing of data from the sensors can be made onanother computer connected by WLAN. One of the advatages is that theprocessing, calculations can be made on a much faster computer than theone on the robot. One of the disadvatages is that it takes some time to senddata back and forth between the user and the robot.

2.5 Transformation and Rotation

The SICK LMS200 laser is mounted on the back support of the seat on theMICA wheelchair. The laser unit is slightly misaligned. By using a rigidsurface, part of the robots framework, a transformation matrix could be

Page 11: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

2. The MICA Wheelchair 6

derived and used for correction. See figure 2.2. The αtilt can be calculated

Figure 2.2: The laser is misaligned on the robot in several directions. Thetilt angle is often disturbed since it is very easy to change it. This means thatthe tilt is not fixed to 20.3o.

by

αtilt = arcsin

(

heightlaser

lengthlasertofloor

)

(2.1)

Here the range from laser to the floor is calculated by analyzing a scan. Theheight of the laser with its current placing is 1.25 m, see figure 2.3. The tiltangle can be changed. These adjustment parameters is relative to the robot.However, the robot in its turn can be tilted or is tilted in several directions.This is because of the wheels that are air-filled, and its hard to keep theinflation/load constant. Just by driving it from indoor to outdoor on a coldday will probably misalign the laser, as well as a flat tire.

When taking into consideration that the laser is not mounted straight andthat it is tilted. The following misalignment angles was found

• 20.3o around the X-axis.• 1.7o around the Y-axis.• 2.0o around the Z-axis.

Page 12: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

2. The MICA Wheelchair 7

Figure 2.3: The Laser is put 35 cm from the COR - Center Of Rotation alongthe Y-axis of the robot. The Laser is also located 1.25 meters above the floor.

This results in the three rotational matrices below

RX (1.7o) =

cos(

1.7·π180

)

0 sin(

1.7·π180

)

0 1 0

− sin(

1.7·π180

)

0 cos(

1.7·π180

)

(2.2)

RY (αtilt) =

1 0 00 cos (αtilt) − sin (αtilt)0 sin (αtilt) cos (αtilt)

(2.3)

RZ (2.0o) =

cos(

2.0·π180

)

− sin(

2.0·π180

)

0

sin(

2.0·π180

)

cos(

2.0·π180

)

0

0 0 1

(2.4)

These three rotational matrices could of course be multiplied together to onecorrection matrix. These matrices should not be derived manually, since theychange almost from day to day.

Page 13: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

2. The MICA Wheelchair 8

Figure 2.4: Example of a corrected scan, but not translated, as seen only inthe range of four meters the scan is around 0.2 m wrong in the X-axis becauseof the yaw, pitch and roll offset.

The calibration matrices can be found by looking at the floor. And thenrotating in a clear room/corridor. Using the Hough/Radon lines found willbe sufficient to adjust the laser in all directions.

Page 14: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

Chapter 3

Extracting GeometricParameters from the LaserScan

The best way to extract linear segments in a laser scan is to use the Hough/Radontransform. Walls and other planar surfaces such as doors becomes easy tofind. If it then is know where the object is that is tracked. Then it is possibleto make the Hough/Radon transform work faster.

3.1 The Hough/Radon Transform

The Hough/Radon transform is based on the equation for a line. Consider aline at distance d and angle θ of the normal. On this line there is a numberof points (xi, yi). Then

d = xi · cos (θ) + yi · sin (θ) (3.1)

Where x and y is taken directly from the scans. The Hough/Radon trans-form counts all the points at an certain angle θ and at a distance d and inan predefined stripe from that distance, in this case 1 cm. d restricted to aninterval [0, 8] and θ is also restricted to an interval [0, 2 · π].

Systematically go through these intervals in a loop and build up an matrix,where the highest peaks represents an distance and an angle where there isa straight line. Also, the floor is always on the same place in the scan, anddepends of tilt of the laser. This makes it easy to remove some irrelevantdata from the scan in a early stage of the algorithm.

Page 15: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

3. Extracting Geometric Parameters from the Laser Scan 10

Figure 3.1: The Hough/Radon transform counts all the points at an certainangle θ and at a distance d and in an predefined stripe from that distance, inthis case 1 cm

3.2 Zooming in the Hough/Radon Transform

To be able to zoom in the Hough/Radon transform is needed. Since, thelaser can measure up to 80 meters and if reasonable resolution is wanted, theHough/Radon matrix could be unnecessary large. If a length resolution offive centimeters in length and 0.5 degrees of the angular resolution. Then theHough/Radon matrix will consist of 80

0.05·360

0.5≈ 1.2·106 elements. If the length

resolution is made smaller, the time needed to extract the Hough/Radon ma-trix still will be rather long. Longer than the 0.2 s time that it takes to geta new laser scan.

The computation time of the Hough/Radon transform can be pretty longin worst case. The solution was first of all to write the Hough/Radon trans-form in Java. With the inputs, the laser scan and an array with lengths andangles. Where suspected objects are located. This window could be used toextract objects at a certain distance and angle.

Page 16: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

3. Extracting Geometric Parameters from the Laser Scan 11

Figure 3.2: The Hough/Radon transform for the measurements in figure 2.4.Where the three tops represents two walls and the floor. The rightmost topbelongs to the leftmost since the is some wrap-around because of the fact thatsin (2 · π) = sin (0).

If a large window is used, and if two(or more) peaks are suppose to be inthat area. Then remove the first peaks laser scan points, and then start overwith the remaining laser scan points.

Benefits of Zooming the Hough/Radon Transform

The Hough/Radon transform is modified to be able to check any distancesand angles. It is possible to use Rp , the predicted covariances in a Kalmanfilter

Rp = H · Cp · HT (3.2)

For each of the parameters in the Kalman filter to reduce the search area inthe Hough/Radon matrix. This windowing function could easily reduce thecalculation time up to ten times. This is a part of figure 3.2 same resolution,

Page 17: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

3. Extracting Geometric Parameters from the Laser Scan 12

Figure 3.3: This is the a part of figure 3.2 and it is the leftmost top. It isjust −10o to 10o and the distances is 1.1 to 1.3 meters.

but only 20 degrees and 2 dm instead of 0 to 8 meters and 360 degrees. If itis known where a wall is within say 20 degrees and 2 dm there is no need tocompute the whole Hough/Radon area. That is the the main disadvantageis that no new surfaces will be found this way. A complementing functionfor finding new objects has be made.

3.3 Extracting Valuable Information from the

Hough/Radon Transform

To find the right and left wall of a corridor is based on the fact that they areparallel to each other.

γL − γR = 180◦ (3.3)

Page 18: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

3. Extracting Geometric Parameters from the Laser Scan 13

Although, it is required that the robot starts with two walls left and rightdefined. The deviation from the zero angle of the corridor respectively thedeviation from the middle point can be calculated by

θ =γL + γR

2(3.4)

and

y =dL − dR

2(3.5)

It is of course so that a filter of some sort has to be applied to take care ofany spuriouses, preferably a Kalman filter.

Page 19: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

Chapter 4

Geometry, Object Labeling andControl; A Prestudy

This chapter will describe the basic geometry and kinematic models to beused to control the robot. We start up with the simplest case, driving in acorridor. At this point there will be no obstacles present in the corridor.

4.1 Geometry and Object Labeling

Basically the goal is to find a feedback law from laser measurements in such away that the robot drives automatically between objects. The simplest caseis a corridor with right and left walls.

The approach to the more general case is the following; We consider the fol-lowing steps:

1. A scene/workplace with several objects.

2. Local range sensing in the forward direction of the moving robot.

3. A decision on how to locally pass between the objects.

4. Based on this decision a labeling of the objects with respect to Right(R)or Left(L) of the planned trajectory.

5. Polygons of straight lines can be used to describe the Right(R) and Left(L)envelops. Indoors, the Range Weighted Hough/Radon transform gives a nat-ural input in many cases.

Page 20: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

4. Geometry, Object Labeling and Control; A Prestudy 15

Figure 4.1: Robot at pose (x,y,θ) in a corridor. The steering wheel(dog) isdirected α towards the aiming point(rabbit) in the middle of the corridor.

6. The distance transform gives a general method for planning the trajectory.This is not studied in this report.

7. The simplest case above is a corridor. The suggested control systemshould have some generality. If we, say, want the robot to turn around inthe corridor the input to the control system should just be a relabeling R →

L and L → R of the walls.

4.2 Kinematic Motion Models

The MICA wheelchair has motors on both of its front wheels. The backcaster wheels are only there as support wheels. This means that the robot

Page 21: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

4. Geometry, Object Labeling and Control; A Prestudy 16

can rotate around its own axis, when one wheel drives forward and the otherwheel drives backwards.

Next we are to describe the basic control law of the robot. Thus consider arobot with a real or virtual steering wheel at distance L in front of the twofixed wheels.

The steering wheel angle is α and the velocity of the steering wheel is vs.Then the robots velocity will be

v = vs · cos α (4.1)

and the angular velocity of the robot will be

ω =(

vs

L

)

· cos α (4.2)

For a robot with motors on both fixed front wheels we have

v =(vR + vL)

2(4.3)

ω =(vR − vL)

l(4.4)

where l is the distance between the two drive wheels. The two sets of equa-tions are just alternative descriptions. [2] gives more details.

4.3 Control Law

When driving in a corridor, laser measurements of the walls will generatevery clear peaks in the Hough transform.

If the robot is suppose to travel in the middle of the corridor, then thewalls should be located at the same distance and be parallel to the directionof travel. This can be used to design a control law.

The control systems task will be to control the robot based on the two mostsignificant peaks in the Hough transform. The peaks should be located atthe same distance, and have the angles γR = −90o and γL = 90o. To furtherimprove the accuracy the least square line fitting is applied to the points inthe wall stripe returned by the Hough transform.

Page 22: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

4. Geometry, Object Labeling and Control; A Prestudy 17

The resulting approximation is dL,dR and γL, γR shown in figure 4.1 above.

The robots position and orientation relative to the corridor is given by

y =dR − dL

2(4.5)

θ =γL + γR

2(4.6)

This control law was tested in an earlier master thesis here in Lulea[7]. Thesteering along the middle line in the corridor is made by a control law usedin “Mobile Robot Navigation using the Range-weighted Hough transform”[2].

Another control law that have been used is the “dog-rabbit” control law.

Page 23: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

Chapter 5

Navigating Through Junctions

This chapter will describe the basic equations needed to navigate along acorridor and through junctions of corridors. Passing through doors i alsoconsidered. The parameters are essentially as in the Hough/Radon trans-form.

5.1 The Kalman Filter

Consider a corridor with two walls and a Kalman filter with four states

Xk =[

dL γL dR γR

]

(5.1)

where γL and dL is the angle for the wall respectively the distance. The an-gles are measured counter-clockwise from the robots frame, compare figure4.1 above.

The process model is updated as

Xk+1 = F · Xk + Gk · Uk (5.2)

where Xk is the current position data. The control during the interval τ s.

Uk =[

v ω]

· τ (5.3)

where v is the velocity and ω is the angular velocity. Depending on the typesof robots v and ω are given by equations 4.1 to 4.4 above.

The input matrix G equals

G =

sin(γL) 00 −1

sin(γR) 00 −1

(5.4)

Page 24: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

5. Navigating Through Junctions 19

Figure 5.1: Corridor with a change of direction and/or width. When thelaser sees this combination of two corridors, we need to extend the state inequation 5.1 to eight variables.

and F is the system matrix which is a four by four unit matrix

F =

1 0 0 00 1 0 00 0 1 00 0 0 1

(5.5)

The filter is updated every 200 ms, i.e. τ = 0.2s.

Observe that if we have a “perfect corridor” the estimation of dL and dR

will have a strong (negative) correlation, since dL + dR is equal to the widthof the corridor. There will also be a similar strong correlation between γL

and γR.

Page 25: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

5. Navigating Through Junctions 20

Figure 5.2: A 90o “turn” of a corridor. Is also a simplification of normalorthogonal corridor junctions.

5.2 Extensions to Junctions

figure 4.1 and the equations above are for estimating the position of thepeaks in the Radon/Hough transform. In this subsection we describe howthis basic equation can be extended to junctions, open doors etc.

The simplest case is in figure 5.1 when the corridor changes direction and/orwidth. If we use the Kalman filter described above the new walls will notbe accepted Inside the association gate. Depending on the control law/rulethe robot will stop or run into the new (left) wall. To handle such cases thestate vector in equation 5.1 should be extended with new “walls” (describedby distances d and angles γ) as they are found by the laser. We leave theexplicit equations for G and F to the reader.

Page 26: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

5. Navigating Through Junctions 21

Figure 5.3: This is an example of an open door in the right side of thecorridor. This is the case tested in the next chapter. Note, in this case arethe two line segments to the left not connected - there is a gap.

For both the case in figure 5.1 and in figure 5.2 the laser can observe twowalls left of the planned trajectory. The state vector is then

X =[

dL1γL1

dL2γL2

; dR γR

]

(5.6a)

When the robot moves on there will also be an extension of the X for asecond wall to the right giving

X =[

dL1γL1

dL2γL2

; dR1γR1

dR2γR2

]

(5.6b)

The case with the open door in figure 5.3 can be described in the same wayas equation 5.6 above. The main difference is that the two line segments L1

and L2 are not connected. Note that the angle γL2will in this case initially

be negative.

Page 27: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

5. Navigating Through Junctions 22

5.3 Control Law

There is a range of possibilities for designing control laws to our problem ofnavigating between objects. The choices stood between a dog-rabbit controllaw and more smooth one that is the one used. A Dog-Rabbit control law

Figure 5.4: The navigation between two objects is described by a pair ofreference points and a steer line in between. The reference points put on thetwo walls/objects, and the “steer-line” in between the objects. The propertiesof the control between the points depends on the robot and can be tuned bythe gains k1 and k2 in equation 5.8

has large disadvantages in that it is slow and cuts corners or after tuningproduces a large overshoot. It is not preferred in this case since we wantone control law for all cases studied. Several geometrical cases are given inAppendix 1. Expressed in laser coordinates, the angle to the point in betweenthe two objects

θ =γR + γL

2(5.7)

The robot will then always strive to go to the line that goes orthogonal to aline between the reference points. Where the angle of the steer wheel will be

α = − arctan

(

k1 ·dR − dL

2+ k2 · sin (θ)

)

− θ (5.8)

If we interpret figure 4.1 we get that

k1 =1

d(5.9)

Page 28: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

5. Navigating Through Junctions 23

k2 =L

d(5.10)

This control law is also useful in other cases, since it is possible to put thereference points on any object. For example a corner or on a door opening.

Page 29: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

Chapter 6

Navigating Through Doors

This chapter is on navigating through doors. The navigation through doorsis essentially the same as navigating in junctions. There are some differences.In a junction the new corridor is most often orthogonal to the corridor fromwhich the robot are leaving. The open door into the hall could be open atdifferent angles. Another difference is the fact that a doorway is narrowerthan a corridor, so the error has to be low when navigating through a door.

6.1 Laser Measurements

The case studied is illustrated in figure 6.1. The corresponding laser scan isplotted in figure 6.2. The thickness of the door can not be ignored. In thiscase the door is six centimeters thick. If the door thickness is ignored and thedoor is open at a large angle the crossing point of the two “Hough/Radonlines” will be moved

E =0.06

sin (θdoor)(6.1)

If the door is even thicker the error will increase faster if not taken intoconsideration. Although, if the door is open at 90 degrees the error will bezero.

6.2 The Innovation Process

The first step in this evaluation of the result is to analyze the innovationprocess. This is “some kind of testing the internal consistency” of the modeland measurements.

Page 30: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

6. Navigating Through Doors 25

Figure 6.1: Picture taken from the position of the laser.The correspondinglaser scan is plotted in figure 6.2

The innovation is defined as the difference between the predicted values andthe measured values. In figure 6.3 is the distance innovation plot for navigat-ing through a door. In figure 6.4 is the angle innovation plot for navigatingthrough a door. At t ≈ 31s the Kalman filter loses track of the door, andwall, since the robot has passed into the room. Consequently the three timesthe sigma limits are exceeded. At t ≈ 20s the robot makes a rather hardturn and the limits for the wall increases.

The innovation is down on approximately one cm in distance. This is theresolution of the laser. That is an satisfying innovation.

The innovation for the angle is approximately one degree. This is also asatisfying innovation.

Page 31: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

6. Navigating Through Doors 26

Figure 6.2: Laser scan taken in a corridor with a door open.

6.3 Time Analysis

A lot of effort have to go into making all algorithms time effective. Manysmall sources of time consuming code will at the end give a noneffective al-gorithm.

•The Hough/Radon transform - An extremely time consuming way of process-ing data, although there is only 361 points. There is other ways of extract-ing linear elements from laser range scan data, but no-one as robust as theHough/Radon transform.

•Acquire the position data - As a laser scan is received, matching encoderand gyro data must be acquired. Position data gets a time stamp and areput in an buffer. Searching in this buffer is at the moment slow, so the buffer

Page 32: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

6. Navigating Through Doors 27

Figure 6.3: Range innovation, Green: innovation of wall. Red: innovationof door. The innovation for the door is leaving the 3-σ boundary 0.8s beforethe one for the wall.

should be small. It should not be larger than that it fits all position datapackets between two laser-scans.

•Updating the Kalman filter. - This might be the fastest operation done,but there is a lot of matrix multiplying. If the Kalman filter is expanded tocontain more states this must be taken into more consideration, and proba-bly be implemented in Java.

•Plotting - When testing algorithms, it is nice to have some plots to lookat. MATLAB is an excellent tool to use for this purpose. However, there aresome disadvantages, MATLAB is a bit slow. Real-time plotting should be

Page 33: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

6. Navigating Through Doors 28

Figure 6.4: Angle innovation, Cyan: innovation of wall. Magenta: innova-tion of door. The innovation for the door is leaving the 3-σ boundary 0.8s

before the one for the wall.

avoided, although it is wanted.

6.4 Error when Driving Through Doors

A number of test was made to evaluate this algorithm. First of all to find k1

and k2 in the control law, equation 5.8. This might not be the most effectivecontrol law for driving through tight spots, since it produces a overshoot.Although, the overshoot is possible to reduce to be approximately ten cen-timeters. In figure 6.5 it is easy to see the overshoot in x. However, thedoorframe is not placed at the peak of the overshoot but at y = 1.5 where

Page 34: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

6. Navigating Through Doors 29

the overshoot is in at only a few centimeters. In figure 6.6 the last two me-ters is zoomed from figure 6.5, where it is easier to se that the error in x aty = 1.5 is just a few centimeters.

The gain parameters in the control law k1 and k2, that gives a satisfyingresult is

k1 = 10.7

and

k2 = 1.4

where the k1 parameter controls how much gain should be put in on gettingnearer the centerline see figure 5.4. The k2 parameter controls how much theangle error affect the steering.

In figure 6.5 it is not totally obvious how the robot drove to get to theend position. A clearer picture can be achieved the state space plot (x,y,θ)in figure 6.7. There it is possible to se that the robot first turns almost 90degrees before turning back 90 degrees again and then goes through the door.The robot was also placed off center from the goal line, but had almost theright direction. It drove in a sort of S-curve to get to the goal position.

There is some things worth mentioning in figure 6.6. At y = 1.5 some-thing happens. That is the place where the robot starts to go through thedoor and the curve starts to get noisy. The interpretation is

1. The Hough lines is shorter here, the Hough lines might not be basedon the wall or the door and might therefore not be totally correct.

2. There is a small door-step that disturbs the robot when passing throughthe door.

There is also possible that both of these error sources act together and createa greater error.

What will happen to the error if the true position and orientation of thelaser is not according to the model. If the center of rotation is not cor-rect. What effect will these errors have on the robot when driving through adoorway. One of the other error sources is that the odometric encoders areexpected to add approximately one percent of the travelled distance.

Page 35: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

6. Navigating Through Doors 30

Figure 6.5: Trajectory when the robot is passing through the door: Plottingtwo dimensional x,y. The door frame is passed at y = 1.5 m and x = 0.

Page 36: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

6. Navigating Through Doors 31

Figure 6.6: Approximately the last two meters in figure 6.5. There is a“zoom-in” along the x-axis.

Page 37: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

6. Navigating Through Doors 32

Figure 6.7: Going through the door: Plotting three dimensional state variables(x,y, θ). The door frame is passed at y = 1.5 and x = 0. Observe the initialturning of the robot.

Page 38: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

Chapter 7

Evaluation and Discussion

7.1 Evaluation

The algorithm for driving through a door works very well. Although, the con-trol law could be better, the control law used in these experiments producesan overshoot. However the overshoot is not to big that it is not possible tocontrol the robot. The result driving through the doorway gave a standarddeviation of 1.4 cm and 2.2 degrees based on 10 runs. These results have theright magnitude, and are good enough for driving through the door.

7.2 Discussion

The main goal in this master thesis has been to make the robot, the MICAwheelchair, move around in an indoor environment. Using a test-bed basedon Java and MATLAB. Driving through a doorway and through junction aremaybe the most basic moves an indoor-robot must cope with. The fact thatmoving through a doorframe can be described as driving through junctionsmakes it possible to eliminate some scenarios. This makes it possible to useto same control law for both driving through doors and through junctions.There is still a lot more to be done in this field. Although, a Java andMATLAB test-bed is big step into making it easier to test and evaluate newalgorithms.

7.3 Future work

Some of the goals set at the very beginning of this study has not been reached.Some of the future work to be done is

Page 39: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

7. Evaluation and Discussion 34

• Get the robot to be able to avoid driving into crap in the corridor.• Analyze Laser alignment error.• Error analyze, compare test and modelling.• Time error behavior. Time synchronization and time delay.• Measuring errors and calibration errors.• Scene interpretation error.• Dead reckoning error.

Some of these goals has been mentioned shortly in the report but furtherstudies is needed.

Page 40: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

Appendix A

Tolerances for Passing BetweenTwo Obstacles

A.1 Representation of the Door

A door can be represented as two cylinders which in two dimensions will betwo circles.

A.2 Cylinder

There is two conditions, equations A.1 and A.3 that must be fulfilled toget maximum angle at which the robot can can pass between the cylinders.These conditions are written for one cylinder but it is easy to repeat themfor the other cylinder.

(

Lw

2+ ξ0

)

· sin (α) >

(

r +W

2

)

(A.1)

Where

α =arccos

(

r + W2

)

Lw

2+ r + ξ0

(A.2)

And

L > W > Lw

Or if this condition is fulfilled

(

Lw

2+ r + ξ0 + x

)

>

(

L

2

)2

+(

W

2

)2

· cos

(

arctan

(

L2

W2

)

± θ

)

(A.3)

Page 41: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

A. Appendix: Tolerances for Passing Between Two Obstacles 36

Figure A.1: Robot between two cylinders.

Figure A.2: Robot next to one cylinder. Could be a part of figure A.1

Page 42: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

A. Appendix: Tolerances for Passing Between Two Obstacles 37

Where

x = r − r · cos(

arcsin(

ηpos

r

))

(A.4)

And ηpos is the position of a corner of the robot in the η-direction.

A.3 Wall

The condition for two walls

(

Lw

2+ ξ0

)

>

(

L

2

)2

+(

W

2

)2

· cos

(

arctan

(

L2

W2

)

± θ

)

(A.5)

This condition is similar to equation A.3. If r ⇒ ∞, x ⇒ 0. When theradius in a cylinder is large the cylinder could be considered a wall, since x

is so small that it could be disregarded.

A.4 One wall, One Cylinder

One wall and one cylinder requires that both the conditions discussed aboveis combined and fulfilled.

Page 43: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

A. Appendix: Tolerances for Passing Between Two Obstacles 38

Figure A.3: Filled line(green): two cylinders. Dashed line(blue): two walls.Radius of cylinders 0.05 to 20 meters. As seen the larger the radius of thecylinders becomes they more and more becomes similar walls. W = 0.6,L = 1.5 and Lw = 1.0.

Page 44: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

A. Appendix: Tolerances for Passing Between Two Obstacles 39

Figure A.4: Filled line(green): one cylinder, one wall. Dashed line(blue):two walls. Radius of cylinders 0.05 to 20 meters. As seen the larger theradius of the cylinders becomes they more and more becomes similar walls.Here we also can se that it can benefit to drive nearer the cylinder if thecylinder is small. W = 0.6, L = 1.5 and Lw = 1.0.

Page 45: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

References

[1] Dickmanns E.D.; Zapp A.;. Autonomous high speed road vehicle guid-ance by computer vision. 10th IFAC Congress, vol. 4:232–237, July1987.

[2] Forsberg J.; Larsson U.; Wernersson A. Mobile robot navigation usingthe range-weighted hough transform. Robotics & Automation Magazine,IEEE, vol 2, Issue 1:18–26, March 1995.

[3] SICK AB. http://www.sick.se/. (2004), Sep. 2004.

[4] Maaref H.; Barret C. Sensor-based navigation of mobile robot in anindoor environment. Robotics and Autonomous Systems, 38:1–18, 2002.

[5] Levine S.P.; Bell D.A.; Jaros L.A.; et al. The navchair assistive wheel-chair navigation system. IEEE Transactions on Rehabilitation Engi-neering, Vol 7, Issue 5:443–451, Dec 1999.

[6] Forsberg J.; Larson U.; Ahman P.; et al. The hough transform inside thefeedback loop of a mobile robot. 1993 IEEE International Conferenceon Robotics and Automation, vol 1:791–798, 2-6 May 1993.

[7] Ahman P.; Forsberg J.; Larsson U. Navigering av en mobil robot medhoughtransformen. Master’s thesis, Lulea University of Technology,1992.

[8] Per Holmberg. Sensor fusion with coordinated mobile robots. Master’sthesis, Linkping Institute of Technology, 2003.

[9] Victorino A.C.; Rives P.; Borrely J.-J.;. A relative motion estimationusing a bounded erroe method. IEEE/RSJ International Conference onIntelligent robots and system, vol. 1:643–648, 30 Sept.-5 Oct. 2002.

[10] Ribeiro M.I.; Goncalves J.G.M. Natural landmark based localisation ofmobile robots using laser range data. Advanced mobile robot. Rroceedingsof the first Euromicro workshop, pages 186–193, 9-11 Oct. 1996.

Page 46: 2005:185 CIV MASTER'S THESIS Laser Guided Vehicle

References 41

[11] Chen C.; Payeur P. Scan-based registration of range measurements. Pro-ceedings of the 19th IEEE Instrumentation and measurement technologyconference, vol. 1:19–24, 21-23 May 2002.

[12] Gonzales J.; Gutierrez R. Mobile robot motion estimation from a rangescan sequence. IEEE International conference on Robotics and automa-tion, vol. 2:1034–1039, 20-25 Apr. 1997.

[13] Nilsson B.; Nygards J.; Wernersson A. On-range sensor feedback formobile robot docking within prescribed posture tolerances. Journal ofRobotic Systems, vol 14, issue 4:297–312, 1997.

[14] Nygards J.; Wernersson A. On covariances for fusing laser rangers andvision with sensors onboard a moving robot. 1998 IEEE/RSJ Interna-tional Conference on Intelligent Robots and Systems, vol 2:1053–1059,13-17 Oct 1998.

[15] Ronnback S. On a matlab/java testbed for mobile robots. Licentiatethesis, Lulea University of Technology, 2004:10.

[16] Rofer T. Using histogram correlation to create consistent laser scanmaps. IEE/RSJ International conference on Intelligent robots and sys-tem, vol. 1:625–630, 30 Sept.-5 Oct. 2002.