88import  matplotlib .pyplot  as  plt 
99import  math 
1010import  numpy  as  np 
11- import  sys 
12- sys .path .append ("../../PathPlanning/CubicSpline/" )
13- 
14- try :
15-     import  cubic_spline_planner 
16- except :
17-     raise 
1811
12+ from  scipy  import  interpolate 
13+ from  scipy  import  optimize 
1914
2015Kp  =  1.0   # speed propotional gain 
2116# steering control parameter 
2621L  =  2.9   # [m] 
2722
2823show_animation  =  True 
29- #  show_animation = False 
30- 
3124
3225class  State :
33- 
34-     def  __init__ (self , x = 0.0 , y = 0.0 , yaw = 0.0 , v = 0.0 ):
26+     def  __init__ (self , x = 0.0 , y = 0.0 , yaw = 0.0 , v = 0.0 , direction = 1 ):
3527        self .x  =  x 
3628        self .y  =  y 
3729        self .yaw  =  yaw 
3830        self .v  =  v 
39- 
40- 
41- def  update (state , a , delta ):
42- 
43-     state .x  =  state .x  +  state .v  *  math .cos (state .yaw ) *  dt 
44-     state .y  =  state .y  +  state .v  *  math .sin (state .yaw ) *  dt 
45-     state .yaw  =  state .yaw  +  state .v  /  L  *  math .tan (delta ) *  dt 
46-     state .v  =  state .v  +  a  *  dt 
47- 
48-     return  state 
49- 
50- 
51- def  PIDControl (target , current ):
31+         self .direction  =  direction 
32+ 
33+     def  update (self , a , delta , dt ):
34+         self .x    =  self .x  +  self .v  *  math .cos (self .yaw ) *  dt 
35+         self .y    =  self .y  +  self .v  *  math .sin (self .yaw ) *  dt 
36+         self .yaw  =  self .yaw  +  self .v  /  L  *  math .tan (delta ) *  dt 
37+         self .v    =  self .v  +  a  *  dt 
38+ 
39+ class  CubicSplinePath :
40+     def  __init__ (self , x , y ):
41+         x , y  =  map (np .asarray , (x , y ))
42+         s  =  np .append ([0 ],(np .cumsum (np .diff (x )** 2 ) +  np .cumsum (np .diff (y )** 2 ))** 0.5 )
43+ 
44+         self .X  =  interpolate .CubicSpline (s , x )
45+         self .Y  =  interpolate .CubicSpline (s , y )
46+ 
47+         self .dX  =  self .X .derivative (1 )
48+         self .ddX  =  self .X .derivative (2 )
49+ 
50+         self .dY  =  self .Y .derivative (1 )
51+         self .ddY  =  self .Y .derivative (2 )
52+ 
53+         self .length  =  s [- 1 ]
54+     
55+     def  calc_yaw (self , s ):
56+         dx , dy  =  self .dX (s ), self .dY (s )
57+         return  np .arctan2 (dy , dx )
58+     
59+     def  calc_curvature (self , s ):
60+         dx , dy    =  self .dX (s ), self .dY (s )
61+         ddx , ddy    =  self .ddX (s ), self .ddY (s )
62+         return  (ddy  *  dx  -  ddx  *  dy ) /  ((dx  **  2  +  dy  **  2 )** (3  /  2 ))
63+     
64+     def  __find_nearest_point (self , s0 , x , y ):
65+         def  calc_distance (_s , * args ):
66+             _x , _y =  self .X (_s ), self .Y (_s )
67+             return  (_x  -  args [0 ])** 2  +  (_y  -  args [1 ])** 2 
68+         
69+         def  calc_distance_jacobian (_s , * args ):
70+             _x , _y  =  self .X (_s ), self .Y (_s )
71+             _dx , _dy  =  self .dX (_s ), self .dY (_s )
72+             return  2 * _dx * (_x  -  args [0 ])+ 2 * _dy * (_y - args [1 ])
73+ 
74+         minimum  =  optimize .fmin_cg (calc_distance , s0 , calc_distance_jacobian , args = (x , y ), full_output = True , disp = False )
75+         return  minimum 
76+ 
77+     def  calc_track_error (self , x , y , s0 ):
78+         ret  =  self .__find_nearest_point (s0 , x , y )
79+         
80+         s  =  ret [0 ][0 ]
81+         e  =  ret [1 ]
82+ 
83+         k    =  self .calc_curvature (s )
84+         yaw  =  self .calc_yaw (s )
85+ 
86+         dxl  =  self .X (s ) -  x 
87+         dyl  =  self .Y (s ) -  y 
88+         angle  =  pi_2_pi (yaw  -  math .atan2 (dyl , dxl ))
89+         if  angle  <  0 :
90+             e *=  - 1 
91+ 
92+         return  e , k , yaw , s 
93+ 
94+ def  pid_control (target , current ):
5295    a  =  Kp  *  (target  -  current )
53- 
5496    return  a 
5597
56- 
5798def  pi_2_pi (angle ):
5899    while (angle  >  math .pi ):
59100        angle  =  angle  -  2.0  *  math .pi 
@@ -63,53 +104,24 @@ def pi_2_pi(angle):
63104
64105    return  angle 
65106
66- 
67- def  rear_wheel_feedback_control (state , cx , cy , cyaw , ck , preind ):
68-     ind , e  =  calc_nearest_index (state , cx , cy , cyaw )
69- 
70-     k  =  ck [ind ]
107+ def  rear_wheel_feedback_control (state , e , k , yaw_ref ):
71108    v  =  state .v 
72-     th_e  =  pi_2_pi (state .yaw  -  cyaw [ ind ] )
109+     th_e  =  pi_2_pi (state .yaw  -  yaw_ref )
73110
74111    omega  =  v  *  k  *  math .cos (th_e ) /  (1.0  -  k  *  e ) -  \
75112        KTH  *  abs (v ) *  th_e  -  KE  *  v  *  math .sin (th_e ) *  e  /  th_e 
76113
77114    if  th_e  ==  0.0  or  omega  ==  0.0 :
78-         return  0.0 ,  ind 
115+         return  0.0 
79116
80117    delta  =  math .atan2 (L  *  omega  /  v , 1.0 )
81-     #  print(k, v, e, th_e, omega, delta) 
82- 
83-     return  delta , ind 
84- 
85- 
86- def  calc_nearest_index (state , cx , cy , cyaw ):
87-     dx  =  [state .x  -  icx  for  icx  in  cx ]
88-     dy  =  [state .y  -  icy  for  icy  in  cy ]
89- 
90-     d  =  [idx  **  2  +  idy  **  2  for  (idx , idy ) in  zip (dx , dy )]
91- 
92-     mind  =  min (d )
93118
94-     ind   =   d . index ( mind ) 
119+     return   delta 
95120
96-     mind  =  math .sqrt (mind )
97- 
98-     dxl  =  cx [ind ] -  state .x 
99-     dyl  =  cy [ind ] -  state .y 
100- 
101-     angle  =  pi_2_pi (cyaw [ind ] -  math .atan2 (dyl , dxl ))
102-     if  angle  <  0 :
103-         mind  *=  - 1 
104- 
105-     return  ind , mind 
106- 
107- 
108- def  closed_loop_prediction (cx , cy , cyaw , ck , speed_profile , goal ):
109121
122+ def  simulate (path_ref , goal ):
110123    T  =  500.0   # max simulation time 
111124    goal_dis  =  0.3 
112-     stop_speed  =  0.05 
113125
114126    state  =  State (x = - 0.0 , y = - 0.0 , yaw = 0.0 , v = 0.0 )
115127
@@ -120,16 +132,17 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
120132    v  =  [state .v ]
121133    t  =  [0.0 ]
122134    goal_flag  =  False 
123-     target_ind  =  calc_nearest_index (state , cx , cy , cyaw )
135+ 
136+     s  =  np .arange (0 , path_ref .length , 0.1 )
137+     e , k , yaw_ref , s0  =  path_ref .calc_track_error (state .x , state .y , 0.0 )
124138
125139    while  T  >=  time :
126-         di , target_ind  =  rear_wheel_feedback_control (
127-             state , cx , cy , cyaw , ck , target_ind )
128-         ai  =  PIDControl (speed_profile [target_ind ], state .v )
129-         state  =  update (state , ai , di )
140+         e , k , yaw_ref , s0  =  path_ref .calc_track_error (state .x , state .y , s0 )
141+         di  =  rear_wheel_feedback_control (state , e , k , yaw_ref )
130142
131-         if  abs (state .v ) <=  stop_speed :
132-             target_ind  +=  1 
143+         speed_ref  =  calc_target_speed (state , yaw_ref )
144+         ai  =  pid_control (speed_ref , state .v )
145+         state .update (ai , di , dt )
133146
134147        time  =  time  +  dt 
135148
@@ -147,64 +160,46 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
147160        v .append (state .v )
148161        t .append (time )
149162
150-         if  target_ind   %   1   ==   0   and   show_animation :
163+         if  show_animation :
151164            plt .cla ()
152165            # for stopping simulation with the esc key. 
153166            plt .gcf ().canvas .mpl_connect ('key_release_event' ,
154167                    lambda  event : [exit (0 ) if  event .key  ==  'escape'  else  None ])
155-             plt .plot (cx ,  cy , "-r" , label = "course" )
168+             plt .plot (path_ref . X ( s ),  path_ref . Y ( s ) , "-r" , label = "course" )
156169            plt .plot (x , y , "ob" , label = "trajectory" )
157-             plt .plot (cx [ target_ind ],  cy [ target_ind ] , "xg" , label = "target" )
170+             plt .plot (path_ref . X ( s0 ),  path_ref . Y ( s0 ) , "xg" , label = "target" )
158171            plt .axis ("equal" )
159172            plt .grid (True )
160-             plt .title ("speed[km/h]:"  +  str (round (state .v  *  3.6 , 2 )) + 
161-                       ",target index:"  +  str (target_ind ))
173+             plt .title ("speed[km/h]:{:.2f}, target s-param:{:.2f}" .format (round (state .v  *  3.6 , 2 ), s0 ))
162174            plt .pause (0.0001 )
163175
164176    return  t , x , y , yaw , v , goal_flag 
165177
178+ def  calc_target_speed (state , yaw_ref ):
179+     target_speed  =  10.0  /  3.6 
166180
167- def  calc_speed_profile (cx , cy , cyaw , target_speed ):
168- 
169-     speed_profile  =  [target_speed ] *  len (cx )
170- 
171-     direction  =  1.0 
172- 
173-     # Set stop point 
174-     for  i  in  range (len (cx ) -  1 ):
175-         dyaw  =  cyaw [i  +  1 ] -  cyaw [i ]
176-         switch  =  math .pi  /  4.0  <=  dyaw  <  math .pi  /  2.0 
177- 
178-         if  switch :
179-             direction  *=  - 1 
180- 
181-         if  direction  !=  1.0 :
182-             speed_profile [i ] =  -  target_speed 
183-         else :
184-             speed_profile [i ] =  target_speed 
185- 
186-         if  switch :
187-             speed_profile [i ] =  0.0 
188- 
189-     speed_profile [- 1 ] =  0.0 
181+     dyaw  =  yaw_ref  -  state .yaw 
182+     switch  =  math .pi  /  4.0  <=  dyaw  <  math .pi  /  2.0 
190183
191-     return  speed_profile 
184+     if  switch :
185+         state .direction  *=  - 1 
186+         return  0.0 
187+     
188+     if  state .direction  !=  1 :
189+         return  - target_speed 
192190
191+     return  target_speed 
193192
194193def  main ():
195194    print ("rear wheel feedback tracking start!!" )
196195    ax  =  [0.0 , 6.0 , 12.5 , 5.0 , 7.5 , 3.0 , - 1.0 ]
197196    ay  =  [0.0 , 0.0 , 5.0 , 6.5 , 3.0 , 5.0 , - 2.0 ]
198197    goal  =  [ax [- 1 ], ay [- 1 ]]
199198
200-     cx , cy , cyaw , ck , s  =  cubic_spline_planner .calc_spline_course (
201-         ax , ay , ds = 0.1 )
202-     target_speed  =  10.0  /  3.6 
203- 
204-     sp  =  calc_speed_profile (cx , cy , cyaw , target_speed )
199+     reference_path  =  CubicSplinePath (ax , ay )
200+     s  =  np .arange (0 , reference_path .length , 0.1 )
205201
206-     t , x , y , yaw , v , goal_flag  =  closed_loop_prediction (
207-         cx , cy , cyaw , ck , sp , goal )
202+     t , x , y , yaw , v , goal_flag  =  simulate (reference_path , goal )
208203
209204    # Test 
210205    assert  goal_flag , "Cannot goal" 
@@ -213,7 +208,7 @@ def main():
213208        plt .close ()
214209        plt .subplots (1 )
215210        plt .plot (ax , ay , "xb" , label = "input" )
216-         plt .plot (cx ,  cy , "-r" , label = "spline" )
211+         plt .plot (reference_path . X ( s ),  reference_path . Y ( s ) , "-r" , label = "spline" )
217212        plt .plot (x , y , "-g" , label = "tracking" )
218213        plt .grid (True )
219214        plt .axis ("equal" )
@@ -222,21 +217,20 @@ def main():
222217        plt .legend ()
223218
224219        plt .subplots (1 )
225-         plt .plot (s , [ np .rad2deg (iyaw )  for   iyaw   in   cyaw ] , "-r" , label = "yaw" )
220+         plt .plot (s , np .rad2deg (reference_path . calc_yaw ( s )) , "-r" , label = "yaw" )
226221        plt .grid (True )
227222        plt .legend ()
228223        plt .xlabel ("line length[m]" )
229224        plt .ylabel ("yaw angle[deg]" )
230225
231226        plt .subplots (1 )
232-         plt .plot (s , ck , "-r" , label = "curvature" )
227+         plt .plot (s , reference_path . calc_curvature ( s ) , "-r" , label = "curvature" )
233228        plt .grid (True )
234229        plt .legend ()
235230        plt .xlabel ("line length[m]" )
236231        plt .ylabel ("curvature [1/m]" )
237232
238233        plt .show ()
239234
240- 
241235if  __name__  ==  '__main__' :
242236    main ()
0 commit comments