forked from AnishTheWizard/PathExtrapolator
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathPathReformatter.py
174 lines (141 loc) · 6.24 KB
/
PathReformatter.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
from __future__ import annotations
import math
import numpy as np
import csv
import sys
import json
from typing import Any, Iterable, Tuple, List
from matplotlib import pyplot as plt
from numpy import ndarray
from pandas import read_csv, Series, DataFrame, read_json
from scipy.interpolate import CubicSpline, CubicHermiteSpline
def process_path_planner_csv(file: str, conversion_factor: float) -> Tuple[
Any, List[float | Any], List[float | Any], List[float], Any, List[float], List[float], List[Any]]:
data = read_csv(file, skiprows=1)
t = data['# timeSeconds'].tolist()
x = data[' xPositionMeters'].tolist()
y = data[' yPositionMeters'].tolist()
heading = data[' holonomicRotationDegrees'].tolist()
lin_vel = data[' velocityMetersPerSecond'].tolist()
ang_vel = data[' holonomicAngularVelocityDegreesPerSec'].tolist()
directionalMotion = data[' headingDegrees'].tolist()
x_offset = x[0]
y_offset = y[0]
heading_offset = heading[0]
x = [(position - x_offset) * -conversion_factor for position in x]
y = [(position - y_offset) * conversion_factor for position in y]
# events = [[(x_pos - x_offset) * -1, y_pos-y_offset, name] for x_pos, y_pos, name in events]
heading_shifted = [position + 180 for position in heading]
last_direction = heading_shifted[0]
heading_offset = heading_shifted[0]
overflows = 0
heading_filtered = list()
for direction in heading_shifted:
if direction - last_direction > 180:
overflows -= 1
elif direction - last_direction < -180:
overflows += 1
heading_filtered.append(math.radians(overflows * 360 + direction - heading_offset))
last_direction = direction
ang_vel = [math.radians(omega) for omega in ang_vel]
directionalMotion = [math.radians((direction % 360) - 90) for direction in directionalMotion]
return t, x, y, heading_filtered, lin_vel, ang_vel, directionalMotion, [x_offset, y_offset]
# events is [[x, y, name]]
def export_reformatted_csv(file_name, t, x, y, heading, lin_vel, ang_vel, directionalMotion, events):
with open(file_name, "w", newline='') as file:
csv_writer = csv.writer(file)
j = 0
for i in range(0, len(x)):
event = ""
if j < len(events):
if math.isclose(x[i], events[j][0], rel_tol=.01) and math.isclose(y[i], events[j][1], rel_tol=.01):
event = events[j][2]
events[j][0] = x[i]
events[j][1] = y[i]
j += 1
csv_writer.writerow([t[i], x[i], y[i], heading[i], lin_vel[i], ang_vel[i], directionalMotion[i], event])
file.flush()
file.close()
return events
def display_charts(linear_eval_space: ndarray, x_eval: ndarray, y_eval: ndarray, heading: ndarray, events):
figure, axis = plt.subplots(2, 1)
axis[0].plot(x_eval, y_eval)
axis[0].plot([i[0] for i in events], [i[1] for i in events], 'o')
axis[0].set_title("actual path")
axis[1].plot(linear_eval_space, heading)
axis[1].set_title("heading")
plt.show()
def process_path_json(file_path: str):
data = json.load(open(file_path, "r"))
return data
if __name__ == '__main__':
filename = 'New_New_New_New_Path'
t, y, x, heading, lin_vel, ang_vel, directional_motion, offsets = process_path_planner_csv('D:\\FRC Charged Up\\FRCProjects\\2023RobotCode\\src\\main\\deploy\\pathplanner\\generatedCSV\\New New New New Path.csv', 1)
# for three-piece auto
# event_poses = [
# [1, "intake.extend"],
# [2, "intake.runIn"],
# [3, "intake.stop"],
# [5, "intake.runOut"],
# [6, "intake.stop"],
# [8, 'intake.runIn'],
# [9, 'intake.stop'],
# [12, 'intake.runOut']
# ]
#start count from 0
# event_poses = [
# # [1, "intake.extend"],
# # [2, "intake.runIn"],
# # [3, "intake.stop"],
# # [5, "intake.runOut"],
# # [6, "intake.stop"],
# # [8, 'intake.runIn'],
# [3, 'intake.runIn'],
# [4, 'intake.stop']
# ]
waypoints = process_path_json("D:\\FRC Charged Up\\FRCProjects\\2023RobotCode\\src\\main\\deploy\\pathplanner\\New New New Path.path")['waypoints']
'''
t, y, x, heading, lin_vel, ang_vel, directional_motion, offsets = process_path_planner_csv('D:\\FRC Charged Up\\FRCProjects\\2023RobotCode\\src\\main\\deploy\\pathplanner\\generatedCSV\\New New New New Path.csv', 1)
# for three-piece auto
event_poses = [
[1, "intake.extend"],
[4, "intake.runIn"],
[6, "intake.stop"],
[9, "intake.runOut"],
[10, "intake.stop"],
[11, 'intake.runIn'],
[12, 'intake.stop'],
[16, 'intake.runOut']
]
# event_poses = [
# [2, "intake.extend"],
# [4, "intake.runIn"],
# [5, "intake.stop"],
#
# ]
# waypoints = process_path_json("D:\\FRC Charged Up\\FRCProjects\\2023RobotCode\\src\\main\\deploy\\pathplanner\\New New New New Path.path")['waypoints']
'''
# event_poses = [[1, "intake.extend"],
# [1, "intake.runIn"],
# [2, "intake.retract"]]
# [3, "intake.deadStop"]]
# event_poses = [[1, "intake.runIn"],
# [2, "intake.stop"]]
# event_poses = [
# [2, "intake.extend"],
# [4, "intake.runIn"],
# [5, "intake.stop"],
#
# ]
event_poses = []
for i in range(len(event_poses)):
# wp_num = event_poses[i][0] - 1
wp_num = event_poses[i][0]
ev_name = event_poses[i][1]
event_poses[i] = [waypoints[wp_num]['anchorPoint']['y'], waypoints[wp_num]['anchorPoint']['x'], ev_name]
for i in range(len(event_poses)):
event_poses[i][0] = event_poses[i][0] - offsets[1]
event_poses[i][1] = offsets[0] - event_poses[i][1]
event_poses = export_reformatted_csv('blue_'+ filename + '.csv', t, x, y, heading, lin_vel, ang_vel, directional_motion, event_poses)
export_reformatted_csv('red_'+ filename + '.csv', t, [-i for i in x], y, [-i for i in heading], lin_vel, ang_vel, [-i for i in directional_motion], [[-x, y, name] for x, y, name in event_poses])
display_charts(t, [-i for i in x], y, [-i for i in lin_vel], [[-x, y, name] for x, y, name in event_poses])