Open access

Control Laws Design and Validation of Autonomous Mobile Robot Off-Road Trajectory Tracking Based on ADAMS and MATLAB Co-Simulation Platform

Written By

Yang. Yi, Fu. Mengyin, Zhu. Hao and Xiong. Guangming

Submitted: 11 November 2010 Published: 09 September 2011

DOI: 10.5772/20954

From the Edited Volume

Applications of MATLAB in Science and Engineering

Edited by Tadeusz Michałowski

Chapter metrics overview

3,788 Chapter Downloads

View Full Metrics

1. Introduction

Autonomous automobile technology is a rapidly developing field, with interest in both academia and industry. Outdoor navigation of autonomous vehicles, especially for rough-terrain driving, has already been a new research focus. DARPA Grand Challenge and LAGR program stand for the top development level in this research region. Rough-terrain driving research offers a challenge that the in-vehicle control system must be able to handle rough and curvy roads, and quickly varying terrain types, such as gravel, loose sand, and mud puddles – while stably tracking trajectories between closely spaced hazards. The vehicle must be able to recover from large disturbances, without intervention (Gabriel, 2007).

Since robotics autonomous navigation tasks in outdoor environment can be effectively performed by skid-steering vehicles, these vehicles are being widely used in military affairs, academia research, space exploration, and so on. In reference (Luca, 1999), a model-based nonlinear controller is designed, following the dynamic feedback linearization paradigm. In reference (J.T. Economou, 2000), the authors applied experimental results to enable Fuzzy Logic modelling of the vehicle-ground interactions in an integrated manner. These results illustrate the complexity of systematic modeling the ground conditions and the necessity of using two variables in identifying the surface properties. In reference (Edward, 2001), the authors described relevant rover safety and health issues and presents an approach to maintaining vehicle safety in a navigational context. Fuzzy logic approaches to reasoning about safe attitude and traction management are presented. In reference (D. Lhomme-Desages, 2006), the authors introduced a model-based control for fast autonomous mobile robots on soft soils. This control strategy takes into account slip and skid effects to extend the mobility over planar, granular soils. Different from above researches, which control the robots on the tarmac, grass, sand, gravel or soil, this chapter focuses on the motion control for skid-steering vehicles on the bumpy and rocklike terrain, and presents novel and effective trajectory tracking control methods, including the longitudinal, lateral, and sensors pan-tilt control law. Furthermore, based on ADAMS&MATLAB co-simulation platform, iRobot ATRV2 is modelled and the bumpy off-road terrain is constructed, at the same time, trajectory tracking control methods are validated effectively on this platform.

Advertisement

2. Mobile robot dynamic analysis

To research on the motion of skid-steering robots, the 4-wheeled differentially driven robot, which is moving on the horizontal road normally without longitudinal wheel slippage, is analyzed for kinematics and dynamics. As shown in Fig. 1 (a), global Descartes frame and in-vehicle Descartes frame are established. In Global frame O X Y Z , its origin O is sited on the horizontal plane where the robot is running, and Z axis is orthogonal to the plane; in in-vehicle frame o x y z , its origin o is located at the robot center of mass, z axis is orthogonal to the chassis of robot, x axis is parallel to the rectilinear translation orientation of the robot and y axis is orthogonal to the translation orientation in the plane of the chassis. The robot wheelbase is A and the distance between the left and right wheels is B . According to the relation between O X Y Z and o x y z , the kinematics equation is as follows.

[ X ˙ Y ˙ ] = [ x ˙ cos θ y ˙ sin θ x ˙ sin θ + y ˙ cos θ ] = [ cos θ sin θ sin θ cos θ ] [ x ˙ y ˙ ] E1

The derivative of equation (1) with respect to time is

[ X ¨ Y ¨ ] = [ cos θ sin θ sin θ cos θ ] [ x ¨ y ˙ θ ˙ y ¨ x ˙ θ ˙ ]         = [ cos θ sin θ sin θ cos θ ] [ a x a y ] E2

Figure 1.

Dynamics analysis of the robot and the motion constraint about C o

In the above equations, X ˙ , Y ˙ , X ¨ , Y ¨ represent the absolute longitudinal and lateral velocities, and the absolute longitudinal and lateral accelerations respectively; θ is the angle between x and X axes. x ˙ , y ˙ , θ ˙ denote longitudinal, lateral and angular velocities in in-vehicle frame, respectively; a x , a y are the longitudinal and lateral acceleration respectively in in-vehicle frame.

The equations of the robot motion are as follows:

{ m a x = i = 1 4 F x i i = 1 4 f x i m a y = i = 1 4 f y i J θ ¨ = ( B / 2 ) ( ( F x 1 F x 3 ) + ( F x 2 + F x 4 ) ) M r E3

where J is the moment of inertia of the robot; F x i denotes the tractive force produced by the i -th wheel, and composes the outside tractive force F o u t s i d e and the inside F i n s i d e ; f x i is the longitudinal resistance of the i -th wheel; f y i is the lateral resistance of the i -th wheel; M r is the resistive moment around the center of o .

During the turning, the robot is subject to the centripetal force f c e n , the equation of which is,

f c e n cos β = f y 3 + f y 4 f y 1 f y 2 E4

Let μ r and μ s be the coefficient of longitudinal rolling resistance and the coefficient of lateral friction respectively. In (4), β is the angle between C o o and y axis. Accordingly, when the centripetal acceleration is considered, assume β 0 , then the equation of the tractive force of the robot is,

{ F o u t s i d e = ( m g 2 + h m a y B ) μ r + m a y x c o 2 R + μ s m g A 4 B [ 1 ( a y g μ s ) 2 ] F i n s i d e = ( m g 2 h m a y B ) μ r + m a y x c o 2 R μ s m g A 4 B [ 1 ( a y g μ s ) 2 ] E5

where h is the height of the robot center of mass, the distance between the robot center of mass and the ground, and R is the radius of the robot turning (J. Y. Wong, 1978).

In the context of the robot motion around instantaneous, fixed-axis rotation, the straight line motion of the robot can be referred to R = . C o is the instantaneous center of the rotation, and the coordinates of C o can be expressed as [ x c o y c o ] T = [ y ˙ θ ˙ x ˙ θ ˙ ] T

In Fig. 1 (b), the real line arrowheads represent the transfer orientations of the four wheels of the robot, that is C o moves within the wheelbase range of the robot; the dashed arrowheads stand for the transfer orientations of the four wheels of the robot, when C o , that is C o , moves beyond the wheelbase range of the robot. Clearly, if C o moves out of the wheelbase range, the lateral transfer orientations of four wheels are the same; as a result, the motion of the robot will be out of control. The motion constraint is as follows,

[ sin θ cos θ l ] [ X ˙ Y ˙ θ ˙ ] = 0     ( | l | A / 2   ) E6

where l is the distance from C o to y axis. According to Fig. 1 (a) and equation (5), it is l = A a y cos β / 2 μ s g that can be obtained. Therefore, the constraint of the motion, shown as follow, is imperative.

( x ˙ ) 2 / R μ s g  or  ( θ ˙ ) 2 R μ s g E7

In this paper, a description of trajectory space (Matthew Spenko, 2006) is presented according to the robot’s dynamic analysis, which is defined as the two-dimensional space of the robot’s turning angular speed θ ˙ and longitudinal velocity V l o n g , ( V l o n g = x ˙ ) . This kind of description is very useful during motion control. Consider inequalities (7): ( V l o n g ( t ) ) 2 / R μ s g or ( θ ˙ ( t ) ) 2 R μ s g , it is easy to get | V l o n g ( t ) | μ s g R or | θ ˙ ( t ) | μ s g / R , then take another constraint into consideration, V l o n g = θ ˙ R , now a figure of the robot’s ( V , θ ˙ ) space (see Fig. 2.) can be obtained. The boundary curve in the figure satisfies V l o n g ( t ) θ ˙ ( t ) = μ s g . When the robot’s ( V , θ ˙ ) state is in the shadow region, that’s to say V l o n g ( t ) θ ˙ ( t ) μ s g , the robot is safe, which means the hazardous situation like side slippage won’t occur. As a result, inequalities (7) is crucial for control decision making.

Fig. 2. The ( V , θ ˙ ) space of motion control of the robot. (In this figure, μ s = 0.49 and g = 9.8 m / s 2 )

Advertisement

3. Trajectory tracking control laws design

Autonomous mobile robot achieves outdoor navigation by three processes, including the environment information acquired by the perception module, the control decision made by the planner module, and the motion plan performed by the motion control module (Gianluca, 2007). Consequently, for safe and accurate outdoor navigation it is vital to harmonize the three modules performance. In this paper, the emphasis is focused on the decision of control laws of the robot, and these controlled objects include the longitudinal velocity, the lateral velocity, and the angles of sensor pan-tilts.

As shown in Fig. 3, in an off-road environment, the robot uses laser range finder (LRF) with one degree of freedom (DOF) pan-tilt (only tilt) to scan bumpy situation of the close front ground, on which the robot is moving, and employs stereo vision with two DOF pan-tilt to perceive drivable situation of far front ground. With the data accessed from laser and vision sensors, the passable path can be planned, and the velocities of left and right robot’s sides can be controlled to track the path, consequently, the robot off-road running is completed.

Figure 2.

Off-road driving of the robot

3.1. Longitudinal control law

In this section, a kind of humanoid driving longitudinal control law based on fuzzy logic is proposed. First, the effect factors to the longitudinal velocity are classified. As shown in Fig. 4,

Figure 3.

The longitudinal control law of the robot

these factors include curvature radius of trajectory, road roughness, process time of sensors and speed requirement. Based on the four factors and the analysis of kinematics and dynamics, the longitudinal velocity equation can be given,

V l o n g = ( μ c v ( r c ) + μ r r ( R r o u g h ) ) μ t ( T s e n ) μ v ( V r e ) V r e E8

where V l o n g is longitude velocity command, μ c v , μ r r , μ t and μ v are the weight factors of the curvature radius of trajectory r c , road roughness R r o u g h , processing time of sensors T s e n and speed requirement V r e respectively. The weight factors can vary within [ 0 , 1 ] .

3.2. Lateral control law

Autonomous vehicle off-road driving is a special control problem because mathematical models are highly complex and can’t be accurately linearized. Fuzzy logic control, however, is robust and efficient for non-linear system control (Gao Feng, 2006), and a well-tested method for dealing with this kind of system, provides good results, and can incorporate human procedural knowledge into control algorithms. Also, fuzzy logic lets us mimic human driving behavior to some extent (José E. Naranjo, 2007). Therefore, the paper has presented a kind of novel fuzzy lateral control law for the robot off-road running.

Thereafter, the lateral control law is designed for the purpose of position tracking by adjusting navigation orientation to reduce position error.

Definition: When the robot moves toward the trajectory, the orientation angle of the robot is positive, whichever of the two regions, namely left error region and right error region of the tracking position, the robot is in. When the robot moves against the trajectory, the angle is negative. When the robot motion is parallel to the trajectory, the angle is zero.

Figure 4.

Plots of membership functions of e d and θ e . The upper plot stands for μ ( e d ) . [ 0.1 , 0.1 ] is the range of the c e n t e r region, μ ( e d ) = 1.0 in this region. The lower plot expresses μ ( θ e ) , which is indicated with triangle membership function. In this figure, the colorful bands represent the continuous changing course of e d .

In the course of trajectory tracking of the robot, position error e d and orientation error θ e , which are the error values between the robot and the trajectory, are the inputs of the lateral controller. First, the error inputs, including the position error and the orientation error, are pre-processed to improve steady precision of the trajectory tracking, and restrain oscillation of that. The error E can be written as E = E ¯ + Δ E , where E ¯ is the result of smoothing filter about E , i.e. E ¯ = i n + 1 i e i / n , Δ E forecasts the error produced in the next system sample time, Δ E = i n + 1 i k e i e i / n   ( i n ) .

As a result, E = i n + 1 i ( 1 + k e i ) e i / n    ( i n ) , n = 4 , k e i = f e i ( x ˙ , T s ) .

T s represents system sample time. Second, the error inputs, after being pre-processed, are fuzzyfication-processed. As shown in Fig. 5, degree of membership μ ( e d ) and μ ( θ e ) are indicated in terms of triangle and rectangle membership functions:

Part One: the space of e d is divided into L B , L S , M C , R S , R B . According to the result of the e d division, the phenotype rules of the lateral fuzzy control law hold.

Part Two: the space of θ e is also divided into L B , L S , M C , R S , R B . According to the result of the θ e division, the recessive rules of the control law are obtained.

It is necessary to explain that the phenotype rules are the basis of the recessive rules, namely each phenotype rule possesses a group of relevant recessive rules. Each phenotype rule has already established their own expectation orientation angle θ ˜ e , that is to say the robot is expected to run on this orientation angle, θ ˜ e , and this angle is the very center angle of this group recessive rules. When the center angle, θ ˜ e , of each group of recessive rules is varying, the division of θ e of each group recessive rules changes accordingly.

All of the control rules can be expressed as continuous functions: f L B , f L S , f M C , f R S , f R B , and, consequently, the global continuity of the control rules is established.

The functions, f L B , f L S , f R S , f R B , which express the rule functions of the n o n c e n t e r region of e d , are as follows:

θ ˙ = k θ ˜ e k t ( θ ˜ e θ e ) T s + k t θ ˙ ˜ t r E9

In (9), θ ˜ e is the expectation tracking-angle in the current position-error region, and θ ˜ e is monotonically increasing with e d . θ ˜ e can be given by this formula θ ˜ e = arctan k e d e d V l o n g , k e d = μ D L ( e d ) k D L + μ D S ( e d ) k D S where μ D L stands for the large error region, including L B and R B , membership degree of e d , and μ D S represents the small error region, including L S and R S , membership degree of e d . θ ˙ ˜ t r is the estimation of the trajectory-angle rate. k θ ˜ e can be worked out by this equation: k θ ˜ e = μ θ L ( θ e ) k θ L + μ θ S ( θ e ) k θ S ,where μ θ L stands for the large error region, including L B and R B , membership degree of θ e , and μ θ S denotes the small error region, including L S and R S , membership degree of θ e . k D L and k θ L express the standard coefficients of the large error region of e d and θ e ; k D S and k θ S indicate the small error region of e d and θ e , respectively. k t is the proportional coefficients of the system sample time T S .

f M C is deduced as follows:

Figure 5.

Tracking trajectory of the robot. In this Figure, the red dashdotted line stands for the trajectory tracked by the robot. The different color dotted lines represent the bounderies of the different error regions of e d .

When the robot moves into the center region at the orientation of α , the motion state of the robot can be divided into two kinds of situations.

Situation One: Assume that α has decreased into the rule admission angular range of center region, i.e. 0 α θ c e n t , where θ c e n t , which is subject to (7), is the critical angle of center region. To make the robot approach the trajectory smoothly, the planner module requires the robot to move along a certain circle path. As the robot moves along the circle path in Fig. 6, the values of e d and θ e decrease synchronously. In Fig. 6, λ is the variety range of e d in the center region. α is the angle between the orientation of the robot and the trajectory when the robot just enters the center region. R 2 λ / α 2 can be worked out by geometry, and in addition, the value of α is very small, so the process of approaching trajectory can be represented as Δ α = α Δ λ λ .

Situation Two: When α 0 or α θ c e n t . If the motion decision from the planner module were the same as Situation One, the motion will not meet (7). According to the above analysis, the error of tracking can not converge until the adjusted θ ˜ e makes α be true of Situation One. Therefore, the purpose of control in Situation Two is to decrease θ e .

Based on the above deduction, f M C is as follow:

θ ˙ = k t ( θ ˜ e θ e ) T s + k t θ ˜ ˙ t r E10

Where θ ˜ e = e d θ c e n t λ , λ is the variety range of e d in the center region, [ 0.1 m , 0 ] o r [ 0 , 0.1 m ] . θ ˙ is the output of (9) and (10), at the same time, θ ˙ is subject to (7), consequently, ( θ ˙ ) 2 R μ s g is required by the control rules.

The execution sequence of the control rules is as follows:

First, the phenotype control rules are enabled, namely to estimate which error region ( L B , L S , M C , R S , R B ) the current e d of the robot belongs to, and to enable the relevant recessive rules; Second, the relevant recessive rules are executed, at the same time, θ ˜ e is established in time.

The lateral control law is exemplified in Fig. 7. In this figure, the different color concentric circle bands represent the different position error e d . From the outermost circle band to the

Figure 6.

Plot of the lateral control law of the robot. These dasheds stand for the parts of the performance result of the control law.

center round, the values of e d is decreasing. The red center round stands for M C of e d , that is the center region of e d . At the center point of the red round, e d = 0 . According to the above definition, the orientation range of the robot is ( π , π ] , and the two 0 degree axes of θ e stand for the 0 degree orientation of the left and right region of the trajectory, respectively. At the same time, π / 2 axis and π / 2 axis of θ e are two common axes of the orientation of the robot in the left and right region of the trajectory. In the upper sub-region of 0 degree axes, the orientation of the robot is toward the trajectory, and in the lower sub-region, the orientation of the robot is opposite to the trajectory. The result of the control rules converges to the center of the concentric circle bands according to the direction of the arrowheads in Fig. 7. Based on the analysis of the figure, the global asymptotic stability of the lateral control law can be established, and if e d = 0 and θ e = 0 , the robot reaches the only equilibrium zero. The proving process is shown as follow:

Proof: From the kinematic model (see Fig. 8.), it can be seen that the position error of the robot e d satisfies the following equation,

Figure 7.

Trajectory Tracking of the mobile robot

e ˙ d ( t ) = V l o n g ( t ) sin ( θ ˜ e ( t ) ) E11
  • When the robot is in the non – center region, a controller is designed to control the robot’s lateral movement:

θ ˜ e ( t ) = arctan k e d e d ( t ) V l o n g ( t ) E12

Combining Equations (11) and (12), we get

e ˙ d ( t ) = V l o n g ( t ) sin ( arctan ( θ ˜ e ( t ) ) ) = k e d e d ( t ) 1 + ( k e d e d ( t ) V l o n g ( t ) ) 2 E13

Figure 8.

LRF Pan-Tilt and Stereo Viszion Pan-Tilt motion

As the sign of e ˙ d is always opposite that of e d , e d will converge to 0 . In equation (11), | e ˙ d ( t ) | V l o n g ( t ) , and | e ˙ d ( t ) | k e d e d ( t ) can formed by equation (13). Therefore the convergence rate of e d is between linear and exponential. When the robot is far away from the trajectory, it’s heading for trajectory vertically, then θ ˜ e = π 2 , e ˙ d ( t ) = V l o n g ( t ) , e d ( t ) = V l o n g ( t ) + e d ( t 0 ) ,when the robot is near the trajectory, e d 0 , then in equation (12), 1 + ( k e d e d ( t ) V l o n g ( t ) ) 2 1 , e ˙ d ( t ) = k e d e d ( t ) .

According to equation (12), e d and θ ˜ e can converge to 0 simultaneously.

  • When the robot enters the center region, another controller is designed,

θ ˜ e ( t ) = e d ( t ) θ c e n t λ E14

Combining Equations (11) and (14), we get e ˙ d = V l o n g sin ( e d θ c e n t λ )

In this region, e d is very small, and consequently, e d θ c e n t λ will also be very small, and then sin ( e d θ c e n t λ ) e d θ c e n t λ is derived. Therefore, e ˙ d = V l o n g e d θ c e n t λ = V l o n g θ c e n t λ e d , and then e d ( t ) = e d ( t 1 ) exp { V l o n g θ c e n t λ } ,where t 1 is the time when the robot enters the center region. In other word, e d converges to 0 exponentially. Then, according to θ ˜ e ( t ) = e d θ c e n t λ , θ ˜ e ( t ) converges to 0 .

So the origin is the only equilibrium in the ( e d , θ ˜ e ) phase space.

3.3. LRF Pan-tilt and stereo vision pan-tilt control

Perception is the key to high-speed off-road driving. A vehicle needs to have maximum data coverage on regions in its trajectory, but must also sense these regions in time to react to obstacles in its path. In off-road conditions, the vehicle is not guaranteed a traversable path through the environment, thus better sensor coverage provides improved safety when traveling. Therefore, it is important for off-road driving to apply active sensing technology. In the chapter, the angular control of the sensor pan-tilts assisted in achieving the active sensing of the robot. Equation (15) represents the relation between the angles measured, i.e. φ c , γ c and γ l , of the sensors mounted on the robot and the motion state, i.e. θ e and x ˙ , of the robot.

[ φ c γ c γ l ] = [ k φ c 0 0 0 k γ c 0 0 0 k γ c ] [ θ e x ˙ x ˙ ] E15

In (15), φ c , γ c are the pan angle and tilt angle of the stereo vision respectively. γ l is the tilt angle of the LRF; k φ c , k γ c and k γ l are the experimental coefficients between the angles measured and the motion state, and they are given by practical experiments of the sensors and connected with the measurement range requirement of off-road driving. At the same time, the coordinates of the scanning center are x e c = x c + h c cot γ c cos φ c , y e c = y c + h c cot γ c sin φ c ; and x e l = x l + h l cot γ l , y e l = 0 . In the above equations, x c , y c , x l , y l , respectively, are the coordinates of the sense center points of the stereo vision and LRF in in-vehicle frame. As shown in Fig. 9, h c and h l are their height value, to the ground, accordingly.

The angular control and the longitudinal control are achieved by P I controllers, and they are the same as the reference (Gabriel, 2007).

Advertisement

4. Simulation tests

4.1. Simulation platform build

In this section, ADAMS and MATLAB co-simulation platform is built up. In the course of co-simulation, the platform can harmonize the control system and simulation machine system, provide the 3 D performance result, and record the experimental data. Based on the analysis of the simulation result, the design of experiments in real world can become more reasonable and safer.

First, based on the character data of the test agent, ATRV2, such as the geometrical dimensions ( H L W 65 × 105 × 80 c m ) , the mass value ( 118 K g ) , the diameter of the tire ( Φ 38 c m ) and so on, the simulated robot vehicle model is accomplished, as shown in Fig.10.

Figure 9.

ATRV2 and its model in ADAMS

Second, according to the test data of the tires of ATRV2, the attribute of the tires and the connection character between the tires and the ground are set. The ADAMS sensor interface module can be used to define the motion state sensors parameters, which can provide the information of position and orientation to ATRV2.

It is road roughness that affects the dynamic performance of vehicles, the state of driving and the dynamic load of road. Therefore, the abilities of overcoming the stochastic road roughness of vehicles are the key to test the performance of the control law during off-road driving. In the paper, the simulation terrain model is built up by Gaussian-distributed pseudo random number sequence and power spectral density function (Ren, 2005). The details are described as follows:

  • Gaussian-distributed random number sequence x ( t ) , whose variance σ = 18 and mean E = 2.5 , is yielded;

  • The power spectral S X ( f ) of x ( t ) is worked out by Fourier transform of R X ( τ ) , which is the autocorrelation function of σ ,

S X ( f ) = + R X ( τ ) e j 2 π f τ d τ           = T σ 2 ( sin π f T π f T ) 2 E16

where T is the time interval of the pseudo random number sequence;

  • Assume the following,

y ( t ) = x ( t ) h ( t ) = + x ( τ ) h ( t τ ) d τ E17
h ( t ) = + H ( f ) e j 2 π f t d f E18

where h ( t ) is educed by inverse Fourier transform from H ( f ) , and they both are real even functions, then,

H ( f ) = S Y ( f ) S X ( f ) E19
y k = y ( k T )      = T M + M x ( r T ) h ( k T r T ) = T M + M x r h k r E20

where S Y ( f ) is the power spectral of y ( t ) , y k is the pseudo random sequence of S Y ( f ) , k = 0 , 1 , 2 , N , and M can be established by the equation lim m M h m = h ( M T ) = 0 ;

  • Assign a certain value to the road roughness and adjust the parameters of the special points on the road according to the test design, and the simulation test ground is shown in Fig. 11.

Figure 10.

The simulation test ground in ADAMS

4.2. Simulation tests

In this section, the control law is validated with the ADAMS&MATLAB co-simulation platform.

Based on the position-orientation information provided by the simulation sensors and the control law, the lateral, longitudinal motion of the robot and the sensors pan-tilts motion are achieved. The test is designed to make the robot track two different kinds of trajectories, including the straight line path, sinusoidal path and circle path. In Test One, the tracking trajectory consists of the straight line path and sinusoidal path, in which the wavelength of the sinusoidal path is 5 π m , the amplitude is 3 m . The simulation result of Test One is shown in Fig. 12. In Test Two, the tracking trajectory contains the straight line path and circle path, in which the radius of the circle path is 5 m . The simulation result of Test Two is shown in Fig. 13.

Figure 11.

Plots of the result of Test One ( T s = 0.05 s )

Figure 12.

Plots of the result of Test Two ( T s = 0.05 s )

In Fig. 12, which is the same as Fig. 13, sub-figure a is the simulation data recorded by ADAMS. In sub-figure a, the upper-left part is the 3 D animation figure of the robot off-road driving on the simulation platform, in which the white path shows the motion trajectory of the robot. The upper-right part is the velocity magnitude figure of the robot. It is indicated that the velocity of the robot is adjusted according to the longitudinal control law. In addition, it is clear that the longitudinal control law, whose changes are mainly due to the curvature radius of the path and the road roughness, can assist the lateral control law to track the trajectory more accurately. In Test One, the average velocity approximately is 1.2 m / s , and in Test Two, the average velocity approximately is 1.0 m / s . The bottom-left part presents the height of the robot’s mass center during the robot’s tracking; in the figure, the road roughness can be implied. The bottom-right part shows that the kinetic energy magnitude is required by the robot motion in the course of tracking. In Sub-figure b, the angle data of the stereo vision pan rotation is indicated. The pan rotation angle varies according to the trajectory. Sub-figure c is the error statistic figure of trajectory tracking. As is shown, the error values almost converge to 0 . The factors, which produce these errors, include the roughness and the curvature variation of the trajectory. In Fig. 13 (d), the biggest error is yielded at the start point due to the start error between the start point and the trajectory. Sub-figure d is the trajectory tracking figure, which contains the objective trajectory and real tracking trajectory. It is obvious that the robot is able to recover from large disturbances, without intervention, and accomplish the tracking accurately.

Advertisement

5. Conclusions

The ADAMS&MATLAB co-simulation platform facilitates control method design, and dynamics modeling and analysis of the robot on the rough terrain. According to the practical requirement, the various terrain roughness and obstacles can be configured with modifying the relevant parameters of the simulation platform. In the simulation environment, the extensive experiments of control methods of rough terrain trajectory tracking of mobile robot can be achieved. The experiment results indicate that the control methods are robust and effective for the mobile robot running on the rough terrain. In addition, the simulation platform makes the experiment results more vivid and credible.

References

  1. 1. Lhomme-Desages D. Ch-C Grand. J. Guinot 2006Model-based Control of a fast Rover over natural Terrain,” Published in the Proceedings of CLAWAR’06: Int. Conf. on Climbing and Walking Robots, Sept.
  2. 2. Edward Tunstel, Ayanna Howard, Homayoun Seraji, 2001 “Fuzzy Rule-Based Reasoning for Rover Safety and Survivability,” Proceedings of the 2001 IEEE International Conference on Robotics & Automation, pp. 1413-1420, Seoul, Korea • May 21-261413 1420
  3. 3. Gabriel M. Hoffmann, Claire J. Tomlin, Michael Montemerlo, and Sebastian Thrun (2007). Autonomous Automobile Trajectory Tracking for Off-Road Driving: Controller Design, Experimental Validation and Racing. Proceedings of the ‘07 American Control Conference,New York City, USA2296 2301
  4. 4. Gao Feng, 2006A Survey on Analysis and Design of Model-Based Fuzzy Control Systems,” IEEE Transactions on Fuzzy Systems, 14 5 676 697
  5. 5. Gianluca Antonell, Stefano Chiaverini, and Giuseppe Fusco. 2007A Fuzzy-Logic-Based Approach for Mobile Robot Path Tracking,” IEEE Transactions on Fuzzy Systems, 15 2 211 221
  6. 6. José E. Naranjo Carlos. González Ricardo. García Teresa de Pedro. 2007Using Fuzzy Logic in Automated Vehicle Control. IEEE Intelligent Systems,” 22 1 36 45
  7. 7. Economou J. T. Colyer R. E. 2000Modelling of Skid Steering and Fuzzy Logic Vehicle Ground Interaction,” Proceedings of the American Control Conference, 100 104Chicago, Illinois June.
  8. 8. Wong J. Y. 1978Theory of Ground Vehicles,” John Wiley and Sons, New York, USA,.
  9. 9. Luca Caracciolo, Alessandro De Luca, and Stefano Iannitti, 1999Trajectory Tracking Control of a Four-Wheel Differentially Driven Mobile Robot,” Proceedings of the IEEE International Conference on Robotics & Automation, 2632 2638Detroit, Michigan, USA.
  10. 10. Matthew Spenko, Yoji Kuroda,Steven Dubowsky, and Karl Iagnemma, 2006Hazard avoidance for High-Speed Mobile Robots in Rough Terrain”, Journal of Field Robotics, 23 5 311 331
  11. 11. Ren Weiqun.Virtual Prototype in Vehicle-Road Dynamics System, Chapter Four. Publishing House of Electronics Industry, Beijing, China.

Written By

Yang. Yi, Fu. Mengyin, Zhu. Hao and Xiong. Guangming

Submitted: 11 November 2010 Published: 09 September 2011