55author: Atsushi Sakai (@Atsushi_twi) 
66
77""" 
8+ from  __future__ import  division , print_function 
9+ 
810import  sys 
11+ 
912sys .path .append ("../../PathPlanning/CubicSpline/" )
1013
11- import  math 
1214import  matplotlib .pyplot  as  plt 
13- import  cubic_spline_planner 
15+ import  numpy   as   np 
1416
17+ import  cubic_spline_planner 
1518
1619k  =  0.5   # control gain 
1720Kp  =  1.0   # speed propotional gain 
1821dt  =  0.1   # [s] time difference 
1922L  =  2.9   # [m] Wheel base of vehicle 
20- max_steer  =  math .radians (30.0 )  # [rad] max steering angle 
23+ max_steer  =  np .radians (30.0 )  # [rad] max steering angle 
2124
2225show_animation  =  True 
2326
2427
25- class  State :
28+ class  State (object ):
29+     """ 
30+     Class representing the state of a vehicle. 
31+ 
32+     :param x: (float) x-coordinate 
33+     :param y: (float) y-coordinate 
34+     :param yaw: (float) yaw angle 
35+     :param v: (float) speed 
36+     """ 
2637
2738    def  __init__ (self , x = 0.0 , y = 0.0 , yaw = 0.0 , v = 0.0 ):
39+         """Instantiate the object.""" 
40+         super (State , self ).__init__ ()
2841        self .x  =  x 
2942        self .y  =  y 
3043        self .yaw  =  yaw 
3144        self .v  =  v 
3245
46+     def  update (self , acceleration , delta ):
47+         """ 
48+         Update the state of the vehicle. 
3349
34- def   update ( state ,  a ,  delta ): 
50+         Stanley Control uses bicycle model. 
3551
36-     if   delta   >=   max_steer : 
37-         delta   =   max_steer 
38-     elif   delta   <=   - max_steer : 
39-         delta  =  - max_steer 
52+         :param acceleration: (float) Acceleration  
53+         :param  delta: (float) Steering  
54+         """  
55+         delta  =  np . clip ( delta ,  - max_steer ,  max_steer ) 
4056
41-     state . x   =   state .x  +   state .v  *  math .cos (state .yaw ) *  dt 
42-     state . y   =   state .y  +   state .v  *  math .sin (state .yaw ) *  dt 
43-     state . yaw   =   state .yaw  +   state .v  /  L  *  math .tan (delta ) *  dt 
44-     state .yaw  =  pi_2_pi ( state .yaw )
45-     state . v   =   state .v  +   a  *  dt 
57+          self .x  +=    self .v  *  np .cos (self .yaw ) *  dt 
58+          self .y  +=    self .v  *  np .sin (self .yaw ) *  dt 
59+          self .yaw  +=    self .v  /  L  *  np .tan (delta ) *  dt 
60+          self .yaw  =  normalize_angle ( self .yaw )
61+          self .v  +=    acceleration  *  dt 
4662
47-     return  state 
4863
64+ def  pid_control (target , current ):
65+     """ 
66+     Proportional control for the speed. 
4967
50- def  PIDControl (target , current ):
51-     a  =  Kp  *  (target  -  current )
68+     :param target: (float) 
69+     :param current: (float) 
70+     :return: (float) 
71+     """ 
72+     return  Kp  *  (target  -  current )
5273
53-     return  a 
5474
75+ def  stanley_control (state , cx , cy , cyaw , last_target_idx ):
76+     """ 
77+     Stanley steering control. 
5578
56- def  stanley_control (state , cx , cy , cyaw , pind ):
79+     :param state: (State object) 
80+     :param cx: ([float]) 
81+     :param cy: ([float]) 
82+     :param cyaw: ([float]) 
83+     :param last_target_idx: (int) 
84+     :return: (float, int) 
85+     """ 
86+     current_target_idx , error_front_axle  =  calc_target_index (state , cx , cy )
5787
58-     ind , efa  =  calc_target_index (state , cx , cy )
88+     if  last_target_idx  >=  current_target_idx :
89+         current_target_idx  =  last_target_idx 
5990
60-     if   pind   >=   ind : 
61-          ind   =   pind 
62- 
63-     theta_e  =  pi_2_pi ( cyaw [ ind ]  -   state .yaw )
64-     theta_d   =   math . atan2 ( k   *   efa ,  state . v ) 
91+     # theta_e corrects the heading error 
92+     theta_e   =   normalize_angle ( cyaw [ current_target_idx ]  -   state . yaw ) 
93+      # theta_d corrects the cross track error 
94+     theta_d  =  np . arctan2 ( k   *   error_front_axle ,  state .v )
95+     # Steering control 
6596    delta  =  theta_e  +  theta_d 
6697
67-     return  delta , ind 
98+     return  delta , current_target_idx 
99+ 
68100
101+ def  normalize_angle (angle ):
102+     """ 
103+     Normalize an angle to [-pi, pi]. 
69104
70- def  pi_2_pi (angle ):
71-     while  (angle  >  math .pi ):
72-         angle  =  angle  -  2.0  *  math .pi 
105+     :param angle: (float) 
106+     :return: (float) Angle in radian in [-pi, pi] 
107+     """ 
108+     while  angle  >  np .pi :
109+         angle  -=  2.0  *  np .pi 
73110
74-     while  ( angle  <  - math .pi ) :
75-         angle  =   angle   +   2.0  *  math .pi 
111+     while  angle  <  - np .pi :
112+         angle  +=   2.0  *  np .pi 
76113
77114    return  angle 
78115
79116
80117def  calc_target_index (state , cx , cy ):
81- 
82-     # calc frant axle position 
83-     fx  =  state .x  +  L  *  math .cos (state .yaw )
84-     fy  =  state .y  +  L  *  math .sin (state .yaw )
85- 
86-     # search nearest point index 
118+     """ 
119+     Compute index in the trajectory list of the target. 
120+ 
121+     :param state: (State object) 
122+     :param cx: [float] 
123+     :param cy: [float] 
124+     :return: (int, float) 
125+     """ 
126+     # Calc front axle position 
127+     fx  =  state .x  +  L  *  np .cos (state .yaw )
128+     fy  =  state .y  +  L  *  np .sin (state .yaw )
129+ 
130+     # Search nearest point index 
87131    dx  =  [fx  -  icx  for  icx  in  cx ]
88132    dy  =  [fy  -  icy  for  icy  in  cy ]
89-     d  =  [math .sqrt (idx  **  2  +  idy  **  2 ) for  (idx , idy ) in  zip (dx , dy )]
90-     mind  =  min (d )
91-     ind  =  d .index (mind )
133+     d  =  [np .sqrt (idx  **  2  +  idy  **  2 ) for  (idx , idy ) in  zip (dx , dy )]
134+     error_front_axle  =  min (d )
135+     target_idx  =  d .index (error_front_axle )
92136
93-     tyaw  =  pi_2_pi ( math . atan2 (fy  -  cy [ind ], fx  -  cx [ind ]) -  state .yaw )
94-     if  tyaw  >  0.0 :
95-         mind  =  -  mind 
137+     target_yaw  =  normalize_angle ( np . arctan2 (fy  -  cy [target_idx ], fx  -  cx [target_idx ]) -  state .yaw )
138+     if  target_yaw  >  0.0 :
139+         error_front_axle  =  -  error_front_axle 
96140
97-     return  ind ,  mind 
141+     return  target_idx ,  error_front_axle 
98142
99143
100144def  main ():
145+     """Plot an example of Stanley steering control on a cubic spline.""" 
101146    #  target course 
102147    ax  =  [0.0 , 100.0 , 100.0 , 50.0 , 60.0 ]
103148    ay  =  [0.0 , 0.0 , - 30.0 , - 20.0 , 0.0 ]
@@ -107,26 +152,26 @@ def main():
107152
108153    target_speed  =  30.0  /  3.6   # [m/s] 
109154
110-     T  =  100.0    # max simulation time 
155+     max_simulation_time  =  100.0 
111156
112-     # initial  state 
113-     state  =  State (x = - 0.0 , y = 5.0 , yaw = math .radians (20.0 ), v = 0.0 )
157+     # Initial  state 
158+     state  =  State (x = - 0.0 , y = 5.0 , yaw = np .radians (20.0 ), v = 0.0 )
114159
115-     lastIndex  =  len (cx ) -  1 
160+     last_idx  =  len (cx ) -  1 
116161    time  =  0.0 
117162    x  =  [state .x ]
118163    y  =  [state .y ]
119164    yaw  =  [state .yaw ]
120165    v  =  [state .v ]
121166    t  =  [0.0 ]
122-     target_ind ,  mind  =  calc_target_index (state , cx , cy )
167+     target_idx ,  _  =  calc_target_index (state , cx , cy )
123168
124-     while  T  >=  time  and  lastIndex  >  target_ind :
125-         ai  =  PIDControl (target_speed , state .v )
126-         di , target_ind  =  stanley_control (state , cx , cy , cyaw , target_ind )
127-         state   =   update (state ,  ai , di )
169+     while  max_simulation_time  >=  time  and  last_idx  >  target_idx :
170+         ai  =  pid_control (target_speed , state .v )
171+         di , target_idx  =  stanley_control (state , cx , cy , cyaw , target_idx )
172+         state . update (ai , di )
128173
129-         time  =   time   +  dt 
174+         time  +=  dt 
130175
131176        x .append (state .x )
132177        y .append (state .y )
@@ -138,14 +183,14 @@ def main():
138183            plt .cla ()
139184            plt .plot (cx , cy , ".r" , label = "course" )
140185            plt .plot (x , y , "-b" , label = "trajectory" )
141-             plt .plot (cx [target_ind ], cy [target_ind ], "xg" , label = "target" )
186+             plt .plot (cx [target_idx ], cy [target_idx ], "xg" , label = "target" )
142187            plt .axis ("equal" )
143188            plt .grid (True )
144189            plt .title ("Speed[km/h]:"  +  str (state .v  *  3.6 )[:4 ])
145190            plt .pause (0.001 )
146191
147192    # Test 
148-     assert  lastIndex  >=  target_ind , "Cannot goal" 
193+     assert  last_idx  >=  target_idx , "Cannot reach  goal" 
149194
150195    if  show_animation :
151196        plt .plot (cx , cy , ".r" , label = "course" )
0 commit comments