blob: 5fc4c4a343c9282fa960c253e4fcd1ceacb54e58 [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
6class Points():
7 def __init__(self):
8 self.points = [] # Holds all points not yet in spline
9 self.libsplines = [] # Formatted for libspline library usage
10 self.splines = [] # Formatted for drawing
Ravago Jones3b92afa2021-02-05 14:27:32 -080011 self.constraints = [ # default constraints
12 {
13 "constraint_type": "LONGITUDINAL_ACCELERATION",
14 "value": 3
15 }, {
16 "constraint_type": "LATERAL_ACCELERATION",
17 "value": 2
18 }, {
19 "constraint_type": "VOLTAGE",
20 "value": 10
21 }
22 ]
John Park91e69732019-03-03 13:12:43 -080023
Ravago Jones56941a52021-07-31 14:42:38 -070024 def __deepcopy__(self, memo):
25 new_copy = Points()
26 new_copy.points = copy.deepcopy(self.points, memo)
27 new_copy.splines = copy.deepcopy(self.splines, memo)
28 new_copy.constraints = copy.deepcopy(self.constraints, memo)
29 new_copy.update_lib_spline()
30 return new_copy
31
John Park91e69732019-03-03 13:12:43 -080032 def getPoints(self):
33 return self.points
34
35 def resetPoints(self):
36 self.points = []
37
38 def getLibsplines(self):
39 return self.libsplines
40
Ravago Jones3b92afa2021-02-05 14:27:32 -080041 def setConstraint(self, id, value):
42 for constraint in self.constraints:
43 if constraint["constraint_type"] == id:
44 constraint["value"] = value
45 break
46
kyle96e46e12021-02-10 21:47:55 -080047 def getConstraint(self, id):
48 for constraint in self.constraints:
49 if constraint["constraint_type"] == id:
50 return constraint["value"]
51
Ravago Jones3b92afa2021-02-05 14:27:32 -080052 def addConstraintsToTrajectory(self, trajectory):
53 for constraint in self.constraints:
54 if constraint["constraint_type"] == "VOLTAGE":
55 trajectory.SetVoltageLimit(constraint["value"])
56 elif constraint["constraint_type"] == "LATERAL_ACCELERATION":
57 trajectory.SetLateralAcceleration(constraint["value"])
58 elif constraint["constraint_type"] == "LONGITUDINAL_ACCELERATION":
59 trajectory.SetLongitudinalAcceleration(constraint["value"])
60
John Park91e69732019-03-03 13:12:43 -080061 def splineExtrapolate(self, o_spline_edit):
62 spline_edit = o_spline_edit
63 if not spline_edit == len(self.splines) - 1:
John Park91e69732019-03-03 13:12:43 -080064 f = self.splines[spline_edit][5]
65 e = self.splines[spline_edit][4]
66 d = self.splines[spline_edit][3]
James Kuszmaulb33b07c2021-02-25 22:39:24 -080067 self.splines[spline_edit + 1][0] = f
68 self.splines[spline_edit + 1][1] = f * 2 + e * -1
69 self.splines[spline_edit + 1][2] = d + f * 4 + e * -4
John Park91e69732019-03-03 13:12:43 -080070
71 if not spline_edit == 0:
John Park91e69732019-03-03 13:12:43 -080072 a = self.splines[spline_edit][0]
73 b = self.splines[spline_edit][1]
74 c = self.splines[spline_edit][2]
James Kuszmaulb33b07c2021-02-25 22:39:24 -080075 self.splines[spline_edit - 1][5] = a
76 self.splines[spline_edit - 1][4] = a * 2 + b * -1
77 self.splines[spline_edit - 1][3] = c + a * 4 + b * -4
John Park91e69732019-03-03 13:12:43 -080078
79 def updates_for_mouse_move(self, index_of_edit, spline_edit, x, y, difs):
80 if index_of_edit > -1:
Ravago Jones36c92f02021-07-24 16:35:33 -070081 self.splines[spline_edit][index_of_edit] = [x, y]
John Park91e69732019-03-03 13:12:43 -080082
83 if index_of_edit == 5:
84 self.splines[spline_edit][
85 index_of_edit -
86 2] = self.splines[spline_edit][index_of_edit - 2] + difs
87 self.splines[spline_edit][
88 index_of_edit -
89 1] = self.splines[spline_edit][index_of_edit - 1] + difs
90
91 if index_of_edit == 0:
92 self.splines[spline_edit][
93 index_of_edit +
94 2] = self.splines[spline_edit][index_of_edit + 2] + difs
95 self.splines[spline_edit][
96 index_of_edit +
97 1] = self.splines[spline_edit][index_of_edit + 1] + difs
98
99 if index_of_edit == 4:
100 self.splines[spline_edit][
101 index_of_edit -
102 1] = self.splines[spline_edit][index_of_edit - 1] + difs
103
104 if index_of_edit == 1:
105 self.splines[spline_edit][
106 index_of_edit +
107 1] = self.splines[spline_edit][index_of_edit + 1] + difs
108
James Kuszmaulb33b07c2021-02-25 22:39:24 -0800109 self.splineExtrapolate(spline_edit)
John Park91e69732019-03-03 13:12:43 -0800110
111 def update_lib_spline(self):
112 self.libsplines = []
113 array = np.zeros(shape=(6, 2), dtype=float)
114 for points in self.splines:
115 for j, point in enumerate(points):
116 array[j, 0] = point[0]
117 array[j, 1] = point[1]
118 spline = Spline(np.ascontiguousarray(np.transpose(array)))
119 self.libsplines.append(spline)
120
Ravago Jones3b92afa2021-02-05 14:27:32 -0800121 def toMultiSpline(self):
122 multi_spline = {
123 "spline_count": 0,
124 "spline_x": [],
125 "spline_y": [],
126 "constraints": self.constraints,
127 }
128 for points in self.splines:
129 multi_spline["spline_count"] += 1
130 for j, point in enumerate(points):
131 if j == 0 and multi_spline["spline_count"] > 1:
132 continue # skip overlapping points
133 multi_spline["spline_x"].append(point[0])
134 multi_spline["spline_y"].append(point[1])
135 return multi_spline
136
137 def fromMultiSpline(self, multi_spline):
138 self.constraints = multi_spline["constraints"]
139 self.splines = []
140 self.points = []
141
142 i = 0
143 for j in range(multi_spline["spline_count"]):
144 # get the last point of the last spline
145 # and read in another 6 points
146 for i in range(i, i + 6):
147 self.points.append(
148 [multi_spline["spline_x"][i], multi_spline["spline_y"][i]])
149 self.splines.append(np.array(self.points))
150 self.points = []
151 self.update_lib_spline()
152
John Park91e69732019-03-03 13:12:43 -0800153 def getSplines(self):
154 return self.splines
155
John Park91e69732019-03-03 13:12:43 -0800156 def setSplines(self, spline_edit, index_of_edit, x, y):
157 self.splines[spline_edit][index_of_edit] = [x, y]
158
159 def add_point(self, x, y):
160 if (len(self.points) < 6):
Ravago Jones36c92f02021-07-24 16:35:33 -0700161 self.points.append([x, y])
John Park91e69732019-03-03 13:12:43 -0800162 if (len(self.points) == 6):
163 self.splines.append(np.array(self.points))
164 self.points = []
165 self.update_lib_spline()
166 return True
167
168 def extrapolate(self, point1, point2,
169 point3): # where point3 is 3rd to last point
170 self.points.append(point1)
171 self.points.append(point1 * 2 - point2)
172 self.points.append(point3 + point1 * 4 - point2 * 4)