This repository has been archived by the owner on Apr 10, 2022. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 10
/
TestSelfie.py
224 lines (188 loc) · 9.16 KB
/
TestSelfie.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
# Unit tests for SelfieShot
import math
import mock
from mock import call
from mock import Mock
from mock import MagicMock
import os
from os import sys, path
from pymavlink import mavutil
import struct
import unittest
from dronekit import LocationGlobalRelative, Vehicle
sys.path.append(os.path.realpath('..'))
import location_helpers
import selfie
from selfie import SelfieShot
from shotManager import ShotManager
from rcManager import rcManager
from shotManagerConstants import *
import shots
import app_packet
# on host systems these files are located here
from sololink import btn_msg
ERROR = 0.1
class Attitude():
yaw = 0.0
class TestSelfieHandleRCsNotStarted(unittest.TestCase):
def setUp(self):
mgr = mock.create_autospec(ShotManager)
mgr.buttonManager = Mock()
mgr.currentShot = shots.APP_SHOT_SELFIE
mgr.rcMgr = Mock(specs = ['remapper'])
v = mock.create_autospec(Vehicle)
v.location.global_relative_frame = LocationGlobalRelative(30.13241, 10.112135, 0.0)
self.controller = SelfieShot(v, mgr)
self.controller.altLimit = 0
def testHandleRCsNotStarted(self):
""" Without points, handleRCs shouldn't do anything """
channels = [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
self.controller.handleRCs(channels)
class TestSelfieHandleRCs(unittest.TestCase):
def setUp(self):
mgr = mock.create_autospec(ShotManager)
mgr.buttonManager = Mock()
mgr.currentShot = shots.APP_SHOT_SELFIE
mgr.rcMgr = Mock(specs = ['remapper'])
mgr.appMgr = Mock()
v = mock.create_autospec(Vehicle)
v.location.global_relative_frame = LocationGlobalRelative(30.13241, 10.112135, 0.0)
self.controller = SelfieShot(v, mgr)
self.controller.altLimit = 0
self.controller.addLocation( LocationGlobalRelative(-14.654861, 108.4645, 32.6545) )
self.controller.addLocation( LocationGlobalRelative(23.654504, 40.4645, 17.6545) )
self.controller.addLocation( LocationGlobalRelative(23.661, 10.4645, 2.6545) )
def testRCsMax(self):
""" Test RCs Max """
channels = [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
self.controller.handleRCs(channels)
def testRCsMin(self):
""" Test RCs Min """
channels = [-1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0]
self.controller.handleRCs(channels)
def testRCsZero(self):
""" Test RCs Max """
channels = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
self.controller.handleRCs(channels)
def testRCs2(self):
""" Test RCs Max """
channels = [0.2, 0.2, 0.2, 0.2, 0.2, 0.2, 0.2, 0.2]
self.controller.handleRCs(channels)
class TestSetButtonMappings(unittest.TestCase):
def setUp(self):
mgr = mock.create_autospec(ShotManager)
mgr.buttonManager = Mock()
mgr.currentShot = shots.APP_SHOT_SELFIE
mgr.buttonManager = Mock()
mgr.rcMgr = Mock(specs = ['remapper'])
v = mock.create_autospec(Vehicle)
v.location.global_relative_frame = LocationGlobalRelative(30.13241, 10.112135, 0.0)
self.controller = SelfieShot(v, mgr)
self.controller.altLimit = 0
def testSetButtonMappingsNoROI(self):
""" Testing setting button mappings when we haven't locked on yet """
self.controller.setButtonMappings()
calls = [call(btn_msg.ButtonA, shots.APP_SHOT_SELFIE, 0, "\0"), call(btn_msg.ButtonB, shots.APP_SHOT_SELFIE, 0, "\0")]
self.controller.shotmgr.buttonManager.setArtooButton.assert_has_calls(calls, any_order = False)
def testSetButtonMappings(self):
""" Testing setting button mappings when we have started """
self.controller.addLocation( LocationGlobalRelative(-14.654861, 108.4645, 32.6545) )
self.controller.addLocation( LocationGlobalRelative(23.654504, 40.4645, 17.6545) )
self.controller.addLocation( LocationGlobalRelative(23.661, 10.4645, 2.6545) )
self.controller.setButtonMappings()
calls = [call(btn_msg.ButtonA, shots.APP_SHOT_SELFIE, 0, "\0"), call(btn_msg.ButtonB, shots.APP_SHOT_SELFIE, 0, "\0")]
self.controller.shotmgr.buttonManager.setArtooButton.assert_has_calls(calls)
class TestHandlePacket(unittest.TestCase):
def setUp(self):
mgr = mock.create_autospec(ShotManager)
mgr.buttonManager = Mock()
mgr.currentShot = shots.APP_SHOT_SELFIE
mgr.rcMgr = Mock(specs = ['remapper'])
v = mock.create_autospec(Vehicle)
v.location.global_relative_frame = LocationGlobalRelative(30.13241, 10.112135, 0.0)
self.controller = SelfieShot(v, mgr)
self.controller.pathHandler = Mock(specs=['isPaused'])
self.controller.altLimit = 0
def testCruiseSpeedSet0(self):
options = struct.pack('<f', 0.0)
self.controller.handlePacket(app_packet.SOLO_SHOT_OPTIONS, 4, options)
self.controller.pathHandler.setCruiseSpeed.assert_called_with(0.0)
def testCruiseSpeedSet6(self):
options = struct.pack('<f', 6.0)
self.controller.handlePacket(app_packet.SOLO_SHOT_OPTIONS, 4, options)
self.controller.pathHandler.setCruiseSpeed.assert_called_with(6.0)
def testCruiseSpeedSet3(self):
options = struct.pack('<f', 3.0)
self.controller.handlePacket(app_packet.SOLO_SHOT_OPTIONS, 4, options)
self.controller.pathHandler.setCruiseSpeed.assert_called_with(3.0)
def testNoPathHandler(self):
""" Shouldn't crash if we don't have a path handler """
options = struct.pack('<f', 1.0)
self.controller.pathHandler = None
self.controller.handlePacket(app_packet.SOLO_SHOT_OPTIONS, 4, options)
class TestHandleButton(unittest.TestCase):
def setUp(self):
mgr = mock.create_autospec(ShotManager)
mgr.buttonManager = Mock()
mgr.currentShot = shots.APP_SHOT_SELFIE
mgr.rcMgr = Mock(specs = ['remapper'])
v = mock.create_autospec(Vehicle)
v.location.global_relative_frame = LocationGlobalRelative(30.13241, 10.112135, 0.0)
self.controller = SelfieShot(v, mgr)
self.controller.pathHandler = Mock(specs=['isPaused','togglePause'])
self.controller.updateAppOptions = Mock()
self.controller.altLimit = 0
def TestPauseCruise(self):
""" pause button pauses cruising """
self.controller.pathHandler.isPaused = Mock(return_value=False)
self.controller.handleButton( btn_msg.ButtonLoiter, btn_msg.Press )
self.controller.pathHandler.togglePause.assert_called_with()
self.controller.updateAppOptions.assert_called_with()
def TestResumeCruise(self):
""" pause button resumes cruising (if already paused) """
self.controller.pathHandler.isPaused = Mock(return_value=True)
self.controller.handleButton( btn_msg.ButtonLoiter, btn_msg.Press )
self.controller.pathHandler.togglePause.assert_called_with()
self.controller.updateAppOptions.assert_called_with()
def TestNotifyPauseLoiter(self):
self.controller.pathHandler = None
self.controller.handleButton(btn_msg.ButtonLoiter, btn_msg.Press)
self.controller.shotmgr.notifyPause.assert_called_with(False)
def TestNotifyPauseGuided(self):
self.controller.handleButton(btn_msg.ButtonLoiter, btn_msg.Press)
self.controller.shotmgr.notifyPause.assert_called_with(True)
class TestAddLocation(unittest.TestCase):
def setUp(self):
mgr = mock.create_autospec(ShotManager)
mgr.buttonManager = Mock()
mgr.currentShot = shots.APP_SHOT_SELFIE
mgr.rcMgr = Mock(specs = ['remapper'])
v = mock.create_autospec(Vehicle)
v.location.global_relative_frame = LocationGlobalRelative(30.13241, 10.112135, 0.0)
self.controller = SelfieShot(v, mgr)
self.controller.altLimit = 0
def testAltitudeLimit(self):
'''Makes sure 2nd selfie point is capped at the user-defined altitude limit'''
self.controller.altLimit = 25 # meters
self.controller.addLocation( LocationGlobalRelative(23.654504, 40.4645, 17.6545) )
self.controller.addLocation( LocationGlobalRelative(-14.654861, 108.4645, 32.6545) )
self.assertAlmostEqual(self.controller.altLimit,self.controller.waypoints[1].alt,1)
def testAltitudeLimitDisabled(self):
'''Makes sure 2nd selfie point is NOT capped if altitude limit is disabled'''
self.controller.altLimit = None
x2 = -14.654861
y2 = 108.4645
z2 = 32.6545
self.controller.addLocation( LocationGlobalRelative(23.654504, 40.4645, 17.6545) )
self.controller.addLocation( LocationGlobalRelative(x2, y2, z2) )
self.assertAlmostEqual(x2, self.controller.waypoints[1].lat,1)
self.assertAlmostEqual(y2, self.controller.waypoints[1].lon,1)
self.assertAlmostEqual(z2, self.controller.waypoints[1].alt,1)
def testAddLocations(self):
""" Test adding locations """
loc = LocationGlobalRelative(37.242124, -122.12841, 15.3)
self.controller.addLocation(loc)
loc = LocationGlobalRelative(30.13241, 10.112135, 0.0)
self.controller.addLocation(loc)
loc = LocationGlobalRelative(-14.654861, 108.4645, 32.6545)
self.controller.addLocation(loc)