forked from OpenSolo/shotmanager
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathselfie.py
More file actions
291 lines (229 loc) · 10.2 KB
/
selfie.py
File metadata and controls
291 lines (229 loc) · 10.2 KB
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
# selfie.py
# shotmanager
#
# The selfie smart shot.
# Press Fly Out in the app and the drone flies up and out, keeping the camera pointed at the ROI
# Runs as a DroneKit-Python script.
#
# Created by Will Silva and Eric Liao in 2015
# Copyright (c) 2016 3D Robotics.
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
from dronekit import VehicleMode, LocationGlobalRelative
from pymavlink import mavutil
import os
from os import sys, path
import struct
import math
sys.path.append(os.path.realpath(''))
import app_packet
import location_helpers
import pathHandler
import shotLogger
import shots
from shotManagerConstants import *
# on host systems these files are located here
sys.path.append(os.path.realpath('../../flightcode/stm32'))
from sololink import btn_msg
YAW_SPEED = 60.0
PITCH_SPEED = 60.0
logger = shotLogger.logger
class SelfieShot():
def __init__(self, vehicle, shotmgr):
self.vehicle = vehicle
self.shotmgr = shotmgr
self.waypoints = []
self.roi = None
self.pathHandler = None
# Camera control
self.camPitch = 0
self.camYaw = 0
self.camDir = 1
self.canResetCam = False
self.setButtonMappings()
# get current altitude limit
self.altLimit = self.shotmgr.getParam( "FENCE_ALT_MAX", DEFAULT_FENCE_ALT_MAX ) # in meters
# check APM params to see if Altitude Limit should apply
if self.shotmgr.getParam( "FENCE_ENABLE", DEFAULT_FENCE_ENABLE ) == 0:
self.altLimit = None
logger.log("[Selfie]: Altitude Limit is disabled.")
# channels are expected to be floating point values in the (-1.0, 1.0) range
def handleRCs( self, channels ):
#selfie needs 2 waypoints and an ROI to be ready
if len(self.waypoints) != 2 or not self.roi:
return
self.pathHandler.MoveTowardsEndpt(channels)
self.manualPitch(channels)
self.manualYaw(channels)
self.handleFreeLookPointing()
if self.pathHandler.isNearTarget():
# if we reached the end, flip
if self.pathHandler.cruiseSpeed > 0.0:
self.pathHandler.cruiseSpeed = -self.pathHandler.cruiseSpeed
logger.log("[Selfie]: reached end of selfie path, flipping")
elif self.pathHandler.cruiseSpeed < 0.0:
logger.log("[Selfie]: reached end of selfie path, pausing")
self.pathHandler.pause()
self.updateAppOptions()
def setButtonMappings(self):
buttonMgr = self.shotmgr.buttonManager
if self.canResetCam:
buttonMgr.setArtooButton(btn_msg.ButtonA, shots.APP_SHOT_SELFIE, btn_msg.ARTOO_BITMASK_ENABLED, "Look At Me\0")
else:
buttonMgr.setArtooButton(btn_msg.ButtonA, shots.APP_SHOT_SELFIE, 0, "\0")
buttonMgr.setArtooButton(btn_msg.ButtonB, shots.APP_SHOT_SELFIE, 0, "\0")
# if we can handle the button we do
def handleButton(self, button, event):
if button == btn_msg.ButtonA and event == btn_msg.ClickRelease:
self.pointAtROI()
if button == btn_msg.ButtonLoiter and event == btn_msg.ClickRelease:
if self.pathHandler:
self.shotmgr.notifyPause(True)
self.pathHandler.togglePause()
self.updateAppOptions()
else:
# notify autopilot of pause press (technically not in shot)
self.shotmgr.notifyPause(False)
# send our current set of options to the app
def updateAppOptions(self):
speed = 0.0
if self.pathHandler:
speed = self.pathHandler.cruiseSpeed
packet = struct.pack('<IIf', app_packet.SOLO_SHOT_OPTIONS, 4, speed)
self.shotmgr.appMgr.sendPacket(packet)
def handlePacket(self, packetType, packetLength, packetValue):
try:
if packetType == app_packet.SOLO_MESSAGE_LOCATION:
(lat, lon, alt) = struct.unpack('<ddf', packetValue)
logger.log("[selfie]: Location received from app: %f, %f, %f." %( lat, lon, alt ) )
self.addLocation(LocationGlobalRelative(lat, lon, alt))
elif packetType == app_packet.SOLO_SHOT_OPTIONS:
(cruiseSpeed,) = struct.unpack('<f', packetValue)
if self.pathHandler:
self.pathHandler.setCruiseSpeed(cruiseSpeed)
logger.log("[selfie]: Cruise speed set to %.2f." % (cruiseSpeed,))
else:
return False
except Exception as e:
logger.log('[selfie]: Error handling packet. (%s)' % e)
return False
else:
return True
def addLocation(self, loc):
# we're ready once we have 2 waypoints and an ROI
if len(self.waypoints) < 2:
# check altitude limit on 2nd point
if self.altLimit is not None and len(self.waypoints) > 0:
if loc.alt > self.altLimit:
logger.log("[Selfie]: 2nd selfie point breaches user-set altitude limit (%.1f meters)." % (self.altLimit))
# find vector to 2nd point
selfieVector = location_helpers.getVectorFromPoints(self.waypoints[0],loc)
# normalize it
selfieVector.normalize()
# calculate distance between two points
d = location_helpers.getDistanceFromPoints3d(self.waypoints[0],loc)
# calculate hypotenuse
hyp = (self.altLimit-self.waypoints[0].alt)/((loc.alt-self.waypoints[0].alt)/d)
# scale selfie vector by hypotenuse
selfieVector *= hyp
# add selfieVector to original selfie point to create a new 2nd point
loc = location_helpers.addVectorToLocation(self.waypoints[0],selfieVector)
self.waypoints.append(loc)
logger.log("[Selfie]: Added a selfie point: %f, %f, %f." % ( loc.lat, loc.lon,loc.alt))
elif not self.roi:
self.roi = loc
logger.log("[Selfie]: Added a selfie ROI: %f, %f, %f." %
( loc.lat, loc.lon,
loc.alt))
self.pathHandler = pathHandler.TwoPointPathHandler( self.waypoints[0], self.waypoints[1], self.vehicle, self.shotmgr )
# ready! set up everything
self.shotmgr.rcMgr.enableRemapping( True )
# Now change the vehicle into guided mode
self.vehicle.mode = VehicleMode("GUIDED")
self.manualGimbalTargeting()
self.setButtonMappings()
def manualGimbalTargeting(self):
'''set gimbal targeting mode to manual'''
msg = self.vehicle.message_factory.mount_configure_encode(
0, 1, # target system, target component
mavutil.mavlink.MAV_MOUNT_MODE_MAVLINK_TARGETING, # mount_mode
1, # stabilize roll
1, # stabilize pitch
1, # stabilize yaw
)
self.vehicle.send_mavlink(msg)
self.pointAtROI()
def pointAtROI(self):
logger.log("[Selfie]: Point at ROI")
# calcs the yaw and pitch to point the gimbal
self.camYaw, self.camPitch = location_helpers.calcYawPitchFromLocations(self.vehicle.location.global_relative_frame, self.roi)
if self.canResetCam:
self.canResetCam = False
self.setButtonMappings()
def updateCanResetCam(self, resetCam):
# only send button label updates on change
if resetCam != self.canResetCam:
logger.log("[Selfie]: can reset to ROI")
self.canResetCam = resetCam
self.setButtonMappings()
def manualPitch(self, channels):
if abs(channels[RAW_PADDLE]) > abs(channels[THROTTLE]):
value = channels[RAW_PADDLE]
else:
value = channels[THROTTLE]
if value == 0:
return
self.updateCanResetCam(True)
self.camPitch += value * PITCH_SPEED * UPDATE_TIME
if self.camPitch > 0.0:
self.camPitch = 0.0
elif self.camPitch < -90:
self.camPitch = -90
def manualYaw(self, channels):
if channels[YAW] == 0:
return
self.updateCanResetCam(True)
self.camYaw += channels[YAW] * YAW_SPEED * UPDATE_TIME
if self.camYaw > 360:
self.camYaw -= 360
if self.camYaw < 0:
self.camYaw += 360
# required for gimbals w/o Yaw
if channels[YAW] > 0:
self.camDir = 1
else:
self.camDir = -1
def handleFreeLookPointing(self):
'''Handle free look'''
# if we do have a gimbal, use mount_control to set pitch and yaw
if self.vehicle.mount_status[0] is not None:
msg = self.vehicle.message_factory.mount_control_encode(
0, 1, # Target system, target component
self.camPitch * 100, # Pitch in centidegrees
0.0, # Roll not used
self.camYaw * 100, # Yaw in centidegrees
0 # save position
)
self.vehicle.send_mavlink(msg)
else:
# if we don't have a gimbal, just set CONDITION_YAW
msg = self.vehicle.message_factory.command_long_encode(
0, 1, # target system, target component
mavutil.mavlink.MAV_CMD_CONDITION_YAW, #command
0, # confirmation
self.camYaw, # param 1 - target angle
YAW_SPEED, # param 2 - yaw speed
self.camDir, # param 3 - direction
0.0, # relative offset
0, 0, 0 # params 5-7 (unused)
)
self.vehicle.send_mavlink(msg)