-
Notifications
You must be signed in to change notification settings - Fork 0
/
flask_app.py
285 lines (221 loc) · 8.24 KB
/
flask_app.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
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
""""Path Builder Module
Depending on the arguments passed, this module can be used the following ways:
- To run certain path functions from the command line
- To launch and serve as the backend to the path builder GUI
CLI Args:
--file_path: The relative path to the global path file.
--interpolate: The interval spacing for interpolation.
--delete: Whether to delete generated global path files.
"""
import csv
import os
import re
import webbrowser
from typing import Dict, List, Tuple
from os import walk
import numpy as np
import plotly.graph_objects as go
from _path import Path
from _helper_lat_lon import HelperLatLon
from flask import Flask, jsonify, render_template, request
from node_mock_global_path import (
_interpolate_path,
calculate_interval_spacing,
write_to_file,
)
app = Flask(__name__)
DEFAULT_DIR = os.path.dirname(os.path.abspath(__file__))
def main():
# extra_dirs is used to reload the server when a file is changed for debugging
extra_dirs = [
"/workspaces/path_builder",
]
extra_files = extra_dirs[:]
for extra_dir in extra_dirs:
for dirname, dirs, files in walk(extra_dir):
for filename in files:
filename = os.path.join(dirname, filename)
if os.path.isfile(filename):
extra_files.append(filename)
webbrowser.open("http://127.0.0.1:5000")
# opens two tabs on startup when debug=True
app.run(host="0.0.0.0", port=5000, debug=True, extra_files=extra_files)
@app.route("/")
def _index():
return render_template("index.html")
@app.route("/export_waypoints", methods=["POST"])
def _export_waypoints():
data = request.json
result = _handle_export(data)
return jsonify(result)
@app.route("/import_waypoints", methods=["POST"])
def _import_waypoints():
data = request.json
result = _handle_import(data)
return jsonify(result)
@app.route("/plot_path", methods=["POST"])
def _plot_path():
data = request.json
result = _handle_plot(data)
return jsonify(result)
@app.route("/delete_paths", methods=["POST"])
def _delete_paths():
data = request.json
result = _handle_delete(data)
return jsonify(result)
@app.route("/interpolate_path", methods=["POST"])
def _interpolate_path_():
data = request.json
result = _handle_interpolate(data)
return jsonify(result)
def _handle_export(data):
filename = data.get("filename", "")
waypoints = data.get("waypoints", [])
file_path = os.path.join(DEFAULT_DIR, filename)
if not str(filename).endswith(".csv"):
file_path = file_path + ".csv"
# convert from json to list of HelperLatLon
waypoints = [
(HelperLatLon(latitude=float(item["lat"]), longitude=float(item["lon"])))
for item in waypoints
]
# convert to Path, to pass to file writer
path = Path(waypoints=waypoints)
try:
write_to_file(file_path=file_path, global_path=path, tmstmp=False)
return {"status": "success", "message": "Waypoints exported successfully"}
except Exception as e:
return {"status": "error", "message": f"Error exporting waypoints: {str(e)}"}
def _handle_import(data):
filename = data.get("filename", "")
file_path = os.path.join(DEFAULT_DIR, filename)
if not str(filename).endswith(".csv"):
file_path = file_path + ".csv"
try:
with open(file_path, "r") as f:
reader = csv.reader(f)
# skip header
reader.__next__()
waypoints = list(reader)
waypoints = [{"lat": float(item[0]), "lon": float(item[1])} for item in waypoints]
return {
"status": "success",
"message": "Waypoints imported successfully",
"waypoints": waypoints,
}
except Exception as e:
return {"status": "error", "message": f"Error importing waypoints: {str(e)}"}
def _handle_plot(data):
waypoints = data.get("waypoints", [])
# convert from json to list of HelperLatLon
waypoints = [(float(item["lat"]), float(item["lon"])) for item in waypoints]
waypoints = np.array(waypoints)
lats, lons = waypoints.T
try:
plot_global_path(lats, lons)
return {"status": "success", "message": "Path plotted successfully"}
except Exception as e:
return {"status": "error", "message": f"Error plotting path: {str(e)}"}
def _handle_delete(data):
key = data.get("key", None)
try:
delete_files(key=key)
return {"status": "success", "message": "Paths deleted successfully"}
except Exception as e:
return {"status": "error", "message": f"Error deleting paths: {str(e)}"}
def _handle_interpolate(data):
waypoints = data.get("waypoints", [])
interval_spacing = float(data.get("interval_spacing", 30.0))
# convert from json to list of HelperLatLon
waypoints = [
(HelperLatLon(latitude=float(item["lat"]), longitude=float(item["lon"])))
for item in waypoints
]
# convert to Path, to pass to interpolator
path = Path(waypoints=waypoints)
# pop out the first waypoint as point1, since the interpolator will add it to the start of path
point1 = path.waypoints.pop(0)
path_spacing = calculate_interval_spacing(pos=point1, waypoints=path.waypoints)
path = _interpolate_path(
global_path=path,
interval_spacing=interval_spacing,
pos=point1,
path_spacing=path_spacing,
)
# add first waypoint back to the start of path
path.waypoints = [point1] + path.waypoints
# convert waypoints to serializable format
waypoints = [
{"lat": float(item.latitude), "lon": float(item.longitude)} for item in path.waypoints
]
return {
"status": "success",
"message": f"{len(waypoints)} Waypoints exported successfully",
"waypoints": waypoints,
}
def delete_files(key=None):
""" "Deletes all files in /global_paths that match the given key (if any) or that contain a
timestamp."""
dir_path = "/workspaces/sailbot_workspace/src/local_pathfinding/global_paths"
files = os.listdir(dir_path)
timestamp_pattern = re.compile(r"_\d{4}-\d{2}-\d{2}_\d{2}-\d{2}-\d{2}\.csv")
# check if a keyword was entered
if key is not None:
key = re.compile(rf"{key}")
for file_name in files:
if re.search(timestamp_pattern, file_name) or (
key is not None and re.search(key, file_name)
):
file_path = os.path.join(dir_path, file_name)
try:
os.remove(file_path)
print(f"Deleted: {os.path.basename(file_path)} from /global_paths")
except OSError as e:
print(f"Error deleting {file_path}: {e}")
def get_lats_and_lons(file_path: str) -> Tuple[List[float], List[float]]:
"""Reads a csv file and returns the lats and lons as lists"""
lats = []
lons = []
with open(file_path, "r") as file:
reader = csv.reader(file)
# skip header
reader.__next__()
for row in reader:
lats.append(float(row[0]))
lons.append(float(row[1]))
return lats, lons
def plot_global_path(lats, lons):
"""3D plotter with plotly"""
fig = go.Figure(
data=go.Scattergeo(
lat=lats,
lon=lons,
mode="markers+lines",
line=dict(width=2, color="blue"),
)
)
fig.update_layout(
title_text="Mock Global Path Plot",
showlegend=True,
geo=dict(
showland=True,
showcountries=True,
showocean=True,
countrywidth=0.5,
landcolor="rgb(230, 145, 56)",
lakecolor="rgb(0, 255, 255)",
oceancolor="rgb(0, 255, 255)",
projection=dict(type="orthographic", rotation=dict(lon=-100, lat=40, roll=0)),
lonaxis=dict(showgrid=True, gridcolor="rgb(102, 102, 102)", gridwidth=0.5),
lataxis=dict(showgrid=True, gridcolor="rgb(102, 102, 102)", gridwidth=0.5),
),
)
fig.show()
def lats_and_lons_to_dict(
lats: List[float], lons: List[float], num_decimals: int = 4
) -> Dict[int, str]:
return {
i: f"({lats[i]:.{num_decimals}f}, {lons[i]:.{num_decimals}f})" for i in range(len(lats))
}
if __name__ == "__main__":
main()