-
Notifications
You must be signed in to change notification settings - Fork 12
/
dvl.py
415 lines (366 loc) · 13.8 KB
/
dvl.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
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
"""
Code for integration of Waterlinked DVL A50 with Companion and ArduSub
"""
import threading
import time
from mavlink2resthelper import Mavlink2RestHelper
from blueoshelper import request
import json
import socket
from select import select
import math
import os
from enum import Enum
HOSTNAME = "192.168.2.117"
DVL_DOWN = 1
DVL_FORWARD = 2
class MessageType(str, Enum):
POSITION_DELTA = "POSITION_DELTA"
POSITION_ESTIMATE = "POSITION_ESTIMATE"
SPEED_ESTIMATE = "SPEED_ESTIMATE"
def contains(value):
return value in set(item.value for item in MessageType)
class DvlDriver (threading.Thread):
"""
Responsible for the DVL interactions themselves.
This handles fetching the DVL data and forwarding it to Ardusub
"""
status = "Starting"
version = ""
mav = Mavlink2RestHelper()
socket = None
port = 0
last_attitude = (0, 0, 0) # used for calculating the attitude delta
current_orientation = DVL_DOWN
enabled = True
rangefinder = True
hostname = HOSTNAME
timeout = 3 # tcp timeout in seconds
origin = [0, 0]
settings_path = os.path.join(os.path.expanduser(
"~"), ".config", "dvl", "settings.json")
should_send = MessageType.POSITION_DELTA
def __init__(self, orientation=DVL_DOWN):
threading.Thread.__init__(self)
self.current_orientation = orientation
def load_settings(self):
"""
Load settings from .config/dvl/settings.json
"""
try:
with open(self.settings_path) as settings:
data = json.load(settings)
self.enabled = data["enabled"]
self.current_orientation = data["orientation"]
self.hostname = data["hostname"]
self.origin = data["origin"]
self.rangefinder = data["rangefinder"]
self.should_send = data["should_send"]
print("Loaded settings: ", data)
except FileNotFoundError:
print("Settings file not found, using default.")
except ValueError:
print("File corrupted, using default settings.")
except KeyError as error:
print("key not found: ", error)
print("using default instead")
def save_settings(self):
"""
Load settings from .config/dvl/settings.json
"""
def ensure_dir(file_path):
"""
Helper to guarantee that the file path exists
"""
directory = os.path.dirname(file_path)
if not os.path.exists(directory):
os.makedirs(directory)
ensure_dir(self.settings_path)
with open(self.settings_path, 'w') as settings:
settings.write(json.dumps({
"enabled": self.enabled,
"orientation": self.current_orientation,
"hostname": self.hostname,
"origin": self.origin,
"rangefinder": self.rangefinder,
"should_send": self.should_send,
}))
def get_status(self) -> dict:
"""
Returns a dict with the current status
"""
return {
"status": self.status,
"enabled": self.enabled,
"orientation": self.current_orientation,
"hostname": self.hostname,
"origin": self.origin,
"rangefinder": self.rangefinder,
"should_send": self.should_send,
}
@property
def host(self):
""" Make sure there is no port in the hostname allows local testing by where http can be running on other ports than 80"""
try:
host = self.hostname.split(":")[0]
except IndexError:
host = self.hostname
return host
def look_for_dvl(self):
"""
Waits for the dvl to show up at the designated hostname
"""
ip = self.hostname
self.status = f"Trying to talk to dvl at http://{ip}/api/v1/about"
while not self.version:
# TODO: get mdns back in here
try:
self.version = request(f"http://{ip}/api/v1/about")
except Exception as e:
print(f"could not open url at ip {ip} : {e}")
time.sleep(1)
def detect_port(self):
"""
Fetchs the TCP port from the DVL api, stores in self.port
"""
while not self.port:
time.sleep(1)
port_raw = request(
"http://{0}/api/v1/outputs/tcp".format(self.hostname))
if port_raw:
data = json.loads(port_raw)
if "port" not in data:
print("no port data from API?!")
self.port = 16171
self.port = data["port"]
print("Using port {0} from API".format(self.port))
def wait_for_vehicle(self):
"""
Waits for a valid heartbeat to Mavlink2Rest
"""
self.status = "Waiting for vehicle..."
while not self.mav.get("/HEARTBEAT"):
time.sleep(1)
def set_orientation(self, orientation: int) -> bool:
"""
Sets the DVL orientation, either DVL_FORWARD of DVL_DOWN
"""
if orientation in [DVL_FORWARD, DVL_DOWN]:
self.current_orientation = orientation
self.save_settings()
return True
return False
def set_should_send(self, should_send):
if not MessageType.contains(should_send):
raise Exception(f"bad messagetype: {should_send}")
self.should_send = should_send
self.save_settings()
def set_gps_origin(self, lat, lon):
"""
Sets the EKF origin to lat, lon
"""
self.mav.set_gps_origin(lat, lon)
self.origin = [lat, lon]
self.save_settings()
def set_enabled(self, enable: bool) -> bool:
"""
Enables/disables the driver
"""
self.enabled = enable
self.save_settings()
return True
def set_use_as_rangefinder(self, enable: bool) -> bool:
"""
Enables/disables DISTANCE_SENSOR messages
"""
self.rangefinder = enable
self.save_settings()
return True
def set_hostname(self, hostname: str) -> bool:
"""
Sets the hostname where the driver looks for the DVL
(typically waterlinked-dvl.local)
"""
try:
self.hostname = hostname
if self.socket: # Don't crash if the socket hasn't been configured yet
self.socket.shutdown(socket.SHUT_RDWR)
self.socket.close()
self.setup_connections(timeout=1)
self.save_settings()
return True
except Exception as e:
print("Failed set hostname: '{}'".format(e))
return False
def setup_mavlink(self):
"""
Sets up mavlink streamrates so we have the needed messages at the
appropriate rates
"""
self.status = "Setting up MAVLink streams..."
self.mav.ensure_message_frequency('ATTITUDE', 30, 5)
def setup_params(self):
"""
Sets up the required params for DVL integration
"""
self.mav.set_param("AHRS_EKF_TYPE", "MAV_PARAM_TYPE_UINT8", 3)
# TODO: Check if really required. It doesn't look like the ekf2 stops at all
self.mav.set_param("EK2_ENABLE", "MAV_PARAM_TYPE_UINT8", 0)
self.mav.set_param("EK3_ENABLE", "MAV_PARAM_TYPE_UINT8", 1)
self.mav.set_param("VISO_TYPE", "MAV_PARAM_TYPE_UINT8", 1)
self.mav.set_param("EK3_GPS_TYPE", "MAV_PARAM_TYPE_UINT8", 3)
self.mav.set_param("EK3_SRC1_POSXY", "MAV_PARAM_TYPE_UINT8", 6) # EXTNAV
self.mav.set_param("EK3_SRC1_VELXY", "MAV_PARAM_TYPE_UINT8", 6) # EXTNAV
self.mav.set_param("EK3_SRC1_POSZ", "MAV_PARAM_TYPE_UINT8", 1) # BARO
def setup_connections(self, timeout=300):
"""
Sets up the socket to talk to the DVL
"""
while timeout > 0:
try:
self.socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
self.socket.connect((self.host, self.port))
self.socket.setblocking(0)
return True
except socket.error:
time.sleep(0.1)
timeout -= 1
self.status = "Setup connection timeout"
return False
def reconnect(self):
if self.socket:
try:
self.socket.shutdown(socket.SHUT_RDWR)
self.socket.close()
except:
pass
success = self.setup_connections()
if success:
self.last_recv_time = time.time() # Don't disconnect directly after connect
return True
return False
def update_attitude(self) -> list:
"""
Fetchs the Attitude and calculate Attitude deltas
"""
# Getting the data from mavlink2rest takes around 5ms
attitude_raw = self.mav.get("/ATTITUDE")
if not attitude_raw:
# TODO: report status?
print("Failed fetching attitude!")
return [0, 0, 0]
attitude = json.loads(attitude_raw)
current_attitude = (
attitude["roll"], attitude["pitch"], attitude["yaw"])
angles = list(map(float.__sub__, current_attitude, self.last_attitude))
angles[2] = angles[2] % (math.pi*2)
self.last_attitude = current_attitude
return angles
def handle_velocity(self, data):
# TODO: test if this is used by ArduSub or could be [0, 0, 0]
# extract velocity data from the DVL JSON
vx, vy, vz, alt, valid, fom = data["vx"], data["vy"], data["vz"], data["altitude"], data["velocity_valid"], data["fom"]
dt = data["time"] / 1000
dx = dt*vx
dy = dt*vy
dz = dt*vz
# fom is the standard deviation. scaling it to a confidence from 0-100%
# 0 is a very good measurement, 0.4 is considered a inaccurate measurement
_fom_max = 0.4
confidence = 100 * (1-min(_fom_max, fom)/_fom_max) if valid else 0
# confidence = 100 if valid else 0
# feeding back the angles seem to aggravate the gyro drift issue
# angles = self.update_attitude()
angles = [0, 0, 0]
if self.rangefinder:
self.mav.send_rangefinder(alt)
if not valid:
return
if self.should_send == MessageType.POSITION_DELTA:
if self.current_orientation == DVL_DOWN:
self.mav.send_vision([dx, dy, dz],
angles,
dt=data["time"]*1e3,
confidence=confidence)
elif self.current_orientation == DVL_FORWARD:
self.mav.send_vision([dz, dy, -dx],
angles,
dt=data["time"]*1e3,
confidence=confidence)
elif self.should_send == MessageType.SPEED_ESTIMATE:
if self.current_orientation == DVL_DOWN:
self.mav.send_vision_speed_estimate([vx, vy, vz])
elif self.current_orientation == DVL_FORWARD:
self.mav.send_vision_speed_estimate([vz, vy, -vx])
def handle_position_local(self, data):
if self.should_send == MessageType.POSITION_ESTIMATE:
x, y, z, roll, pitch, yaw = data["x"], data["y"], data["z"], data["roll"], data["pitch"], data["yaw"]
timestamp = data["ts"]
self.mav.send_vision_position_estimate(
timestamp,
[x, y, z],
[roll, pitch, yaw])
def run(self):
"""
Runs the main routing
"""
self.load_settings()
self.look_for_dvl()
self.detect_port()
self.setup_connections()
self.wait_for_vehicle()
self.setup_mavlink()
self.setup_params()
time.sleep(1)
#self.set_gps_origin(*self.origin)
self.status = "Running"
self.last_recv_time = time.time()
buf = ""
connected = True
while True:
if not self.enabled:
time.sleep(1)
buf = "" # Reset buf when disabled
continue
r, _, _ = select([self.socket], [], [], 0)
data = None
if r:
try:
recv = self.socket.recv(1024).decode()
connected = True
if recv:
self.last_recv_time = time.time()
buf += recv
except socket.error as e:
print("Disconnected")
connected = False
except Exception as e:
print("Error receiveing:", e)
pass
# Extract 1 complete line from the buffer if available
if len(buf) > 0:
lines = buf.split("\n", 1)
if len(lines) > 1:
buf = lines[1]
data = json.loads(lines[0])
if not connected:
buf = ""
self.status = "restarting"
dis = self.reconnect()
time.sleep(0.003)
continue
if not data:
if time.time() - self.last_recv_time > self.timeout:
buf = ""
self.status = "timeout, restarting"
connected = self.reconnect()
time.sleep(0.003)
continue
self.status = "Running"
if "type" not in data:
continue
if data["type"] == "velocity":
self.handle_velocity(data)
if data["type"] == "position_local":
self.handle_position_local(data)
time.sleep(0.003)