mirror of
https://github.com/OpenSolo/OpenSolo.git
synced 2025-04-29 14:14:30 +02:00
REWIND: Discontinue rewind smart shot
The rewind smart shot has a number of reliability and safety issues. As such, it is being discontinued in Open Solo. If anything still happens to call the rewind smart shot, it will immediately exit to ArduCopter RTL mode.
This commit is contained in:
parent
879f8352a3
commit
244546d390
@ -19,6 +19,7 @@
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
|
||||
from dronekit import Vehicle, LocationGlobalRelative, VehicleMode
|
||||
from pymavlink import mavutil
|
||||
import os
|
||||
@ -74,6 +75,13 @@ class RewindShot():
|
||||
# assign the shotManager object
|
||||
self.shotmgr = shotmgr
|
||||
|
||||
# Exit the shot and use RTL Mode
|
||||
self.vehicle.mode = VehicleMode("RTL")
|
||||
self.shotmgr.rcMgr.enableRemapping( false )
|
||||
return
|
||||
|
||||
############################################################
|
||||
|
||||
# data manager for breadcrumbs
|
||||
self.rewindManager = shotmgr.rewindManager
|
||||
|
||||
@ -149,7 +157,7 @@ class RewindShot():
|
||||
|
||||
def exitRewind(self):
|
||||
self.rewindManager.resetSpline()
|
||||
self.shotmgr.enterShot(shots.APP_SHOT_RTL)
|
||||
self.vehicle.mode = VehicleMode("RTL")
|
||||
|
||||
|
||||
def travel(self):
|
||||
@ -196,7 +204,7 @@ class RewindShot():
|
||||
|
||||
def handleButton(self, button, event):
|
||||
# any Pause button press or release should get out of Rewind
|
||||
if button == btn_msg.ButtonLoiter and (event == btn_msg.Release or event == btn_msg.Press):
|
||||
if button == btn_msg.ButtonLoiter and (event == btn_msg.Release or event == btn_msg.ClickRelease):
|
||||
#exit to fly
|
||||
self.shotmgr.enterShot(shots.APP_SHOT_NONE)
|
||||
return
|
||||
|
Loading…
x
Reference in New Issue
Block a user