blob: 4444a72edb4207efc6b3e91120a0a83a5e1ef4de [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
39 def addConstraintsToTrajectory(self, trajectory):
40 for constraint in self.constraints:
41 if constraint["constraint_type"] == "VOLTAGE":
42 trajectory.SetVoltageLimit(constraint["value"])
43 elif constraint["constraint_type"] == "LATERAL_ACCELERATION":
44 trajectory.SetLateralAcceleration(constraint["value"])
45 elif constraint["constraint_type"] == "LONGITUDINAL_ACCELERATION":
46 trajectory.SetLongitudinalAcceleration(constraint["value"])
47
John Park91e69732019-03-03 13:12:43 -080048 def splineExtrapolate(self, o_spline_edit):
49 spline_edit = o_spline_edit
50 if not spline_edit == len(self.splines) - 1:
51 spline_edit = spline_edit + 1
52 f = self.splines[spline_edit][5]
53 e = self.splines[spline_edit][4]
54 d = self.splines[spline_edit][3]
55 self.splines[spline_edit][0] = f
56 self.splines[spline_edit][1] = f * 2 + e * -1
57 self.splines[spline_edit][2] = d + f * 4 + e * -4
58
59 if not spline_edit == 0:
60 spline_edit = spline_edit - 1
61 a = self.splines[spline_edit][0]
62 b = self.splines[spline_edit][1]
63 c = self.splines[spline_edit][2]
64 self.splines[spline_edit][5] = a
65 self.splines[spline_edit][4] = a * 2 + b * -1
66 self.splines[spline_edit][3] = c + a * 4 + b * -4
67
68 return spline_edit
69
70 def updates_for_mouse_move(self, index_of_edit, spline_edit, x, y, difs):
71 if index_of_edit > -1:
72 self.splines[spline_edit][index_of_edit] = [pxToM(x), pxToM(y)]
73
74 if index_of_edit == 5:
75 self.splines[spline_edit][
76 index_of_edit -
77 2] = self.splines[spline_edit][index_of_edit - 2] + difs
78 self.splines[spline_edit][
79 index_of_edit -
80 1] = self.splines[spline_edit][index_of_edit - 1] + difs
81
82 if index_of_edit == 0:
83 self.splines[spline_edit][
84 index_of_edit +
85 2] = self.splines[spline_edit][index_of_edit + 2] + difs
86 self.splines[spline_edit][
87 index_of_edit +
88 1] = self.splines[spline_edit][index_of_edit + 1] + difs
89
90 if index_of_edit == 4:
91 self.splines[spline_edit][
92 index_of_edit -
93 1] = self.splines[spline_edit][index_of_edit - 1] + difs
94
95 if index_of_edit == 1:
96 self.splines[spline_edit][
97 index_of_edit +
98 1] = self.splines[spline_edit][index_of_edit + 1] + difs
99
100 return self.splineExtrapolate(spline_edit)
101
102 def update_lib_spline(self):
103 self.libsplines = []
104 array = np.zeros(shape=(6, 2), dtype=float)
105 for points in self.splines:
106 for j, point in enumerate(points):
107 array[j, 0] = point[0]
108 array[j, 1] = point[1]
109 spline = Spline(np.ascontiguousarray(np.transpose(array)))
110 self.libsplines.append(spline)
111
Ravago Jones3b92afa2021-02-05 14:27:32 -0800112 def toMultiSpline(self):
113 multi_spline = {
114 "spline_count": 0,
115 "spline_x": [],
116 "spline_y": [],
117 "constraints": self.constraints,
118 }
119 for points in self.splines:
120 multi_spline["spline_count"] += 1
121 for j, point in enumerate(points):
122 if j == 0 and multi_spline["spline_count"] > 1:
123 continue # skip overlapping points
124 multi_spline["spline_x"].append(point[0])
125 multi_spline["spline_y"].append(point[1])
126 return multi_spline
127
128 def fromMultiSpline(self, multi_spline):
129 self.constraints = multi_spline["constraints"]
130 self.splines = []
131 self.points = []
132
133 i = 0
134 for j in range(multi_spline["spline_count"]):
135 # get the last point of the last spline
136 # and read in another 6 points
137 for i in range(i, i + 6):
138 self.points.append(
139 [multi_spline["spline_x"][i], multi_spline["spline_y"][i]])
140 self.splines.append(np.array(self.points))
141 self.points = []
142 self.update_lib_spline()
143
John Park91e69732019-03-03 13:12:43 -0800144 def getSplines(self):
145 return self.splines
146
John Park91e69732019-03-03 13:12:43 -0800147 def setSplines(self, spline_edit, index_of_edit, x, y):
148 self.splines[spline_edit][index_of_edit] = [x, y]
149
150 def add_point(self, x, y):
151 if (len(self.points) < 6):
152 self.points.append([pxToM(x), pxToM(y)])
153 if (len(self.points) == 6):
154 self.splines.append(np.array(self.points))
155 self.points = []
156 self.update_lib_spline()
157 return True
158
159 def extrapolate(self, point1, point2,
160 point3): # where point3 is 3rd to last point
161 self.points.append(point1)
162 self.points.append(point1 * 2 - point2)
163 self.points.append(point3 + point1 * 4 - point2 * 4)