blob: c22582e2131f15b1f8c13e522ab88ade35e9b03c [file] [log] [blame]
John Park91e69732019-03-03 13:12:43 -08001from constants import *
2import numpy as np
3from libspline import Spline, DistanceSpline, Trajectory
4
5
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
24 def getPoints(self):
25 return self.points
26
27 def resetPoints(self):
28 self.points = []
29
30 def getLibsplines(self):
31 return self.libsplines
32
Ravago Jones3b92afa2021-02-05 14:27:32 -080033 def setConstraint(self, id, value):
34 for constraint in self.constraints:
35 if constraint["constraint_type"] == id:
36 constraint["value"] = value
37 break
38
kyle96e46e12021-02-10 21:47:55 -080039 def getConstraint(self, id):
40 for constraint in self.constraints:
41 if constraint["constraint_type"] == id:
42 return constraint["value"]
43
Ravago Jones3b92afa2021-02-05 14:27:32 -080044 def addConstraintsToTrajectory(self, trajectory):
45 for constraint in self.constraints:
46 if constraint["constraint_type"] == "VOLTAGE":
47 trajectory.SetVoltageLimit(constraint["value"])
48 elif constraint["constraint_type"] == "LATERAL_ACCELERATION":
49 trajectory.SetLateralAcceleration(constraint["value"])
50 elif constraint["constraint_type"] == "LONGITUDINAL_ACCELERATION":
51 trajectory.SetLongitudinalAcceleration(constraint["value"])
52
John Park91e69732019-03-03 13:12:43 -080053 def splineExtrapolate(self, o_spline_edit):
54 spline_edit = o_spline_edit
55 if not spline_edit == len(self.splines) - 1:
John Park91e69732019-03-03 13:12:43 -080056 f = self.splines[spline_edit][5]
57 e = self.splines[spline_edit][4]
58 d = self.splines[spline_edit][3]
James Kuszmaulb33b07c2021-02-25 22:39:24 -080059 self.splines[spline_edit + 1][0] = f
60 self.splines[spline_edit + 1][1] = f * 2 + e * -1
61 self.splines[spline_edit + 1][2] = d + f * 4 + e * -4
John Park91e69732019-03-03 13:12:43 -080062
63 if not spline_edit == 0:
John Park91e69732019-03-03 13:12:43 -080064 a = self.splines[spline_edit][0]
65 b = self.splines[spline_edit][1]
66 c = self.splines[spline_edit][2]
James Kuszmaulb33b07c2021-02-25 22:39:24 -080067 self.splines[spline_edit - 1][5] = a
68 self.splines[spline_edit - 1][4] = a * 2 + b * -1
69 self.splines[spline_edit - 1][3] = c + a * 4 + b * -4
John Park91e69732019-03-03 13:12:43 -080070
71 def updates_for_mouse_move(self, index_of_edit, spline_edit, x, y, difs):
72 if index_of_edit > -1:
73 self.splines[spline_edit][index_of_edit] = [pxToM(x), pxToM(y)]
74
75 if index_of_edit == 5:
76 self.splines[spline_edit][
77 index_of_edit -
78 2] = self.splines[spline_edit][index_of_edit - 2] + difs
79 self.splines[spline_edit][
80 index_of_edit -
81 1] = self.splines[spline_edit][index_of_edit - 1] + difs
82
83 if index_of_edit == 0:
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 == 4:
92 self.splines[spline_edit][
93 index_of_edit -
94 1] = self.splines[spline_edit][index_of_edit - 1] + difs
95
96 if index_of_edit == 1:
97 self.splines[spline_edit][
98 index_of_edit +
99 1] = self.splines[spline_edit][index_of_edit + 1] + difs
100
James Kuszmaulb33b07c2021-02-25 22:39:24 -0800101 self.splineExtrapolate(spline_edit)
John Park91e69732019-03-03 13:12:43 -0800102
103 def update_lib_spline(self):
104 self.libsplines = []
105 array = np.zeros(shape=(6, 2), dtype=float)
106 for points in self.splines:
107 for j, point in enumerate(points):
108 array[j, 0] = point[0]
109 array[j, 1] = point[1]
110 spline = Spline(np.ascontiguousarray(np.transpose(array)))
111 self.libsplines.append(spline)
112
Ravago Jones3b92afa2021-02-05 14:27:32 -0800113 def toMultiSpline(self):
114 multi_spline = {
115 "spline_count": 0,
116 "spline_x": [],
117 "spline_y": [],
118 "constraints": self.constraints,
119 }
120 for points in self.splines:
121 multi_spline["spline_count"] += 1
122 for j, point in enumerate(points):
123 if j == 0 and multi_spline["spline_count"] > 1:
124 continue # skip overlapping points
125 multi_spline["spline_x"].append(point[0])
126 multi_spline["spline_y"].append(point[1])
127 return multi_spline
128
129 def fromMultiSpline(self, multi_spline):
130 self.constraints = multi_spline["constraints"]
131 self.splines = []
132 self.points = []
133
134 i = 0
135 for j in range(multi_spline["spline_count"]):
136 # get the last point of the last spline
137 # and read in another 6 points
138 for i in range(i, i + 6):
139 self.points.append(
140 [multi_spline["spline_x"][i], multi_spline["spline_y"][i]])
141 self.splines.append(np.array(self.points))
142 self.points = []
143 self.update_lib_spline()
144
John Park91e69732019-03-03 13:12:43 -0800145 def getSplines(self):
146 return self.splines
147
John Park91e69732019-03-03 13:12:43 -0800148 def setSplines(self, spline_edit, index_of_edit, x, y):
149 self.splines[spline_edit][index_of_edit] = [x, y]
150
151 def add_point(self, x, y):
152 if (len(self.points) < 6):
153 self.points.append([pxToM(x), pxToM(y)])
154 if (len(self.points) == 6):
155 self.splines.append(np.array(self.points))
156 self.points = []
157 self.update_lib_spline()
158 return True
159
160 def extrapolate(self, point1, point2,
161 point3): # where point3 is 3rd to last point
162 self.points.append(point1)
163 self.points.append(point1 * 2 - point2)
164 self.points.append(point3 + point1 * 4 - point2 * 4)