blob: dd7e199c8f4462e847b1ce4629910f3750508b6a [file] [log] [blame]
John Park91e69732019-03-03 13:12:43 -08001from constants import *
2import numpy as np
3from libspline import Spline, DistanceSpline, Trajectory
Ravago Jones56941a52021-07-31 14:42:38 -07004import copy
John Park91e69732019-03-03 13:12:43 -08005
Ravago Jones8da89c42022-07-17 19:34:06 -07006
John Park91e69732019-03-03 13:12:43 -08007class Points():
8 def __init__(self):
9 self.points = [] # Holds all points not yet in spline
10 self.libsplines = [] # Formatted for libspline library usage
11 self.splines = [] # Formatted for drawing
Ravago Jones3b92afa2021-02-05 14:27:32 -080012 self.constraints = [ # default constraints
13 {
14 "constraint_type": "LONGITUDINAL_ACCELERATION",
15 "value": 3
16 }, {
17 "constraint_type": "LATERAL_ACCELERATION",
18 "value": 2
19 }, {
20 "constraint_type": "VOLTAGE",
21 "value": 10
22 }
23 ]
John Park91e69732019-03-03 13:12:43 -080024
Ravago Jones56941a52021-07-31 14:42:38 -070025 def __deepcopy__(self, memo):
26 new_copy = Points()
27 new_copy.points = copy.deepcopy(self.points, memo)
28 new_copy.splines = copy.deepcopy(self.splines, memo)
29 new_copy.constraints = copy.deepcopy(self.constraints, memo)
30 new_copy.update_lib_spline()
31 return new_copy
32
John Park91e69732019-03-03 13:12:43 -080033 def getPoints(self):
34 return self.points
35
36 def resetPoints(self):
37 self.points = []
38
39 def getLibsplines(self):
40 return self.libsplines
41
Ravago Jones3b92afa2021-02-05 14:27:32 -080042 def setConstraint(self, id, value):
43 for constraint in self.constraints:
44 if constraint["constraint_type"] == id:
45 constraint["value"] = value
46 break
47
kyle96e46e12021-02-10 21:47:55 -080048 def getConstraint(self, id):
49 for constraint in self.constraints:
50 if constraint["constraint_type"] == id:
51 return constraint["value"]
52
Ravago Jones3b92afa2021-02-05 14:27:32 -080053 def addConstraintsToTrajectory(self, trajectory):
54 for constraint in self.constraints:
55 if constraint["constraint_type"] == "VOLTAGE":
56 trajectory.SetVoltageLimit(constraint["value"])
57 elif constraint["constraint_type"] == "LATERAL_ACCELERATION":
58 trajectory.SetLateralAcceleration(constraint["value"])
59 elif constraint["constraint_type"] == "LONGITUDINAL_ACCELERATION":
60 trajectory.SetLongitudinalAcceleration(constraint["value"])
61
John Park91e69732019-03-03 13:12:43 -080062 def splineExtrapolate(self, o_spline_edit):
63 spline_edit = o_spline_edit
64 if not spline_edit == len(self.splines) - 1:
John Park91e69732019-03-03 13:12:43 -080065 f = self.splines[spline_edit][5]
66 e = self.splines[spline_edit][4]
67 d = self.splines[spline_edit][3]
James Kuszmaulb33b07c2021-02-25 22:39:24 -080068 self.splines[spline_edit + 1][0] = f
69 self.splines[spline_edit + 1][1] = f * 2 + e * -1
70 self.splines[spline_edit + 1][2] = d + f * 4 + e * -4
John Park91e69732019-03-03 13:12:43 -080071
72 if not spline_edit == 0:
John Park91e69732019-03-03 13:12:43 -080073 a = self.splines[spline_edit][0]
74 b = self.splines[spline_edit][1]
75 c = self.splines[spline_edit][2]
James Kuszmaulb33b07c2021-02-25 22:39:24 -080076 self.splines[spline_edit - 1][5] = a
77 self.splines[spline_edit - 1][4] = a * 2 + b * -1
78 self.splines[spline_edit - 1][3] = c + a * 4 + b * -4
John Park91e69732019-03-03 13:12:43 -080079
80 def updates_for_mouse_move(self, index_of_edit, spline_edit, x, y, difs):
81 if index_of_edit > -1:
Ravago Jones36c92f02021-07-24 16:35:33 -070082 self.splines[spline_edit][index_of_edit] = [x, y]
John Park91e69732019-03-03 13:12:43 -080083
84 if index_of_edit == 5:
85 self.splines[spline_edit][
86 index_of_edit -
87 2] = self.splines[spline_edit][index_of_edit - 2] + difs
88 self.splines[spline_edit][
89 index_of_edit -
90 1] = self.splines[spline_edit][index_of_edit - 1] + difs
91
92 if index_of_edit == 0:
93 self.splines[spline_edit][
94 index_of_edit +
95 2] = self.splines[spline_edit][index_of_edit + 2] + difs
96 self.splines[spline_edit][
97 index_of_edit +
98 1] = self.splines[spline_edit][index_of_edit + 1] + difs
99
100 if index_of_edit == 4:
101 self.splines[spline_edit][
102 index_of_edit -
103 1] = self.splines[spline_edit][index_of_edit - 1] + difs
104
105 if index_of_edit == 1:
106 self.splines[spline_edit][
107 index_of_edit +
108 1] = self.splines[spline_edit][index_of_edit + 1] + difs
109
James Kuszmaulb33b07c2021-02-25 22:39:24 -0800110 self.splineExtrapolate(spline_edit)
John Park91e69732019-03-03 13:12:43 -0800111
112 def update_lib_spline(self):
113 self.libsplines = []
114 array = np.zeros(shape=(6, 2), dtype=float)
115 for points in self.splines:
116 for j, point in enumerate(points):
117 array[j, 0] = point[0]
118 array[j, 1] = point[1]
119 spline = Spline(np.ascontiguousarray(np.transpose(array)))
120 self.libsplines.append(spline)
121
Ravago Jones3b92afa2021-02-05 14:27:32 -0800122 def toMultiSpline(self):
123 multi_spline = {
124 "spline_count": 0,
125 "spline_x": [],
126 "spline_y": [],
127 "constraints": self.constraints,
128 }
129 for points in self.splines:
130 multi_spline["spline_count"] += 1
131 for j, point in enumerate(points):
132 if j == 0 and multi_spline["spline_count"] > 1:
133 continue # skip overlapping points
134 multi_spline["spline_x"].append(point[0])
135 multi_spline["spline_y"].append(point[1])
136 return multi_spline
137
138 def fromMultiSpline(self, multi_spline):
139 self.constraints = multi_spline["constraints"]
140 self.splines = []
141 self.points = []
142
143 i = 0
144 for j in range(multi_spline["spline_count"]):
145 # get the last point of the last spline
146 # and read in another 6 points
147 for i in range(i, i + 6):
148 self.points.append(
149 [multi_spline["spline_x"][i], multi_spline["spline_y"][i]])
150 self.splines.append(np.array(self.points))
151 self.points = []
152 self.update_lib_spline()
153
John Park91e69732019-03-03 13:12:43 -0800154 def getSplines(self):
155 return self.splines
156
John Park91e69732019-03-03 13:12:43 -0800157 def setSplines(self, spline_edit, index_of_edit, x, y):
158 self.splines[spline_edit][index_of_edit] = [x, y]
159
160 def add_point(self, x, y):
161 if (len(self.points) < 6):
Ravago Jones36c92f02021-07-24 16:35:33 -0700162 self.points.append([x, y])
John Park91e69732019-03-03 13:12:43 -0800163 if (len(self.points) == 6):
164 self.splines.append(np.array(self.points))
165 self.points = []
166 self.update_lib_spline()
167 return True
168
169 def extrapolate(self, point1, point2,
170 point3): # where point3 is 3rd to last point
171 self.points.append(point1)
172 self.points.append(point1 * 2 - point2)
173 self.points.append(point3 + point1 * 4 - point2 * 4)