-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathExperimentControl.py
1272 lines (1060 loc) · 40.8 KB
/
ExperimentControl.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
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
'''Experiment suite for ROV cross-current experiment'''
from tokenize import Double
import PySimpleGUI as sg
import cv2
import gi
import numpy as np
import sys
from utils import ARUCO_DICT
import argparse
import time
from pymavlink import mavutil
import copy
import threading
import socket
import pickle
import json
from math import sqrt
from scipy.spatial.transform import Rotation as R
import csv
gi.require_version('Gst', '1.0')
from gi.repository import Gst
class Video():
"""BlueRov video capture class constructor
Attributes:
port (int): Video UDP port
video_codec (string): Source h264 parser
video_decode (string): Transform YUV (12bits) to BGR (24bits)
video_pipe (object): GStreamer top-level pipeline
video_sink (object): Gstreamer sink element
video_sink_conf (string): Sink configuration
video_source (string): Udp source ip and port
latest_frame (np.ndarray): Latest retrieved video frame
"""
def __init__(self, port=5600):
"""Summary
Args:
port (int, optional): UDP port
"""
Gst.init(None)
self.port = port
self.latest_frame = self._new_frame = None
# [Software component diagram](https://www.ardusub.com/software/components.html)
# UDP video stream (:5600)
self.video_source = 'udpsrc port={}'.format(self.port)
# [Rasp raw image](http://picamera.readthedocs.io/en/release-0.7/recipes2.html#raw-image-capture-yuv-format)
# Cam -> CSI-2 -> H264 Raw (YUV 4-4-4 (12bits) I420)
self.video_codec = '! application/x-rtp, payload=96 ! rtph264depay ! h264parse ! avdec_h264'
# Python don't have nibble, convert YUV nibbles (4-4-4) to OpenCV standard BGR bytes (8-8-8)
self.video_decode = \
'! decodebin ! videoconvert ! video/x-raw,format=(string)BGR ! videoconvert'
# Create a sink to get data
self.video_sink_conf = \
'! appsink emit-signals=true sync=false max-buffers=2 drop=true'
self.video_pipe = None
self.video_sink = None
self.run()
def start_gst(self, config=None):
""" Start gstreamer pipeline and sink
Pipeline description list e.g:
[
'videotestsrc ! decodebin', \
'! videoconvert ! video/x-raw,format=(string)BGR ! videoconvert',
'! appsink'
]
Args:
config (list, optional): Gstreamer pileline description list
"""
if not config:
config = \
[
'videotestsrc ! decodebin',
'! videoconvert ! video/x-raw,format=(string)BGR ! videoconvert',
'! appsink'
]
command = ' '.join(config)
self.video_pipe = Gst.parse_launch(command)
self.video_pipe.set_state(Gst.State.PLAYING)
self.video_sink = self.video_pipe.get_by_name('appsink0')
@staticmethod
def gst_to_opencv(sample):
"""Transform byte array into np array
Args:
sample (TYPE): Description
Returns:
TYPE: Description
"""
buf = sample.get_buffer()
caps_structure = sample.get_caps().get_structure(0)
array = np.ndarray(
(
caps_structure.get_value('height'),
caps_structure.get_value('width'),
3
),
buffer=buf.extract_dup(0, buf.get_size()), dtype=np.uint8)
return array
def frame(self):
""" Get Frame
Returns:
np.ndarray: latest retrieved image frame
"""
if self.frame_available:
self.latest_frame = self._new_frame
# reset to indicate latest frame has been 'consumed'
self._new_frame = None
return self.latest_frame
def frame_available(self):
"""Check if a new frame is available
Returns:
bool: true if a new frame is available
"""
return self._new_frame is not None
def run(self):
""" Get frame to update _new_frame
"""
self.start_gst(
[
self.video_source,
self.video_codec,
self.video_decode,
self.video_sink_conf
])
self.video_sink.connect('new-sample', self.callback)
def callback(self, sink):
sample = sink.emit('pull-sample')
self._new_frame = self.gst_to_opencv(sample)
return Gst.FlowReturn.OK
def maprange( a, b, s):
(a1, a2), (b1, b2) = a, b
return b1 + ((s - a1) * (b2 - b1) / (a2 - a1))
def pose_esitmation(frame, aruco_dict_type, matrix_coefficients, distortion_coefficients, tagSize):
'''
frame - Frame from the video stream
aruco_dict_type - self-explanatory, the aruco dictionary containing the tag
matrix_coefficients - Intrinsic matrix of the calibrated camera
distortion_coefficients - Distortion coefficients associated with your camera
tagSize - the size of the tag (black area) in m = 1.2
return:-
frame - The frame with the axis drawn on it
rvec - rotation vector (opencv condensed version)
tvec - translation vector, translation in x,y,z in m
'''
gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY)
cv2.aruco_dict = cv2.aruco.Dictionary_get(aruco_dict_type)
parameters = cv2.aruco.DetectorParameters_create()
corners, ids, rejected_img_points = cv2.aruco.detectMarkers(gray, cv2.aruco_dict,parameters=parameters,
cameraMatrix=matrix_coefficients,
distCoeff=distortion_coefficients)
# If markers are detected
if len(corners) > 0:
for i in range(0, len(ids)):
# Estimate pose of each marker and return the values rvec and tvec---(different from those of camera coefficients)
rvec, tvec, markerPoints = cv2.aruco.estimatePoseSingleMarkers(corners[i], tagSize, matrix_coefficients,
distortion_coefficients)
#rmat = cv2.Rodrigues(rvec)[0]
#print(rmat)
# Draw a square around the markers
cv2.aruco.drawDetectedMarkers(frame, corners)
# Draw Axis
cv2.aruco.drawAxis(frame, matrix_coefficients, distortion_coefficients, rvec, tvec, 0.1)
#cv2.putText(frame,f't:{-1*tvec}, r:{rvec}', (25, 50), cv2.FONT_HERSHEY_SIMPLEX, 0.7, (255, 0, 255), 2, 3)
else:
tvec = [[[0,0,0]]]
rvec = [[[0,0,0]]]
return frame,tvec[0][0],rvec[0][0]
class repeatedTimer(object):
def __init__(self, interval, function, *args, **kwargs):
self._timer = None
self.interval = interval
self.function = function
self.args = args
self.kwargs = kwargs
self.is_running = False
self.start()
def _run(self):
self.is_running = False
self.start()
self.function(*self.args, **self.kwargs)
def start(self):
if not self.is_running:
self._timer = threading.Timer(self.interval, self._run)
self._timer.start()
self.is_running = True
def stop(self):
self._timer.cancel()
self.is_running = False
'''LIGHTING FUNCTIONS'''
def set_servo_pwm(master, servo_n, microseconds):
""" Sets AUX 'servo_n' output PWM pulse-width.
Uses https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_SERVO
'servo_n' is the AUX port to set (assumes port is configured as a servo).
Valid values are 1-3 in a normal BlueROV2 setup, but can go up to 8
depending on Pixhawk type and firmware.
'microseconds' is the PWM pulse-width to set the output to. Commonly
between 1100 and 1900 microseconds.
"""
# master.set_servo(servo_n+8, microseconds) or:
master.mav.command_long_send(
master.target_system, master.target_component,
mavutil.mavlink.MAV_CMD_DO_SET_SERVO,
0, # first transmission of this command
servo_n + 8, # servo instance, offset by 8 MAIN outputs
microseconds, # PWM pulse-width
0,0,0,0,0 # unused parameters
)
def lightOn(master):
set_servo_pwm(master, 1, 1500)
print("light on")
return
def lightOff(master):
set_servo_pwm(master, 1, 1100)
print("light off")
return
def flashLights(master, n):
for i in range(0,n,1):
lightOn(master)
time.sleep(0.25)
lightOff(master)
time.sleep(1)
return
def lightSignal(master, fast, slow):
print("signalling with lights")
if fast > 0:
print("fast cycle")
for i in range(0,fast,1):
lightOn(master)
time.sleep(0.25)
lightOff(master)
time.sleep(0.5)
if slow > 0:
print("slow cycle")
for i in range(0,slow,1):
lightOn(master)
time.sleep(0.75)
lightOff(master)
time.sleep(0.5)
return
'''ROBOT HELPERS'''
def set_rc_channel_pwm(channel_id, pwm=1500):
""" Set RC channel pwm value
Args:
channel_id (TYPE): Channel ID
pwm (int, optional): Channel pwm value 1100-1900
"""
if channel_id < 1 or channel_id > 18:
print("Channel does not exist.")
return
# Mavlink 2 supports up to 18 channels:
# https://mavlink.io/en/messages/common.html#RC_CHANNELS_OVERRIDE
rc_channel_values = [65535 for _ in range(18)]
rc_channel_values[channel_id - 1] = pwm
master.mav.rc_channels_override_send(
master.target_system, # target_system
master.target_component, # target_component
*rc_channel_values) # RC channel list, in microseconds.
'''
RC Inputs:
1 -> Pitch
2 -> Roll
3 -> Throttle
4 -> Yaw
5 -> Forward
6 -> Lateral (strafe?)
1100 = full dir1, 1900 = full dir2, 1500 = stop
'''
def clearMotion():
# Mavlink 2 supports up to 18 channels:
# https://mavlink.io/en/messages/common.html#RC_CHANNELS_OVERRIDE
rc_channel_values = [65535 for _ in range(18)]
rc_channel_values[0] = 1500
rc_channel_values[1] = 1500
rc_channel_values[2] = 1500
rc_channel_values[3] = 1500
rc_channel_values[4] = 1500
rc_channel_values[5] = 1500
master.mav.rc_channels_override_send(
master.target_system, # target_system
master.target_component, # target_component
*rc_channel_values) # RC channel list, in microseconds.
'''
RC Inputs:
1 -> Pitch
2 -> Roll
3 -> Throttle
4 -> Yaw
5 -> Forward
6 -> Lateral (strafe?)
1100 = full dir1, 1900 = full dir2, 1500 = stop
'''
def heartbeat_helper(master):
print('start heartbeat thread')
while True:
master.mav.heartbeat_send(
6, #MAVTYPE = MAV_TYPE_GCS
8, #MAVAUTOPILOT = MAV_AUTOPILOT_INVALID
128, # MAV_MODE = MAV_MODE_FLAG_SAFETY_ARMED, have also tried 0 here
0,0)
#print('sent heartbeat')
time.sleep(0.9)
def request_message_interval(message_id: int, frequency_hz: float):
"""
Request MAVLink message in a desired frequency,
documentation for SET_MESSAGE_INTERVAL:
https://mavlink.io/en/messages/common.html#MAV_CMD_SET_MESSAGE_INTERVAL
Args:
message_id (int): MAVLink message ID
frequency_hz (float): Desired frequency in Hz
"""
master.mav.command_long_send(
master.target_system, master.target_component,
mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, 0,
message_id, # The MAVLink message ID
1e6 / frequency_hz, # The interval between two messages in microseconds. Set to -1 to disable and 0 to request default rate.
0, 0, 0, 0, # Unused parameters
0, # Target address of message stream (if message has target address fields). 0: Flight-stack default (recommended), 1: address of requestor, 2: broadcast.
)
'''GUI DEFINITIONS'''
def LEDIndicator(key, radius):
return sg.Graph(canvas_size=(radius, radius),
graph_bottom_left=(-radius, -radius),
graph_top_right=(radius, radius),
pad=(0, 0), key=key)
def SetLED(window, key, color):
graph = window[key]
graph.erase()
graph.draw_circle((0, 0), 12, fill_color=color, line_color=color)
def hapticViz(key):
width=300
canvas = sg.Graph(canvas_size=(width,width/2), graph_bottom_left=(0,0), graph_top_right=(1200,600), background_color='white', border_width=2, key=key)
return canvas
def hapticVizLine(window, key):
canvas = window[key]
canvas.draw_line(point_from=(88,300),point_to=(1112,300),color='green',width=2)
def hapticVizUpdate(window, key, circleID, force, position):
canvas = window[key]
if circleID is not None:
canvas.delete_figure(circleID)
newCircle = canvas.draw_circle(center_location=(maprange((0,2000),(0,1200),position),300),radius=(maprange((0,500),(5,50),force)),fill_color='red', line_width=0)
return newCircle
'''Logging threads'''
def hapticsThread(haptics):
global hapticsIn
global hapticsOut
while True:
#Send haptics output
hapticBytesOut = pickle.dumps(hapticsOut)
haptics.send(hapticBytesOut)
#get haptics input
hapticBytesIn = haptics.recv(128)
hapticDataIn = pickle.loads(hapticBytesIn)
#print(time.perf_counter())
#print(hapticDataIn)
hapticsIn[0] = hapticDataIn[0]
hapticsIn[1] = hapticDataIn[1]
''' MAIN '''
print("Entered main")
sg.theme('Dark Blue 15')
#Connect to blueROV2 over MAVlink
master = mavutil.mavlink_connection('udpin:0.0.0.0:14550')
master.wait_heartbeat()
print("Connected to robot!")
#Start heartbeat thread
heartbeatThread = threading.Thread(target=heartbeat_helper, args=(master,))
heartbeatThread.daemon = True
heartbeatThread.start()
#Set robot mode
# Choose a mode
mode = 'ALT_HOLD' #DEPTH_HOLD
# Check if mode is available
if mode not in master.mode_mapping():
print('Unknown mode : {}'.format(mode))
print('Try:', list(master.mode_mapping().keys()))
sys.exit(1)
# Get mode ID
mode_id = master.mode_mapping()[mode]
print(f'I know that mode: {mode_id}')
# Set new mode
# master.mav.command_long_send(
# master.target_system, master.target_component,
# mavutil.mavlink.MAV_CMD_DO_SET_MODE, 0,
# 0, mode_id, 0, 0, 0, 0, 0) or:
master.set_mode(mode_id)
##master.mav.set_mode_send(
# master.target_system,
# mavutil.mavlink.MAV_CMD_DO_SET_MODE,
# mode_id)
print('Sent mode message')
while True:
# Wait for ACK command
# Would be good to add mechanism to avoid endlessly blocking
# if the autopilot sends a NACK or never receives the message
ack_msg = master.recv_match(type='COMMAND_ACK', blocking=True)
ack_msg = ack_msg.to_dict()
# Continue waiting if the acknowledged command is not `set_mode`
if ack_msg['command'] != mavutil.mavlink.MAV_CMD_DO_SET_MODE:
continue
# Print the ACK result !
print(mavutil.mavlink.enums['MAV_RESULT'][ack_msg['result']].description)
break
master.wait_heartbeat()
#request_message_interval(mavutil.mavlink.MAVLINK_MSG_ID_AHRS3, 0.03)
#Create video object bound to ROV webcam
video = Video()
#Connect to haptic device over TCP
host = '10.55.0.1' # as both code is running on same pc
port = 8787 # socket server port number
haptics = socket.socket() # instantiate
haptics.connect((host, port)) # connect to the server
print("Connected to haptics!")
hapticsIn = [0,0]
hapticsOut = [0,500]
print('Initialising stream...')
waited = 0
i = 0
#initialize experiment setup data
participant = 0
repeat = 1
conditionString = 'No current'
tagSize = 1.12
touchControlEnabled = False
#Layout experiment parameter UI elements
setupRow = [
[sg.Text('Participant ID: '),
sg.Input(key="-PID-", size=(4,1), default_text=participant),
sg.Text(" "),
sg.VSeperator(),
sg.Text(" Conditions:"),
sg.Radio("Haptics", "Conditions", default=False, key="-condH-"),
sg.Radio("Current, no haptics", "Conditions", default=False, key="-condC-"),
sg.Radio("Control", "Conditions", default=False, key="-condN-"),
sg.Radio("Training", "Conditions", default=False, key="-condT-"),
sg.VSeperator(),
sg.Text(" Tag size (m): "),
sg.Input(key='-tag-', size=(4,1),default_text=1.12),
sg.Text(" "),
sg.VSeperator(),
sg.Text(" Repeat: "),
sg.Input(key='-rep-', size=(4,1),default_text=repeat),
sg.Text(" "),
sg.Button('Start'),
sg.Button('Pass', disabled=True),
sg.Button('Fail', disabled=True)]
]
statusCol1 = [
[sg.Text("Leak: "), LEDIndicator("-LEAK-",40)],
[sg.Text("Armed: "), LEDIndicator("-ARM-",40)],
[sg.Text("Logging:"), LEDIndicator("-LOG-",40)]
]
statusCol2 = [
[sg.Text("Vibration: "), LEDIndicator("-VIBE-",40)],
[sg.Text("Hard: "), LEDIndicator("-HARD-",40)],
[sg.Text("Control: "), LEDIndicator("-TOUCH-",40)]
]
controlCol1 = [
[sg.Button("Arm")],
[sg.Button("Confirm", disabled=True)],
[sg.Button("Disarm", disabled=True)],
[sg.Button("Touchpad", disabled=True)]
]
controlCol2 = [
[sg.Button("Up", disabled=True)],
[sg.Button("Left", disabled=True)],
[sg.Button("StrafeL", disabled=True)],
[sg.Button("Manual", disabled=False)]
]
controlCol3 = [
[sg.Button("Forward", disabled=True)],
[sg.Button("All Stop", disabled=True)],
[sg.Button("Reverse", disabled=True)],
[sg.Button("Straight", disabled=True)]
]
controlCol4 = [
[sg.Button("Down", disabled=True)],
[sg.Button("Right", disabled=True)],
[sg.Button("StrafeR", disabled=True)],
[sg.Button("Stabilize", disabled=True)]
]
hapticsCol1 = [
[sg.Button("Start vibration")],
[sg.Button("Stop vibration")]
]
hapticsCol2 = [
[sg.Button("Go soft")],
[sg.Button("Go hard")]
]
hapticsCol3 = [
[sg.Button("Zero")],
[sg.Button("Print")]
]
poseCol1 = [
[sg.Text("x: "), sg.Text("0", key="-X-"), sg.Text("m")],
[sg.Text("y: "), sg.Text("0", key="-Y-"), sg.Text("m")],
[sg.Text("z: "), sg.Text("0", key="-Z-"), sg.Text("m")]
]
poseCol2 = [
[sg.Text(" Spd: "), sg.Text("0", key="-SPD-"), sg.Text("m/s")],
[sg.Text(" Yaw: "), sg.Text("0", key="-YAW-"), sg.Text("deg")],
[sg.Text(" Tgt: "), sg.Text("0", key="-TGT-"), sg.Text("m")]
]
poseCol3 = [
[sg.Text(" Depth: "), sg.Text("0", key="-DEPTH-"), sg.Text("m")],
[sg.Text(" Time: "), sg.Text("0", key="-TIME-"), sg.Text("s")]
]
illuminatorCol1 = [
[sg.Button("Ready to start", )],
[sg.Button("Ready to end")]
]
illuminatorCol2 = [
[sg.Button("Move area")],
[sg.Button("EMERGENCY", button_color="RED")]
]
#Layout ROV command elements
lightSignalsColumn = [
[sg.Text("STATUS", size=(40,1))],
[sg.Column(statusCol1), sg.Column(statusCol2)],
[sg.HorizontalSeparator()],
[sg.Text("POSE", size=(40,1))],
[sg.Column(poseCol1), sg.Column(poseCol2), sg.Column(poseCol3)],
[sg.HorizontalSeparator()],
[sg.Text("ROBOT CONTROLS", size=(40,1))],
[sg.Column(controlCol1), sg.Column(controlCol2), sg.Column(controlCol3), sg.Column(controlCol4)],
[sg.HorizontalSeparator()],
[sg.Text("ILLUMINATOR SIGNALS", size=(40,1))],
[sg.Column(illuminatorCol1), sg.Column(illuminatorCol2)],
[sg.HorizontalSeparator()],
[sg.Text("HAPTICS CONTROLS", size=(40,1))],
[sg.Column(hapticsCol1), sg.Column(hapticsCol2), sg.Column(hapticsCol3)],
[hapticViz('touchpad')],
[sg.HorizontalSeparator()],
[sg.Text("CAMERA CONTROLS", size=(40,1))],
[sg.Button("Raw still"), sg.Button("Circle still"), sg.Button("CV still")]
]
cmdColumn = [
[sg.Frame("Setup", setupRow), sg.Frame("Battery", [[sg.Text("99%", key='-BATT-')]],key='battframe')],
[sg.Graph((1280,720),(0,720), (1280,0), key='tagView')]
]
#User view is just the robot camera
userLayout = [
[sg.Graph((1280,720),(0,720), (1280,0), key='robotView')]
]
#Command and control window layout
commandLayout = [
[sg.Column(cmdColumn, vertical_alignment='t'),
sg.VerticalSeparator(),
sg.Frame("Controls", lightSignalsColumn, vertical_alignment='top')]
]
#Set UI windows
userWindow = sg.Window('ROV Teleoperation - User View', userLayout, no_titlebar=True, background_color='black', element_padding=0, location=(425,100)) #(270,10)
commandWindow = sg.Window('ROV Teleoperation - Command and Control', commandLayout)
userWindow.Finalize()
commandWindow.Finalize()
hapticVizLine(commandWindow, 'touchpad')
vizCircle = hapticVizUpdate(commandWindow, 'touchpad', None, 0, 512)
robotViewElem = userWindow['robotView'] # type: sg.Graph
tagViewElem = commandWindow['tagView'] # type: sg.Graph
SetLED(commandWindow,"-LEAK-","#460065") #use red for on
SetLED(commandWindow,"-ARM-","#460065") #use red for on
SetLED(commandWindow,"-LOG-","#004665") #Use green1 for on
SetLED(commandWindow,"-VIBE-","#004665") #Use green1 for on
SetLED(commandWindow,"-HARD-","#004665") #Use green1 for on
SetLED(commandWindow,"-TOUCH-","#004665") #Use green1 for on
#Some variables that will be filled later
rawVideoLog = None
markupVideoLog = None
robot_img = None
tag_img = None
#Parameters for ArUco localisation
aruco_dict_type = ARUCO_DICT['DICT_4X4_100']
k = np.load("calibration_matrix.npy")
d = np.load("distortion_coefficients.npy")
#Logging flags default to false
saveVideo = False
saveData = False
posZero = 1000
fingerPos = 1000
adjustedFingerPos = fingerPos
fingerForce = 512
adjustedFingerForce = fingerForce
networkRead = threading.Thread(target=hapticsThread, args=(haptics,))
networkRead.daemon = True
networkRead.start()
averages = 15
avgx = 0
avgy = 0
avgz = 0
avgroll = 0
avgpitch = 0
avgyaw = 0
speed = 0
turn = 0
expTime = 0
depth = 0
gndspd = 0
startTime = 0
startTimePC = 0
startYaw = 0
runFail = False
failReason = 'Unspecified'
startFrame = True
# ---===--- MAIN LOOP Read, process and display frames, operate the GUI, send haptics data --- #
while True:
#print(time.perf_counter())
if video.frame_available():
# Only retrieve and display a frame if it's new
frame = video.frame()
circleFrame = frame.copy()
cv2.circle(circleFrame,(640,360),80,(0,0,255),5)
tagFrame = frame.copy()
if saveVideo:
rawVideoLog.write(frame)
#pass
startFrame = False
elif startFrame:
frame = cv2.imread("tagSamples/ROVCam_8.jpg")
circleFrame = tagFrame.copy()
cv2.circle(circleFrame,(640,360),80,(0,0,255),5)
tagFrame = frame.copy()
tagFrame,tvec,rvec = pose_esitmation(tagFrame, aruco_dict_type, k, d, tagSize)
cv2.circle(tagFrame,(640,360),100,(0,0,255),10)
robotViewBytes=cv2.imencode('.ppm', circleFrame)[1].tobytes() # on some ports, will need to change to png
if robot_img:
robotViewElem.delete_figure(robot_img) # delete previous image
robot_img = robotViewElem.draw_image(data=robotViewBytes, location=(0,0)) # draw new image
newmsg = master.recv_match(type=('SCALED_IMU2'), blocking=False)
#newmsg = master.messages['SCALED_IMU2']
if newmsg is not None:
msg = newmsg.to_dict()
newcompassmsg = master.messages['VFR_HUD']
if newcompassmsg is not None:
compassmsg = newcompassmsg.to_dict()
newstatusmsg = master.messages['SYS_STATUS']
if newstatusmsg is not None:
statusmsg = newstatusmsg.to_dict()
batteryLife = statusmsg['battery_remaining']
if batteryLife < 20:
commandWindow['-BATT-'].ParentRowFrame.config(background='red')
avgx -= avgx/averages
avgx += tvec[0]/averages
avgy -= avgy/averages
avgy += tvec[1]/averages
avgz -= avgz/averages
avgz += tvec[2]/averages
avgroll -= avgroll/averages
avgroll += msg["ygyro"]/averages
avgpitch -= avgpitch/averages
avgpitch += msg["xgyro"]/averages
'''
avgyaw -= avgyaw/averages
avgyaw += msg["zgyro"]/averages
'''
avgyaw = compassmsg['heading']
gndspd = compassmsg['groundspeed']
depth = compassmsg['alt']
#print(tvec)
targetDist = sqrt((pow(avgx,2) + pow((avgz-2),2)))
if conditionString == 'Haptics' and saveData:
if (avgz < 4.1) and (avgz > 3.7):
#hapticsOut[0] = 1
SetLED(commandWindow,"-VIBE-","green1")
else:
#hapticsOut[0] = 0
SetLED(commandWindow,"-VIBE-","#004665")
if targetDist < 0.5:
#hapticsOut[1] = 500 * (targetDist-0.5)/(-0.5)
SetLED(commandWindow,"-HARD-","green1")
else:
#hapticsOut[1] = 0
SetLED(commandWindow,"-HARD-","#004665")
if saveVideo:
markupVideoLog.write(tagFrame)
#print(time.perf_counter())
tagViewBytes=cv2.imencode('.ppm', tagFrame)[1].tobytes() # on some ports, will need to change to png
if tag_img:
tagViewElem.delete_figure(tag_img) # delete previous image
tag_img = tagViewElem.draw_image(data=tagViewBytes, location=(0,0)) # draw new image
fingerPos = hapticsIn[0]
fingerForce = hapticsIn[1]
vizCircle = hapticVizUpdate(commandWindow, 'touchpad', vizCircle, fingerForce, fingerPos)
if touchControlEnabled:
#Saturate bottom of range
if fingerForce < 40:
adjustedFingerForce = 0
else:
adjustedFingerForce = fingerForce
speed = int(maprange((0,500),(1500,1700),adjustedFingerForce))
set_rc_channel_pwm(5,speed)
#Set some deadzone
deadzone = 50
if (fingerPos < posZero+deadzone and fingerPos > fingerPos-deadzone) or fingerForce<40:
adjustedFingerPos = posZero
else:
adjustedFingerPos = fingerPos
turn = int(maprange((0,posZero*2),(1400,1600),fingerPos)) #Need to tune turn rate
if turn<1100:
turn=1100
print(fingerPos)
set_rc_channel_pwm(4,turn)
#print((fingerPos,turn))
if saveData:
expTime = time.time() - startTime
#Check failure conditions
if (expTime) > 120:
runFail = True
failReason = 'timeout'
print('FAIL - timeout')
log={
'time': time.perf_counter()-startTimePC,
'xacc': msg["xacc"],
'yacc': msg["yacc"],
'zacc': msg["zacc"],
'xgyro': msg["xgyro"],
'ygyro': msg["ygyro"],
'zgyro': msg["zgyro"],
'fingerZero': posZero,
'fingerPos': fingerPos,
'fingerForce': fingerForce,
'adjustedFingerPos': adjustedFingerPos,
'adjustedFingerForce': adjustedFingerForce,
'vibration': hapticsOut[0],
'hardness': hapticsOut[1],
'visualTranslation0': tvec[0],
'visualTranslation1': tvec[1],
'visualTranslation2': tvec[2],
'visualRotation0': rvec[0],
'visualRotation1': rvec[1],
'visualRotation2': rvec[2],
'avgxloc': avgx,
'avgyloc': avgy,
'avgzloc': avgz,
'heading': avgyaw,
'tgtDist': targetDist,
'speedDemand': speed,
'turnDemand': turn,
'groundSpeed': gndspd,
'depth': depth
}
logFile.write(json.dumps(log))
logFile.write('\n')
commandWindow["-X-"].update("{:0.2f}".format(avgx))
commandWindow["-Y-"].update("{:0.2f}".format(avgy))
commandWindow["-Z-"].update("{:0.2f}".format(avgz))
commandWindow["-TGT-"].update("{:0.2f}".format(targetDist))
commandWindow["-YAW-"].update("{:0.2f}".format(avgyaw))
commandWindow["-SPD-"].update("{:0.2f}".format(gndspd))
commandWindow["-DEPTH-"].update("{:0.2f}".format(depth))
commandWindow["-TIME-"].update("{:0.2f}".format(expTime))
commandWindow["-BATT-"].update(f"{batteryLife}%")
#Process events for user window (just handle exiting)
event, values = userWindow.read(timeout=0)
if event in ('Exit', None):
break
#Process events for command window
event, values = commandWindow.read(timeout=0)
if (values["-tag-"] != '') and (values["-tag-"] != '0.') and (float(values["-tag-"]) > 0.0):
tagSize = float(values["-tag-"])
#print(tagSize)
if event in ('Exit', None):
break
if event == 'Start':
print("Saving video/data")
commandWindow['Start'].update(disabled=True)
commandWindow['Pass'].update(disabled=False)
commandWindow['Fail'].update(disabled=False)
#generate log filenames
posZero = fingerPos
print(f"Touchpad zero set to {posZero}")
startTime = time.time()
startYaw = avgyaw
if values["-condH-"]:
conditionString = "Haptics"
elif values["-condC-"]:
conditionString = "NoHaptics"
elif values["-condN-"]:
conditionString = "NoCurrent"
elif values["-condT-"]:
conditionString = "Training"
participant = values["-PID-"]
repeat = int(values["-rep-"])
dataFilename = f"logs/PID_{participant}_CONDITION_{conditionString}_REPEAT_{repeat}_TIME_{time.ctime(startTime)}.txt"
rawVideoFilename = f"logs/PID_{participant}_CONDITION_{conditionString}_REPEAT_{repeat}_TIME_{time.ctime(startTime)}_raw.avi"
markupVideoFilename = f"logs/PID_{participant}_CONDITION_{conditionString}_REPEAT_{repeat}_TIME_{time.ctime(startTime)}_markup.avi"
#print(dataFilename)
#print(videoFilename)
fps=17.4
rawVideoLog = cv2.VideoWriter(rawVideoFilename, cv2.VideoWriter_fourcc(*'MJPG'), fps, (1280,720)) #'test_video.avi'
markupVideoLog = cv2.VideoWriter(markupVideoFilename, cv2.VideoWriter_fourcc(*'MJPG'), fps, (1280,720)) #'test_video.avi'
logFile = open(dataFilename, 'w')
logFile.write(f"{time.perf_counter()}: Trial conducted on: {time.ctime(startTime)}\n")
logFile.write(f"{time.perf_counter()}: Initial heading: {startYaw}\n")
saveVideo = True
saveData = True
SetLED(commandWindow,"-LOG-","green1")
startTimePC = time.perf_counter()
elif event == 'Pass':
logFile.write('PASS\n')
logFile.write(f"{time.perf_counter()}: Trial concluded at: {time.ctime(time.time())}\n")
print("No longer saving video/Data")
commandWindow['Start'].update(disabled=False)
commandWindow['Pass'].update(disabled=True)
commandWindow['Fail'].update(disabled=True)
rawVideoLog.release()
markupVideoLog.release()
logFile.close()
saveVideo = False
saveData = False
SetLED(commandWindow,"-LOG-","#004665")
repeat = repeat + 1
commandWindow["-rep-"].update(f"{repeat}")
commandWindow.refresh()
elif event == 'Fail' or runFail:
runFail = False
logFile.write("FAIL - "+failReason+"\n")
logFile.write(f"{time.perf_counter()}: Trial concluded at: {time.ctime(time.time())}\n")
print("No longer saving video/Data")
commandWindow['Start'].update(disabled=False)
commandWindow['Pass'].update(disabled=True)
commandWindow['Fail'].update(disabled=True)
rawVideoLog.release()
markupVideoLog.release()
logFile.close()
saveVideo = False
saveData = False
SetLED(commandWindow,"-LOG-","#004665")
repeat = repeat + 1
commandWindow["-rep-"].update(f"{repeat}")
commandWindow.refresh()
failReason = 'Unspecified'
elif event == 'Arm':
commandWindow['Confirm'].update(disabled=False)
elif event == 'Confirm':
clearMotion()
# Arm
# master.arducopter_arm() or:
master.mav.command_long_send(
master.target_system,
master.target_component,