CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM...

58
CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate Studies and Advanced Research of the University of Cincinnati in partial fulfillment of the requirements for the degree of MASTER OF SCIENCE In the Department of Mechanical, Industrial and Nuclear Engineering of the College of Engineering 2000 by Sathish K. Shanmugasundaram B.E (Mechanical Engineering), PSG College of Technology Coimbatore, India Thesis Advisor and Committee Chair: Dr. Ernest L. Hall

Transcript of CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM...

Page 1: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

CONTROL SYSTEM DESIGN FOR AN

AUTONOMOUS MOBILE ROBOT

A thesis submitted to the Division of

Graduate Studies and Advanced Research

of the University of Cincinnati

in partial fulfillment of the

requirements for the degree of

MASTER OF SCIENCE

In the Department of Mechanical, Industrial and Nuclear Engineering

of the College of Engineering

2000

by

Sathish K. Shanmugasundaram

B.E (Mechanical Engineering), PSG College of Technology

Coimbatore, India

Thesis Advisor and Committee Chair: Dr. Ernest L. Hall

Page 2: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

2

Abstract

A good control system is an absolute requirement for a mobile robot or any system

that has to be automated. This thesis mainly deals with components of design for an

optimal, stable control system for an autonomous robot. The robot is Bearcat II.

Bearcat II is being developed as an automated guided vehicle to participate in the

annual International Ground Robotics Competition automated vehicles contest.

A closed loop control system called as proportional, integral, and derivate control

system (PID) is used currently on the robot. It uses an elaborate algorithm to

manipulate the parameters. Tuning of the controller is the real tricky part of these

types of controllers.

Various tuning methods currently in use are discussed. The difficulties in using these

are also highlighted. The model of the control system is reviewed and the system

response studied. A general model of a motor and load system is also developed.

Based on the model, a new technique using optimization theory is proposed. This

theory concentrates on reducing the error between output and input at multiple

instants of time. This is a multi-criteria optimization formulation of the problem.

Methods used in the formulation are discussed. Finally, an optimized set of tuning

constants is determined. The developed method is more logical, scientific and better

in terms of minimal mean square error than previous methods. It also reduces the

number of iterations required for tuning the controller.

Page 3: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

3

Acknowledgements

First, I would like to sincerely thank Dr. Ernest Hall my advisor, for having pointed

me to this direction and, for his enthusiastic and energetic guidance throughout my

career at the University of Cincinnati. He has been a constant source of information

and support for this thesis.

A special word of thanks should go the robotic team members, past and present for

having supported in my work. They have helped me in all possible ways to make this

process smooth. I would also like to add a note of thanks and special appreciation to

the staff of the MINE department for having supported the team and me in all

possible ways.

My committee members, Dr. Richard L. Shell and Dr. Ronald L. Huston, should be

thanked for looking through my work and making valid suggestion. Their suggestions

have made this work more focused.

Last but not least, my family should be thanked. They have stood by me and watched

my career evolve for the better. They have also been a source of constant support and

encouragement.

Page 4: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

4

Table of Contents

List of Figures………………………………………………………. 6

1. Introduction………………………………………………………….. 8

1.1 Introduction…………………………………………….. 8

1.2 Motivation and problem statement…………………….. 9

1.3 Objective………………………………………………. 9

1.4 Acknowledgement……………………………………… 9

1.5 Organization…………………………………………… 9

2. Background work and literature search…………………………… 11

2.1 Introduction…………………………………………….. 11

2.2 Linear and non-linear controller design ……………… 14

2.3 Steering control for an AGV………………………... 15

3. Control System theory……………………………………………. 18

3.1 Introduction…………………………………………… 18

3.2 The basic control system……………………………… 19

3.2.1 The control problem…………………… 19

3.2.2 Input and output…………………….. 20

3.3 Feedback and feed forward control…………………… 21

3.4 Linear control systems………………………………… 24

3.5 Non-linear control systems…………………………… 24

3.6 Designing a control system……………………………….. 25

Page 5: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

5

4. PID control. …………………………..…………………………. 29

4.1 PID controller ……….……………………………….. 29

4.1.1 Proportional…….……………………………… 31

4.1.2 Integral.………………………………………… 32

4.1.3 Derivative.……………………………………… 33

4.2 Controller tuning……………………………………… 33

4.3 Galil DMC 1000……………………………………… 34

5. Control parameter determination for the Bearcat II ……. 36

6. Simulation and parameter optimization for the Bearcat II… 40

6.1 Introduction.………………………………………. 40

6.2 Simulation on SIMULINK.………………………… 40

6.3 Optimization model………………………………. 40

6.4 Optimization of the system to obtain tuning constants… 44

6.5 The lsqnonlin method………………………………. 44

7. Results and summary…………………………………………… 49

8. Recommendations……………………………………………… 50

9. References ...……………………………………………………. 51

Page 6: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

6

List of figures

Page

Chapter 2

2.1 Lane following structure …………………………............. 13

2.2 Automated guided vehicle ………………………………… 16

Chapter 3

3.1 Simple control system ………………….…………………… 19

3.2 Elevator system …………………..…………………………. 20

3.3 A typical feedback Control System ……………………………. 21

3.4 Position control system………………………………………… 25

3.5 Block Diagram of the control system ………………….……… 26

Chapter 4

4.1 PID equations…………………………………………………… 30

4.2 Controller action………………………………..………………. 32

Chapter 5

5.1 WSDK Servo Kit ……………………………………..…….. 36

5.2 Servo Kit Tuning ……………………………………………. 37

5.3 Step response plot from the Galil servo design kit………………. 38

Page 7: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

7

Chapter 6

6.1 Basic model of the system………………………………..…………. 41

6.2 Response for the load …………………………………………..…. 42

6.3 General system…………………………..………………………….. 43

6.4 Error values over a time period ……………………………………… 45

6.5 Step response for using the optimized values …………………………… 48

Page 8: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

8

Chapter 1

1. Introduction

1.1. Introduction

Control systems are the very heart of mobile robots. Problems such as coordination of

manipulators, motion planning and coordination of mobile robots require a central

controller. Additionally, automation depends heavily on the ability to precisely

control motion. The issue of control is paramount whether it applies to machine tools

or robots. To achieve precise control the relative position of objects need to be

measured. A continuous comparison of the positions is an essential element in any

motion control system. The comparison generates an error signal which can be used

to provide corrections. If the error is small, the system performance is repeatable and

accurate. This shows the importance of a good control system design. Many feedback

controllers use a proportional-derivative-integral algorithm to manipulate the error

signal and apply a corrective effort to the process.

Page 9: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

9

1.2. Motivation and problem statement

The main motivation of this thesis is the mobile robot Bearcat II that we are

developing and continually improving. The robot uses a PID controller (Reference).

Though this type of controller is common it is very hard to tune and attain stable PID

parameters. The team has tried many different methods to tune the controller.

A few of them are iterative, trial and error and, brute force. Though these work for

most situations the stability of the system is lost at certain times. For example, using

the largest possible values could make the controller very aggressive and cause

amplification of errors. On the other hand if the tuning it too conservative it does not

eliminate the errors and the system appears sluggish. Hence this is a difficult adaptive

tuning process.

1.3. Objective

To solve this problem a new technique using optimization theory is proposed in this

thesis. It uses both simulation and optimization. Because it uses an objective criteria

function, minimum mean square error, it is a more scientific and logical approach to

the problem. Although it is not a perfect and final solution, it is a definite step toward

reaching the perfect and one solution for these adaptive controllers.

1.4. Acknowledgement

This thesis is an extension to the work done in this area especially by two previous

team members, Kalyan Kolli [1] and Krishna Mohan Kola [2]. Some of the ideas and

Page 10: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

10

topics have been derived from their work and have been further worked on and

extended. I acknowledge them for their good and fascinating work.

1.5. Organization

Chapters 2 thorough 4 contain background work on established literature about

control theory, control systems and their applications in every day life. Chapter 2

provides literature and survey of automated guided vehicles. Chapter 3 gives an

introduction to well established control system theory and the various types of control

techniques. Chapter 4 looks at the Galil DMC 1000 controller which is a PID

controller used in the Bearcat II. It also explains the purpose and meaning of the

various parameters in the PID controller. Chapter 5 details the current tuning

procedure for the Bearcat II. The software used to assist the tuning is described in

detail. Chapter 6 models the control system and highlights the new optimization

technique for parameter determination. Finally the results and recommendations for

future work are discussed in Chapter 7. The Appendix shows the actual Matlab and

Simulink code used to obtain the results.

Page 11: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

11

Chapter 2

2. Background work and literature search

2.1. Introduction

Material handing environments such has distribution and manufacturing commonly

use automated guided vehicles (AGVs) to achieve accuracy and efficiency. Such

systems provide material movement through the plant in a variety of applications.

The advantages they offer include automation, flexibility, accuracy, reduced damage,

extendibility, scalability and ability to interface with other systems for configurability

(Miller [3]).

2.1.1. Classification of AGVs – Following are the ways AGVs are classified

2.1.1.1. Guide Path Determination

2.1.1.1.1. Static Path

Unidirectional

Bi-directional

2.1.1.1.2. Dynamic Path

2.1.1.2. Vehicle Capacity

2.1.1.2.1. Single unit load

2.1.1.2.2. Multiple loads

Page 12: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

12

AGVs are designed to run at a specific maximum speed. However, they are rarely

operated at such speeds and are operated at much lower speeds. But, in environments

where there is no human presence they can be operated at their maximum capacity to

improve productivity and efficiency. Running them at high speeds brings about its

own set of challenges in design for stability and control. The challenges are

proportional to the speed of operation. In order to address these challenges, the

dynamic effects of the design parameters must be well understood.

A significant amount of work has already been done in this area to address the

challenges in steering of robots and automobiles. Tagawa et al. [4] have worked on

the issues in kinematics and dynamics and others such as Hattori et al. [5] have

worked on linear and non-linear controllers.

The primary navigational challenge for Bearcat II is to ensure that it follows a line

and stays within the bounds of two lines. In their work on vehicle steering, Ozguner

et al. [6] tackle this exact problem. Their objective was to steer a vehicle by making it

follow a line. Their method was to always look at a point ahead located along the

travel axis. The difference between that point and a reference was set as an offset. To

achieve the best steering conditions, this offset should be kept as low as possible.

Under ideal conditions, the ratio of the steering angle and the offset is not dependant

on the radius of the curve. This ratio was set in terms of the desired speed and the

various parameters such as load and operating conditions of the vehicle. A controller

was developed based on the vehicle model to achieve a steady state. The vehicles

speed was the determining factor to be applied in the controller. Their designed

Page 13: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

13

controller constantly only tracked this offset. Using previously developed analytical

models by Routh-Hurwitz they proved that stability could be achieved with a closed

loop. Their analysis also proves that it is possible to achieve stability for speeds

within an established speed range.

They define the ―look ahead‖ information to include topology, the vehicle‘s centre of

gravity, orientation, vehicle geometry, and position in relation to the road. They

attempted to formulate a control law for vehicle steering based on the above

information.

The model they proposed is shown in the Figure 2.1

Figure 2.1 Lane following structure (Ozguner, et al. [6])

They proved that the controller works by testing it at the Research Center in

Marysville, OH.

L o o k -a h ead o f fse t

S e n so r

C o n s ta n t

C o n tro lle rS te e r an g le

C o m m a n d

V eh ic le d y n am ic s

&

V eh ic le - ro ad in te rac tio n

L o n g itu d in a l S p e ed

Page 14: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

14

2.2. Linear and non-linear controllers

Ackerman, et al. [7] proposed a ―linear and non-linear controller design for robust

steering.‖

In their work, they establish that vehicle steering is one of the main components of an

integrated highway system which they foresaw as the future. In simplistic terms,

automated steering is dependant on being able to track a reference object. Sensors are

an integral part of this system which helps in measuring the distance from the path.

Examples of references may include magnetic fields supplied by electricity or

permanent magnets. The sensor may be mounted at an appropriate location on the

vehicle to effectively track the reference. The correction supplied by the controller is

applied on the front wheels to steer the vehicle.

As the authors outline, among the contributor to challenges in automated steering are

variations in velocity and mass of the vehicle under different travel circumstances.

Taking their example of a city bus, its mass will vary based on the people on the bus.

Its velocity will vary for different driving conditions, for example it will travel at

higher speeds on the highway than city roads. Based on these challenges they tried to

make a fit between linear and non-linear control techniques.

They determined that for a non-linear situation, tracking accuracy was substantially

better by measuring and incorporating the yaw rate using a gyro. The control problem

became less dependant on external and internal vehicle conditions such as friction,

Page 15: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

15

mass and velocity. They proved in their study that the vehicle tracked close and to

acceptable standards to the reference. Their controller with fixed gains produced

acceptable performance for various operating conditions. To bolster their finding they

used the parameter space technique, which accommodated for extreme conditions.

Ackerman, et al. [7] also designed a non-linear structure to further augment the

performance of steering. It was based on a sliding mode with inclusions for dynamic

adaptation for various operating situations. They compared the two approaches by

simulating them. Parameters for the controller for both techniques were tuned by

optimizing vector performance.

2.3. Steering control for an AGV

In their paper on AGVs Sung et al. [8] propose a steering system using a parallel

linkage. They explain their approach in designing its control system which was

modeled using a computer. They utilized proportional control with describing

functions. Gain values and derivate action for control were also suggested.

Proportional, gain and derivate action are explained in the following chapters. Their

research also proposed a simulation model for various operating speeds. The results

they obtained proves that time based control laws are needed for tracking

Page 16: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

16

Figure 2.2 shows their AGV

Figure 2.2 Automated guided vehicle (Sung, et al. [8])

Their vehicle was symmetrical in the front and rear and had the following hardware

components:

• DC servomotor for the drive

• Light emitting diodes as sensors for guidance

• Stepper motors to actuate the steering mechanism

• A micro processor based controller to calculate a steering control signal, which it

fed to the stepper motor

• Reflective tape on the track for guidance

Page 17: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

17

Steering depended on the following critical factors:

• Effectiveness of the sensor

• Configuration of the wheels

• Speed of the vehicle

• Deviation or steering angle

Page 18: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

18

Chapter 3

3. Control system theory

3.1. Introduction

This chapter introduces basic concepts in control theory. A control system is a

collection of connected components connected in way to provide a desired response.

They find use in automobile, household appliances and space craft. Control systems

are an essential part of almost all industrial devices today. They are also prevalent

around us in our homes in every day appliances. Using feedback control, large

objects can be moved with precision. A simple example is a household HVAC

(heating ventilation and air conditioning) unit that contains a thermostat. The

thermostat comprises of a strip of metal that expands or contracts with changes in

room temperature. This activates a switch that either turns on or off the heating or

cooling apparatus. Another good example is an automobile‘s cruise controller. It uses

the vehicle‘s measured speed at a point in time to compare it against the desired speed

set by a person. Based on the difference, it sends a signal to the vehicle‘s acceleration

control to either slow down or speed up.

Page 19: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

19

3.2. The basic control system

A control system is a collection of connected components connected in way to

provide a desired response for controlling a process. Basically a control system

provides an output response for a given input as shown in Figure 3.1

Figure 3.1 Simple control system (Nise [9])

3.2.1. The control problem

A generic closed-loop system consists of:

input

controller

system to be controlled

measuring device

output

reward function

There may also be a:

Plant model

Control

System

Input; stimulus

Desired response

Output; response

Actual response

Page 20: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

20

The latter case is a dynamic system that can be modeled by a set of differential

equations. There are significant differences between dynamic and discrete

systems. Solutions developed for one usually do not apply to the other.

3.2.2. Input and output

In the case of control systems, input is the required response and output is the

actual behavior. As an example, Nise [9] shows in Figure 3.2 the case of an

elevator when the required floor button is pushed and one wants the elevator to

arrive at the destination accurately in a smooth motion.

Figure 3.2 Elevator system (Nise [9])

Pushing of the button is the input represented by a command. The result of the

input is what the person wants the desired output to be. The elevator‘s response

can be demonstrated by the curve shown as the elevator response.

The output is always going to be different from the input. An input can be

specified instantly whereas it takes time for a system to react and reach the output.

Page 21: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

21

This behavior is reinforced by the figure. It is dependant on the device and its

reactive properties. This is the transient response.

After this initial response, the system enters a steady state which is approximately

the desired result. This difference is called the steady-state error (Nise [9]).

3.3. Feedback and feed forward control

Feedback control is a closed-loop system where the output is constantly compared

against the desired response. According to VanDoren, ―A feedback controller is

designed to generate an output that causes some corrective effort to be applied to a

process so as to drive a measurable process variable towards a desired value known

as the set point. The controller uses an actuator to affect the process and a sensor to

measure the results‖ (VanDoren [10]). Figure 3.3 represents a feedback control

system. Feedback control is based on measuring the error. This error is used to bring

the system to its required state from its present state. For linear feedback control

systems, the error drives the amount of correction to be applied.

Figure 3.3 A typical feedback Control System

Page 22: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

22

This method may not apply for non-linear processes, so a gain needs to be applied.

The required state behaves like an attractor and the system exhibits spring-like

tendencies.

To dampen out the behavior of a spring a dampening factor may be added.

r(t) = Kp( x d(t) – x (t)) + Kv (d x(t)/dt) (1)

In the above:

r(t) is the control input

x (t) the state of the system

x d(t) the target state

Kp the proportional constant or the damping coefficient

Kv the derivative constant or spring constant in this case

dx(t)/dt the rate of change of the state of the system (Chaktravarthy [1])

This has a serious flaw in that leaves a constant offset. To address the flaw an

integrative term is also needed.

r(t) = Kp( x d(t) – x (t)) + Kv (d x(t)/dt) + KI ∫ ( x d(t) – x (t)) dt (2)

Page 23: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

23

KI is the integral constant. With this new value there are three constants and

controllers that employ the three constants are called proportional, integral, derivate

controllers (Chaktravarthy [1]).

Feedback control has a few inherent disadvantages which are:

It is predicated on the error, corrective action is not taken until there is a

deviation

It could be sluggish where precise compensation may not be possible

If there are time delays the performance may not be satisfactory

Feed forward control takes a different approach where corrective action is applied

before an actual deviation occurs. This type of control is predicated on having an

accurate model and measuring the disturbance in-line.

It may not be technically possible to accurately model the system. Also the deviations

from target may occur at a rapid pace. This could be due to non-linearity or

unpredictability of the system.

Factors that cause deviation will not be corrected and errors that may otherwise be

handled my not be suitably addressed. This is a flaw in such controllers and they are

usually used in conjunction with feed back controllers.

Page 24: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

24

3.4. Linear control systems

Systems usually have a combination of linear and non linear elements. Under certain

situations it could be possible to treat the non linear elements as linear. The rationale

behind this is that principles of linear mathematics can be applied to develop a

solution. Additionally, if the range of input values is small enough it can be treated as

linear as well. If the system cannot be suitably approximated as linear then only

specific methods can be applied to address them. There are well established methods

to address linear control of systems (Chaktravarthy [1]).

3.5. Non-linear control systems

Non linear control systems are systems meant for non linear or time variant processes.

They are much more difficult to control than linear, mainly because they pose a set of

problems that are really not solvable. This is because in the case of a linear time

variant system it is impossible to simply write down a closed form equation. Due to

this we cannot necessarily tell how the system would behave under a set of

circumstances. They have to be dealt with individually.

It is going to be difficult to control non linear systems where the response could be

unpredictable in relation to the input. Also, in the non linear case stability will be

more difficult to achieve. In the case of linear systems it is easier to predict or design

a system for stability. The stakes get higher if the process being controlled is riskier

such as a refinery or a chemical plant.

Page 25: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

25

3.6. Designing a control system

Control system design involves an iterative process. Nise [9] explains the process

using the example of and antenna position control system. The angle output of the

antenna, o (t) depends on the input angle of the potentiometer, i (t). Figure 3.4

shows the diagram of the system and Figure 3.5 shows the functional block diagram

of the system. In the figure, hardware is in the blocks and the function is indicated

over the blocks.

Figure 3.4 Position control system (Nise [9])

Page 26: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

26

Figure 3.5 Block Diagram of the control system (Nise [9])

1: Transform the requirements into a physical system

Antenna system: To design a control system for the position control of the azimuth of

the antenna.

Requirements: Remotely position the antenna taking its physical attributes such as

weight and dimensions into account

2: Draw a functional block diagram depicting the functional elements and physical

components

In diagram shows functions as input transducer, the controller, and plant and sensor.

3: Convert the physical system into a schematic.

Page 27: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

27

In the iterative process after the first pass, suitable decisions have to be made on the

assumed approximations. If it is not satisfactory additional parameters are

incorporated into the system.

Examples could include:

Assuming a negligible inductance for the motor because of the

complementary inductive and resistive properties

Adding more pure gain on the assumption that amplifier dynamics are rapid

compared to the motor‘s response

Choice of potentiometers

Adding inertial and viscous damping because of rotational mass

4: Develop a mathematical model

Based on the schematic, physical laws such as the Kirchhoff‘s laws and Newton‘s

laws were used.

These laws lead to the following models that highlight the relationship between input

and output.

Linear time invariant differential equation

Transfer function using the Laplace transform. Laplace transform is

advisable for linear systems because the information in the frequency

domain. Parameters can be changed to quickly observe the changes to the

response

Page 28: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

28

State space method

5: Assimilate the block diagram

Sub-component models with their own models are connected to form the diagram of

the larger system. It involves assimilating the subsystems into one single system

block with a mathematical model of the entire system from end to end.

Step 6: Analyze and design

Analyze the design to see if the system‘s response meets specifications. Tuning may

be required to fine tune performance, or additional components may be required to

meet the needs. In certain cases minor adjustments may be sufficient.

Page 29: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

29

Chapter 4

4. PID control

4.1. PID Controller

PID is an acronym for proportional, integral and derivative. PID controllers are

designed to work autonomously over periods of time. The controller works by

determining the error between the desired point and the measured variable. Common

examples of controllers at work are household thermostats and cruise controllers in

automobiles. The proportional element of PID involves changing the gains

proportional to the measured error. This can however lead to negative consequences

of overshooting the desired point. The integral component includes a time factor to

reduce the offset, and the derivative component is included to further smoothen out

the behavior by taking the rate of change into account. It can be summed up as how

much to apply, for how long and at what rate.

PID controllers take these three components into account to produce the desired

response. According to VanDoren, ―It looks at the current value of the error, the

integral of the error over a recent time interval, and the current derivative of the error

signal to determine not only how much of a correction to apply, but for how long.

Those three quantities are each multiplied by a tuning constant and added together to

produce the current controller output CO(t)‖ (VanDoren [10]). Figure 4.1 explains

his description via equations. VanDoren explains, ―P is the proportional tuning

constant, I is the integral tuning constant, D is the derivative tuning constant, and the

Page 30: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

30

error e(t) is the difference between the set point P(t) and the process variable PV(t) at

time t‖ (VanDoren [10]).

Figure 4.1 Equations [1] and [6] in the figure above--both forms of

the PID algorithm generate an output CO(t) according to recent

values of the set point SP(t), the process variable PV(t), and the error

between them e(t)=SP(t) - PV(t) (Graphic and explanation courtesy of

VanDoren [10])

The error in a PID controller is the difference between the measured value and the

desired point

E = S – M (3) (Chaktravarthy [1])

The goal in PID control is to adjust the variables in order to effectively reach the set

point. The output of the controller is generally equal to the variable being adjusted.

This output changes as the measured values or set point changes [11]. The three PID

components are further explained below.

Page 31: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

31

P Proportional band = 100/gain

I Integral = 1/reset (time)

D Derivative = rate (1/ time) [11]

In the above gain is simply the output over input, reset is the measure of time taken to

achieve the output and rate is the pace at which change needs to happen in order to

reach the required state. Reset action could be set in repeats per time unit, or time

taken to repeat the action.

4.1.1. Proportional

The proportional band is simply the amount of gain to apply. The controller

output is proportional to the error or a change in the measured vale.

O = E*100/P (4)

O = Controller Output

E = Error

P = Proportional Band

Offset or deviation is always present with proportional controllers. To achieve the

output, gain could be increased but it will result in the negative consequence of

making the loop unstable. To address this issue, an integral component was

introduced [11].

Page 32: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

32

4.1.2. Integral

Integral action is a measure of ―how long‖ and is used to eliminate the offset that

is introduced with the proportional component. This component is time based and

it is a measure of time the error exists.

O = 1/I(∫e(t) d(t)) (5)

The plot in Figure 4.2 below shows that with the addition of the integral

component, offset is eliminated. This result is however not perfect because it is

not stable. The stability is addressed in a PID controller with the derivative

component [11].

Figure 4.2: Controller action (Expertune Inc [11])

Page 33: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

33

4.1.3. Derivative

The derivate action is a measure of ―at what rate‖. The output is directly

proportional to the rate of change of the measured value or of the error [11]. The

derivative component‘s action helps to prevent overshooting of the target, and is

akin to that of a moderator in inhibiting rapid changes. Whenever there is a

change in the measured value or process, this causes the gain to reverse direction

if the measured value is being reached.

O = D (dm/dt) (6) (Chaktravarthy [1])

In the above, ―m‖ is the measurement at a point in time ―t‖

4.2. Controller tuning

The defined ―P‖, ―I‖, and ―D‖ tuning constants have to be suitable set in any

controller in order to achieve the desired result or as close to the result as possible. As

VanDoren states there are three primary methods to tune a controller, which are:

Experimental: This method calls for tweaking the three constants and

watching the controller‘s response. If the response is inadequate it calls for

adjusting the three values appropriately. As he states, this method is not

recommended for the inexperienced as it is too cumbersome

Page 34: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

34

Analytical: This method calls for modeling the process to include the

controller‘s various parameters and values that influence the controller. If

a model can be built, its parameter can in turn be used to deduce the tuning

constants

Combination technique: This technique calls for a mix of the experimental

and analytical techniques.

4.3. Galil DMC 1000

The DMC-1000 series motion controller is a PID controller that interfaces to a

personal computer. The 1000 series by Galil (www.galilmc.com) is part of their

legacy line up that is very flexible in its applications.

It is available for one, two, three or four axes per card. It can be interfaced to a variety

of devices such as motors (several type) and drives.

The major components of the controller comprise of the microcomputer, motor

interface, communications interface, amplifier and encoder.

The Galil 1000 was chosen as the controller of choice for the Bearcat II because of

the following features:

Availability of multiple motion modes with the flexibility to specify many

parameters such as velocity, acceleration etc.

Ease of programmability

Utilities that can be used to leverage events such as time and distance

Page 35: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

35

Quick edit interface which is very important in the field

Available servo design kit

Error handling features

Robust processor for the time

Fail safe mechanisms

Page 36: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

36

Chapter 5

5. Control parameter determination for the Bearcat II

Presently the control parameters i.e., PID values for the Galil controller are

determined using a software tool supplied by Galil Motion Inc called Windows Servo

Design Kit (WSDK 1000). This software takes frictional losses in the gear mesh,

motors and the drive train into account by performing an experimental Bode plot or

transient step response. This kit is GUI based and which allows setting the various

PID parameters of the controller. Figures 5.1 and 5.2 show the tuning menus of the

controller

Figure 5.1 WSDK Servo Kit (Galil [12])

Page 37: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

37

Figure 5.2 Servo Kit Tuning (Galil [12])

Several startup options are available on the controller to check and enable

connectivity. Before starting the Bearcat, a stability analysis using a closed loop

situation is performed. The tuning constants can be tuned only if the Bearcats

platform is stable. The stability tests were performed in three modes:

Bearcat II on jacks and off the ground

Bearcat II on the ground but stationary

Bearcat II in motion

Care was taken during this process because it causes violent shaking of the robot. To

get a better idea of the parameters this process was done in multiple iterations on

various surfaces to accounts for different friction levels and loads. The different

surfaces that the robot would encounter on a run could be grass, asphalt, wood, tarp,

sand, granite, and highly polished surfaces such as granite. Based on the various

Page 38: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

38

values obtained a representative value can be chosen or, a value based on the roughest

surface can be chosen. Figure 5.3 shows the step response plot evaluation after the

values have been analyzed.

Figure 5.3 Step Response Plot from the Galil servo design kit

First, a sinusoidal input is supplied to the motors. This causes the wheels to rotate

back and forth. During this period the system response magnitude and phase

frequency response is measured. The software allows individual tuning of up to four

axes. Using these values a Bode plot frequency, which is the open loop frequency

transfer function response, is plotted to determine to see if the overshoot is within

satisfactory limits.

Page 39: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

39

An iterative or experimental tuning option was chosen because the load on the

Bearcat II could not be appropriately modeled to apply an analytical approach. Each

of the parameter slides can be changed to adjust the PID values. First, a starting value

is chosen. Using the starting value, the WSDK program plots the step response. The

overshoot is determined by visually observing the plot. Based on the plot the sliders

adjusted to a different set of PID values. The whole process is repeated again.

This process may take a while to arrive at satisfactory PID values. Once satisfactory

values are obtained they can be used in the control program. If there is a slight change

in the drive system hardware the PID values will have to be recalculated if proper

control of the system is required because this could change the load parameters of the

system. The interface for the system is implemented using a Galil 1030 motion

control computer interface board.

As mentioned this process may take many iterations and a long time to finish. To

address this drawback an optimized tuning method is proposed in the next chapter.

The PID values obtained with new process can always be tested and fine-tuned using

the servo kit.

Page 40: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

40

Chapter 6

6. Simulation and parameter optimization for the

Bearcat II

6.1. Introduction

This chapter describes the modeling, simulation and optimization of the control

system. Matlab was the tool chosen for the validating the control system design.

Matlab supplies a set of tools via a collection called Simulink, which was used.

Simulink supports the modeling of various control system scenarios in an integrated

fashion. The optimization tool box supplied by Simulink provides for a basic model

which can be used to optimize parameters for the Bearcat II‘s ([13, 14]).

6.2. Simulation

The idea behind choosing a simulation model was to obtain stability. An additional

objective was to keep the phase margin below forty five degrees and to choose a gain

value that minimizes overshoot. The controller used on the Bearcat II is a PID

controller which can be used in providing the tuning constants necessary.

The steps involved are:

1. A Matlab file that has the model of the transfer function

2. A second Matlab file that converts the digital gains to analog gains

3. A Simulink graphics model which simulates the system step response

Page 41: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

41

Bearcat II‘s control model is shown below:

Figure 6.1 Basic model of the system (Charkavarthy [1])

The proportional, integral and derivative constants are calculated independently. The

digital gains for the corresponding analog values need to be calculated based on the

values. The P, I and D values adjust the signal to the zero order hold. This freezes the

input level until the next input. The idea behind this method is to flatten the input.

The model also includes a sample time in the block. The converter receives the signal

at this point. The converter converts the signal and forwards it on to the amplifier.

The gain value for the amplifier can be adjusted for situational needs, but for the

Bearcat II it was started at two units. The load components for the Bearcat II which

include the physical structure, motor and load drive the amplification factor and the

signal is fed to the Bearcat II‘s controller. Matlab‘s response is shown in the figure

below.

+-

SumStep Input

1

.0005s+1

Zero OrderHold

-K-

Gain2

gs +(g*a+f)s+f*b2

s +bs2

The PIDcontroller

.54

.0003773s2

Motor andLoad

2

AMP

0.00122

DAC

Auto-ScaleGraph

Auto-ScaleGraph1

Page 42: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

42

0 0.02 0.04 0.06 0.08 0.1 0.120

0.02

0.04

0.06

0.08

0.1

0.12

Time (second)

Figure 6.2 Response for the load

The simulation proved that the phase was within the bounds of acceptable values.

This can be validated in the plot.

Page 43: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

43

6.3. Optimization model

Figure 6.1 shows the model of the controller for Bearcat II and is not specific to any

load scenario. The model in figure 6.3 is a more general model which can be used to

represent more load systems.

Figure 6.3 General system [14]

It should be noted that the response does not rise immediately as is desired. But, most

controllers do not behave that way as discussed in Chapter 3. The load on the system

and other design parameters of the system and hardware components play a direct

role in the response.

Page 44: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

44

6.4. Optimization of the system to obtain tuning constants

Simulink‘s solver is used to optimize the parameters and constants. The model the

accurately represents the Bearcat II is non-linear. Matlab‘s optimization toolbox was

utilized to solve the model.

The model is solved in two steps as follows:

Error based measurement between the output and the input signals,

‗lsqnonlin‘

Function ‗fminimax‘. This method limits the maximum value of the output.

This is a more efficient and practical method. The PID values are the

variables to the function. The error minimization can be done one at a time by

adjusting one variable at a time ([14]).

In the case of Bearcat II‘s controller all errors need to be minimized to this became a

multi dimensional function.

6.5. The lsqnonlin method

Fit analysis and application is achieved by using ―lsqnonlnin‖ on the output. Figure

6.5 shows the difference between the actual and required values over a period of time.

Page 45: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

45

Figure 6.4 Error values over a time period

For the Bearcat II to run smoothly the error values shown above have to be minimal

i.e.

Obtain a minimum value for:

(7)

The above it is fed through a file (‗lsq.m‘) to Matlab. The error is represented in the

form of the equation. Matlab‘s function ‗lsq‘ is utilized for the simulation.

Page 46: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

46

Stage 1: Matlab‘s [14] procedure is used with the above file

function F = lsq(pid, a1, a2)

Kp = pid(1);

Ki = pid(2);

Kd = pid(3);

% solver

opt = simset('solver', 'ode5', 'SrcWorkspace', 'Current');

[tout, xout, yout] = sim('optsim', [0 100], opt);

F = yout-1; % error

‗optroutine‘ file for the model is:

Stage 2: Matlab‘s [14] procedure for ‗optroutine‘

pid0 = [1 10 12]

a1 = 0; a2 = 0.0005;

options = optimset('LargeScale', 'off', 'Display', 'iter', 'TolX', 0.001, 'TolFun', 0.001);

pid = lsqnonlin('lsq', pid0, [], [], options, a1, a2)

Kp = pid(1); Ki = pid(2); Kd = pid(3);

The values for the three ―Ks‖ are specified before invoking ‗lsq‘. Based on the

constraints for the Bearcat II the execution of the routine optimizes the model based

on the function. A simulation is executed by choosing a solver. The simulation and

Page 47: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

47

optimization provides a solution for the P, I and D values after fifty five runs. The

output from the Matlab run follows below.

pid0 =

1 5 10

Directional

Iteration Func-count Residual Step-size derivative Lambda

1 3 4.76719e+012 1 -4.91e+012

2 10 4.70723e+012 0.375 -1.51e+011 1.32032e+012

3 17 4.65431e+012 0.253 -2.33e+011 8.77204e+011

4 24 4.58281e+012 0.293 -8.38e+010 1.68981e+012

5 31 4.56367e+012 0.0868 -8.32e+010 2.02202e+012

6 39 4.53102e+012 0.119 -1.63e+011 2.60576e+012

7 55 4.53102e+012 3.28e-007 -3.27e+011 1.07078e+018

Page 48: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

48

pid =

0.7234 4.9399 10.0233

Here are the values for the parameters:

Kp = 0.7235; Ki = 4.9399; Kd = 10.0233

The simulation is run by feeding the values for P, I and D. The following shows the

response.

Time (seconds)

Figure 6.5 Step response for using the optimized values

The results as it relates to Bearcat II are discussed in the conclusions, and

recommendations for further work are also specified.

Page 49: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

49

Chapter 7

7. Results and summary

The PID values obtained through the optimization method are the minimum mean

square error solution needed for the time response of the control system. This is

because it tries to minimize the error between the input and output. The step response

plot using the optimized value is also plotted. Optimized PID values are better as seen

by comparing both the plots.

In the graph using optimized values the signal rises to the required level faster (at

time t = 200 using the optimized PID values, whereas at time t = 300 for starting

values). Hence the optimized values are definitely better than the previous values. It

is also a better alternative to the trial and error method used presently on the current

robot. The method is also more scientific and logical approach to a difficult problem

of tuning the PID controller.

The obtained values can be compared directly to the results obtained with the WSDK

kit to see the response of the system rather than trying iterative values. But, the kit

can be used to fine-tune the PID values after we arrive at the optimized value.

Page 50: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

50

Chapter 8

8. Recommendations

Due the complex nature of framing the model, a generalized model was taken for

optimization. In future methods more work could be done to model actual control

systems for individual applications and be solved using the optimization routine.

Even though the iterative steps are eliminated, a better method for choosing the initial

parameter values should be developed.

This thesis deals with only one of the optimization methods but there are many more

methods to solve multi objective nonlinear problems. One of them is using a minmax

approach. More work could be directed toward that area where many routines are

used on the same problem and the best control parameters chosen. Based on those the

software kit can be used to fine-tune the values.

A stable testing platform, Bearcat II is available for testing. Various values can be

used in the program and the performance evaluated.

Page 51: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

51

9. References

[1] Chaktravarthy, K. K., 1998, ―Steering Control System Design and Analysis for an

Unmanned Autonomous Mobile Robot,‖ Master‘s Thesis.

[2] Krishnamohan, K., 1998, ―Control System Design,‖ Master‘s Thesis.

[3] Miller, R. K., 1987, ―Automated Guided Vehicles and Automated

Manufacturing,‖ Society of Manufacturing Engineers, Dearborn, Michigan.

[4] Tagawa, Y., Ogata, H., Morita, K., Nagai, M., Mori, H., 1996, ―Robust active

steering system taking account of nonlinear dynamics,‖ Vehicle System Dynamics, v

25 n Suppl, pp. 668-681.

[5] Hattori, A. K., Yamada, K., Ooba, K., Ueki, K., Nakano, E., 1993, ―Control

system for an autonomous driving vehicle,‖ Heavy Vehicle Systems, v 1 n 1 pp. 99-

113.

[6] Ozguner, U. U., Konur, A. ., 1995, „Analytical study of vehicle steering control,‖

IEEE Conference on Control Applications - Proceedings 1995. IEEE, Piscataway, NJ,

USA,95CH35764, p 125-130.

[7] Ackermann, J., Guldner, J., Sienel, W., Steinhauser, R., Utkin, V. I., 1995,

―Linear and nonlinear controller design for robust automatic steering,‖ IEEE

Transactions on Control Systems Technology. v 3 n 1, pp. 132-142.

Page 52: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

52

[8] Sung, E., Loon, N. Kok., Chiang, Y. Y.,, 1989, ―Parallel linkage steering for an

automated guided vehicle,‖ IEEE Control Systems Magazine. v 9 n 6, pp. 3-8.

[9] Nise, N. S., 1992, Control systems engineering, Benjamin/Cummings Pub. Co.,

Redwood City, California

[10] VanDoren V. J., March 1998, ―Tuning Fundamentals – Basics of Proportional –

Integral – Derivative Control‖, Control Engineering.

[11] expertune.com/tutor.html, ―What Is PID—Tutorial Overview‖

[12] Galil Inc, DMC-1000 Technical Reference Guide Ver 1.1, Sunnyvale, California

1993.

[13] Math Works Inc., 1996, Matlab Control System Toolbox User‘s Guide.

[14] Math Works Inc., 1996, Matlab Optimization Toolbox.

[15] Abdin, M. F., 1987, ―An investigation of the potentials of Bi-directioanl AGV

Systems,‖ proc. 5th intl. AGVS conf., Tokyo.

[16] Larcombe, M. H. E., 1973, ―Tracking Stability of Wire Guided Vehicles,‖proc.

1st Intl. AGVS cong., pp. 137-144.

[17] Will, A. B., Zak, S. H., 1997, ―Modelling and control of an automated vehicle,‖

Vehicle System Dynamics. v 27 n3, pp 131-155.

Page 53: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

53

[18] Zadeh, A. G., Fahim, A. E. M., 1997, ―Neural network and fuzzy logic

applications to vehicle systems: Literature survey,‖ International Journal of Vehicle

Design. v 18 n 2, pp. 132-193.

[19] Chaktravarthy, K. K., Hall, E. L., 1997, ― Steering Control System for a Mobile

Robot,‖ Proceedings of SPIE - The International Society for Optical Engineering. v

2591, Society of Photo-Optical Instrumentation Engineers, Bellingham, WA, USA.

[20] Chaktravarthy, K. K., Mallikarjun, S., Krishnamohan, K., Hall, E. L., 1997,

―Speed Control for a Mobile Robot,‖ Proceedings of SPIE - The International Society

for Optical Engineering, v 2591. Society of Photo-Optical Instrumentation Engineers,

Bellingham, WA, USA

[21] Kamga, A., Rachid, A., 1996 , ―Speed, steering angle and path tracking controls

for a tricycle robot,‖ Proceedings of the IEEE International Symposium on Computer-

Aided Control System Design., 96TH8136., pp. 56-61.

[22] Matthews, B. O., Ruthemeyer, M. A., Perdue, D., Hall, E. L., 1995,

―Development of a mobile robot for the 1995 AUVS competition,‖ Proceedings of

SPIE - The International Society for Optical Engineering. v 2591. Society of Photo-

Optical Instrumentation Engineers, Bellingham, WA, USA,pp. 194-201.

[23] Samu, T., Kelkar, N., Perdue, D., Ruthemeyer, M. A., Matthews, B. O., Hall, E.

L., 1996, ―Line following using a two camera guidance system for a mobile robot,‖

Proceedings of Spie - the International Society for Optical Engineering. v 2904, pp.

290-297.

Page 54: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

54

[24] Yoshimoto, K., Sakatoh, M., Takeuchi, M., Ogawa, H., 1995, ―Automatic

steering control algorithm using optical flow,‖ Jsae Review. v 16 n2, pp. 165-169.

[25] BenAmar, Faiz., 1997, ―Steering behaviour and control of fast wheeled robots,‖

IEEE International Conference on Intelligent Robots and Systems. v 3, IEEE,

Piscataway, NJ, USA,97CB36108., pp. 1396-1401.

[26] Fourie, C. J., Deist, L. A., 1993, ―Fuzzy algorithm for the control of a mobile

robot,‖ IEEE 2nd International Workshop on Emerging Technologies and Factory

Automation, pp. 42-50.

[27] Lucibello, P., 1994, ―State steering by learning for a class of nonlinear control

systems,‖ Automatica. v 30 n 9,pp. 1463-1468.

[28] Mori, Y., Nyudo, S., 1993, ―Steering and speed control of a car by fuzzy-neural

control,‖ Proceedings of the International Joint Conference on Neural Networks. Publ

by IEEE, IEEE Service Center, Piscataway, NJ, USA. v 2, pp 1753-1756.

[29] Hilton, J. D., Hilton, D. J., ―Design of an automatic steering and speed

controller for a horticultural gantry machine,‖ National Conference Publication -

Institution of Engineers, Australia. Publ by IE Aust, Barton, Aust. n 92 pt 11., pp.

103-107.

[30] Pears, N. E., Bumby, J. R., 1991, ―Steering control of an experimental

autonomous vehicle,‖ Transactions of the Institute of Measurement & Control. v 13 n

4, pp. 190-200.

Page 55: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

55

[31] Kehtarnavaz, N. S. W., ―Steering control of autonomous vehicles by neural

networks,‖ Proceedings of the American Control Conference. Publ by American

Automatic Control Council, Green Valley, AZ, USA (IEEE cat n 91CH2939-7). v 3.,

pp. 3096-3101.

[32] Sawada, T., Oguchi, Y. S. C., ―Basic study on the influence of aging on steering

control,‖ Proceedings – Society of Automotive Engineers. Publ by SAE, Warrendale,

PA, USA, pp. 763-769.

[33] Krogh, B. H., 1985, ―Guaranteed steering control,‖ Proceedings of the American

Control Conference, Publ by IEEE, New York, NY, USA Available from IEEE

Service Cent (Cat. n 85CH2119-6), Piscataway, NJ, USA, pp. 950-955.

[34] McMahon, C. B., Tennes, B. R., Burkhardt, T. H., ―Performance results:

microprocessor-based steering controller using ultrasonic sensors,‖ Paper - American

Society of Agricultural Engineers Joseph, Mich, USA 83-1568,. Publ by ASAE, St.

34p

[35] Warwick, K., 1989, Control systems: an introduction, Prentice Hall, New York

[36] Thompson, S., 1989, Control systems engineering and design, Longman

Scientific & Technical, Wiley, New York, NY.

[37] Nagrath, I. J., Gopal M., 1975, Control systems engineering, Wiley, New York.

[38] Phillips, C. L., Harbor, R. D., 1991, Basic feedback control systems, Prentice

Hall, Englewood Cliffs, N.J.

Page 56: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

56

[39] Clarence, J. M., 1987, Computer-aided design of feedback control systems for

time response, Instrument Society of America, Research Triangle Park, N.C.

[40] Phillips, C. L., Nagle, T. H., 1995, Digital control system analysis and design,

Prentice Hall, Englewood Cliffs, N.J.

[41] Santina, M. S., Stubberud, A. R., Hostetter, G. H., 1994, Digital control system

design, Saunders College Pub., Fort Worth.

[42] Kuo, B. C., , 1992, Digital control systems, Saunders College Pub., Fort Worth.

[43] Alberto Isidori A., 1995, Nonlinear control, Springer, Berlin; New York.

[44] Cheng, R. M. H., Xiao, J. W., LeQuoc, S., ―Neuromorphic controller for AGV

steering,‖ Proceedings of the IEEE International Conference on Robotics and

Automation, IEEE, Piscataway, NJ, v 3., pp 2057-2062.

[45] Milacic, V. R., Putnik, G. D., 1989, ―Steering rules for AGV based on primitive

function and elementary movement control,‖ Robotics and Computer-Integrated

Manufacturing, v 5 n 2-3,pp 249-254.

[46] Cheng, R. M. H., Rajagopalan, R., 1992, ―Kinematics of automatic guided

vehicles with an inclined steering column and an offset distance, criterion for

existence of inverse kinematic solutions,‖ Journal of Robotic Systems, v 9 n 8, pp

1059-1081.

Page 57: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

57

[47] Kim O. H., 1987, ―Optimal Steering Control of an Auto-Guided-Vehicle with

Two Motored Wheels,‖ Transactions of the Institute of Measurement & Control. v 9

n 2, pp 58-63.

[48] Muir, P.F., Neuman, C. P., 1987, "Kinematic Modeling of Wheeled Mobile

Robots," Journal of Robotic Systems, 4(2), pp. 281-340.

[49] Hall, E. L., Hall B. C., 1985, Robotics: A User-Friendly Introduction, Holt,

Rinehart, and Winston, New York, NY.

[50] Cheng, R. M. H., Rajagopalan, R., 1992, "Kinematics of Automated Guided

Vehicles with an Inclined Steering Column and an Offset Distance: Criteria for

Existence of Inverse Kinematic Solution," Journal of Robotic Systems, 9(8), 1059-

1081.

[51] General Electric, 1986, EV-1 SCR Control Manual, Charlottesville, Virginia.

[52] Reliance Electric, 1993, Electro-Craft BDC-12 Instruction Manual, Eden Prairie,

Minnesota.

[53] Fauver Corp., 1993, Parker Linear Actuators Catalog, Cincinnati, Ohio.

[54] Delco Corp., 1993, Motor Specifications, Dayton, Ohio.

[55] BEI Motion Systems Company, 1992, Model H20 Technical Specifications,

Goleta, California.

Page 58: CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT Center for Robotics... · CONTROL SYSTEM DESIGN FOR AN AUTONOMOUS MOBILE ROBOT A thesis submitted to the Division of Graduate

58

10. Appendix

MATLAB code for the calculation of digital gains

Section of code which takes in digital gains and converts them into analog gains

GN=800

ZR=0.9

PL=0

KI=0

% Given GN...solve for K,A,B,C

K=GN;

A=ZR;

B=PL/256;

C=KI/8;

% solve for a,b,g,f

a= (2000-2000*A)/(1+A)

b= (2000-2000*B)/(1+B)

f=1000*C

g=K*(1+A)/(1+B)