@@ -27,16 +27,98 @@ class CubicSpline2D:
27
27
cubic spline for y coordinates.
28
28
"""
29
29
30
- def __init__ (self , x , y ):
31
- self .points = np .c_ [x , y ]
32
- if not np .all (self .points [- 1 ] == self .points [0 ]):
30
+ def __init__ (self , x , y ,
31
+ psis : Optional [np .ndarray ] = None ,
32
+ ks : Optional [np .ndarray ] = None ,
33
+ vxs : Optional [np .ndarray ] = None ,
34
+ axs : Optional [np .ndarray ] = None ,
35
+ ss : Optional [np .ndarray ] = None ,
36
+ ):
37
+ self .xs = x
38
+ self .ys = y
39
+ input_vals = [x , y , psis , ks , vxs , axs , ss ]
40
+
41
+ # Only close the path if for the input values from the user,
42
+ # the first and last points are not the same => the path is not closed
43
+ # Otherwise, the constructed values can mess up the s calculation and closure
44
+ need_closure = False
45
+ for input_val in input_vals :
46
+ if input_val is not None :
47
+ if not (input_val [- 1 ] == input_val [0 ]):
48
+ need_closure = True
49
+ break
50
+
51
+ def close_with_constructor (input_val , constructor , closed_path ):
52
+ '''
53
+ If the input value is not None, return it.
54
+ Otherwise, return the constructor, with closure if necessary.
55
+
56
+ Parameters
57
+ ----------
58
+ input_val : np.ndarray | None
59
+ The input value from the user.
60
+ constructor : np.ndarray
61
+ The constructor to use if the input value is None.
62
+ closed_path : bool
63
+ Indicator whether the orirignal path is closed.
64
+ '''
65
+ if input_val is not None :
66
+ return input_val
67
+ else :
68
+ temp_ret = constructor
69
+ if closed_path :
70
+ temp_ret [- 1 ] = temp_ret [0 ]
71
+ return temp_ret
72
+
73
+ self .psis = close_with_constructor (psis , self ._calc_yaw_from_xy (x , y ), not need_closure )
74
+ self .ks = close_with_constructor (ks , self ._calc_kappa_from_xy (x , y ), not need_closure )
75
+ self .vxs = close_with_constructor (vxs , np .ones_like (x ), not need_closure )
76
+ self .axs = close_with_constructor (axs , np .zeros_like (x ), not need_closure )
77
+ self .ss = close_with_constructor (ss , self .__calc_s (x , y ), not need_closure )
78
+ psis_spline = close_with_constructor (psis , self ._calc_yaw_from_xy (x , y ), not need_closure )
79
+
80
+ # If yaw is provided, interpolate cosines and sines of yaw for continuity
81
+ cosines_spline = np .cos (psis_spline )
82
+ sines_spline = np .sin (psis_spline )
83
+
84
+ ks_spline = close_with_constructor (ks , self ._calc_kappa_from_xy (x , y ), not need_closure )
85
+ vxs_spline = close_with_constructor (vxs , np .zeros_like (x ), not need_closure )
86
+ axs_spline = close_with_constructor (axs , np .zeros_like (x ), not need_closure )
87
+
88
+ self .points = np .c_ [self .xs , self .ys ,
89
+ cosines_spline , sines_spline ,
90
+ ks_spline , vxs_spline , axs_spline ]
91
+
92
+ if need_closure :
33
93
self .points = np .vstack (
34
94
(self .points , self .points [0 ])
35
95
) # Ensure the path is closed
36
- self .s = self .__calc_s (self .points [:, 0 ], self .points [:, 1 ])
96
+
97
+ if ss is not None :
98
+ self .s = ss
99
+ else :
100
+ self .s = self .__calc_s (self .points [:, 0 ], self .points [:, 1 ])
101
+ self .s_interval = (self .s [- 1 ] - self .s [0 ]) / len (self .s )
102
+
37
103
# Use scipy CubicSpline to interpolate the points with periodic boundary conditions
38
- # This is necessary to ensure the path is continuous
104
+ # This is necesaxsry to ensure the path is continuous
39
105
self .spline = interpolate .CubicSpline (self .s , self .points , bc_type = "periodic" )
106
+ self .spline_x = np .array (self .spline .x )
107
+ self .spline_c = np .array (self .spline .c )
108
+
109
+
110
+ def find_segment_for_s (self , x ):
111
+ # Find the segment of the spline that x is in
112
+ return (x / (self .spline .x [- 1 ] + self .s_interval ) * (len (self .spline_x ) - 1 )).astype (int )
113
+
114
+ def predict_with_spline (self , point , segment , state_index = 0 ):
115
+ # A (4, 100) array, where the rows contain (x-x[i])**3, (x-x[i])**2 etc.
116
+ # exp_x = (point - self.spline.x[[segment]])[None, :] ** np.arange(4)[::-1, None]
117
+ exp_x = ((point - self .spline .x [segment % len (self .spline .x )]) ** np .arange (4 )[::- 1 ])[:, None ]
118
+ vec = self .spline .c [:, segment % self .spline .c .shape [1 ], state_index ]
119
+ # Sum over the rows of exp_x weighted by coefficients in the ith column of s.c
120
+ point = vec .dot (exp_x )
121
+ return np .asarray (point )
40
122
41
123
def __calc_s (self , x : np .ndarray , y : np .ndarray ) -> np .ndarray :
42
124
"""
@@ -60,6 +142,24 @@ def __calc_s(self, x: np.ndarray, y: np.ndarray) -> np.ndarray:
60
142
s = [0 ]
61
143
s .extend (np .cumsum (self .ds ))
62
144
return np .array (s )
145
+
146
+ def _calc_yaw_from_xy (self , x , y ):
147
+ dx_dt = np .gradient (x , edge_order = 2 )
148
+ dy_dt = np .gradient (y , edge_order = 2 )
149
+ heading = np .arctan2 (dy_dt , dx_dt )
150
+ return heading
151
+
152
+ def _calc_kappa_from_xy (self , x , y ):
153
+ # For more stable gradients, extend x and y by two (edge_order 2) elements on each side
154
+ # The elements are taken from the other side of the array
155
+ x_extended = np .concatenate ((x [- 2 :], x , x [:2 ]))
156
+ y_extended = np .concatenate ((y [- 2 :], y , y [:2 ]))
157
+ dx_dt = np .gradient (x_extended , edge_order = 2 )
158
+ dy_dt = np .gradient (y_extended , edge_order = 2 )
159
+ d2x_dt2 = np .gradient (dx_dt , edge_order = 2 )
160
+ d2y_dt2 = np .gradient (dy_dt , edge_order = 2 )
161
+ curvature = (dx_dt * d2y_dt2 - d2x_dt2 * dy_dt ) / (dx_dt * dx_dt + dy_dt * dy_dt )** 1.5
162
+ return curvature [2 :- 2 ]
63
163
64
164
def calc_position (self , s : float ) -> np .ndarray :
65
165
"""
@@ -78,7 +178,10 @@ def calc_position(self, s: float) -> np.ndarray:
78
178
y : float | None
79
179
y position for given s.
80
180
"""
81
- return self .spline (s )
181
+ segment = self .find_segment_for_s (s )
182
+ x = self .predict_with_spline (s , segment , 0 )[0 ]
183
+ y = self .predict_with_spline (s , segment , 1 )[0 ]
184
+ return x ,y
82
185
83
186
def calc_curvature (self , s : float ) -> Optional [float ]:
84
187
"""
@@ -95,11 +198,29 @@ def calc_curvature(self, s: float) -> Optional[float]:
95
198
k : float
96
199
curvature for given s.
97
200
"""
98
- dx , dy = self .spline (s , 1 )
99
- ddx , ddy = self .spline (s , 2 )
100
- k = (ddy * dx - ddx * dy ) / ((dx ** 2 + dy ** 2 ) ** (3 / 2 ))
201
+ segment = self .find_segment_for_s (s )
202
+ k = self .predict_with_spline (s , segment , 4 )[0 ]
101
203
return k
102
204
205
+ def find_curvature (self , s : float ) -> Optional [float ]:
206
+ """
207
+ Find curvature at the given s by the segment.
208
+
209
+ Parameters
210
+ ----------
211
+ s : float
212
+ distance from the start point. if `s` is outside the data point's
213
+ range, return None.
214
+
215
+ Returns
216
+ -------
217
+ k : float
218
+ curvature for given s.
219
+ """
220
+ segment = self .find_segment_for_s (s )
221
+ k = self .points [segment , 4 ]
222
+ return k
223
+
103
224
def calc_yaw (self , s : float ) -> Optional [float ]:
104
225
"""
105
226
Calc yaw angle at the given s.
@@ -114,11 +235,10 @@ def calc_yaw(self, s: float) -> Optional[float]:
114
235
yaw : float
115
236
yaw angle (tangent vector) for given s.
116
237
"""
117
- dx , dy = self .spline (s , 1 )
118
- yaw = math .atan2 (dy , dx )
119
- # Convert yaw to [0, 2pi]
120
- yaw = yaw % (2 * math .pi )
121
-
238
+ segment = self .find_segment_for_s (s )
239
+ cos = self .predict_with_spline (s , segment , 2 )[0 ]
240
+ sin = self .predict_with_spline (s , segment , 3 )[0 ]
241
+ yaw = (math .atan2 (sin , cos ) + 2 * math .pi ) % (2 * math .pi )
122
242
return yaw
123
243
124
244
def calc_arclength (
@@ -145,15 +265,15 @@ def calc_arclength(
145
265
"""
146
266
147
267
def distance_to_spline (s ):
148
- x_eval , y_eval = self .spline (s )[0 ]
268
+ x_eval , y_eval = self .spline (s )[0 , : 2 ]
149
269
return np .sqrt ((x - x_eval ) ** 2 + (y - y_eval ) ** 2 )
150
270
151
271
output = so .fmin (distance_to_spline , s_guess , full_output = True , disp = False )
152
272
closest_s = float (output [0 ][0 ])
153
273
absolute_distance = output [1 ]
154
274
return closest_s , absolute_distance
155
275
156
- def calc_arclength_inaccurate (self , x : float , y : float ) -> tuple [float , float ]:
276
+ def calc_arclength_inaccurate (self , x : float , y : float , s_inds = None ) -> tuple [float , float ]:
157
277
"""
158
278
Fast calculation of arclength for a given point (x, y) on the trajectory.
159
279
Less accuarate and less smooth than calc_arclength but much faster.
@@ -173,15 +293,16 @@ def calc_arclength_inaccurate(self, x: float, y: float) -> tuple[float, float]:
173
293
ey : float
174
294
lateral deviation for given x, y.
175
295
"""
296
+ if s_inds is None :
297
+ s_inds = np .arange (self .points .shape [0 ])
176
298
_ , ey , t , min_dist_segment = nearest_point_on_trajectory (
177
- np .array ([x , y ]), self .points
299
+ np .array ([x , y ]). astype ( np . float32 ) , self .points [ s_inds , : 2 ]
178
300
)
179
- # s = s at closest_point + t
301
+ min_dist_segment_s_ind = s_inds [ min_dist_segment ]
180
302
s = float (
181
- self .s [min_dist_segment ]
182
- + t * (self .s [min_dist_segment + 1 ] - self .s [min_dist_segment ])
303
+ self .s [min_dist_segment_s_ind ]
304
+ + t * (self .s [min_dist_segment_s_ind + 1 ] - self .s [min_dist_segment_s_ind ])
183
305
)
184
-
185
306
return s , ey
186
307
187
308
def _calc_tangent (self , s : float ) -> np .ndarray :
@@ -199,7 +320,7 @@ def _calc_tangent(self, s: float) -> np.ndarray:
199
320
tangent : float
200
321
tangent vector for given s.
201
322
"""
202
- dx , dy = self .spline (s , 1 )
323
+ dx , dy = self .spline (s , 1 )[: 2 ]
203
324
tangent = np .array ([dx , dy ])
204
325
return tangent
205
326
@@ -218,6 +339,6 @@ def _calc_normal(self, s: float) -> np.ndarray:
218
339
normal : float
219
340
normal vector for given s.
220
341
"""
221
- dx , dy = self .spline (s , 1 )
342
+ dx , dy = self .spline (s , 1 )[: 2 ]
222
343
normal = np .array ([- dy , dx ])
223
344
return normal
0 commit comments