RTH: Discontinue ReturnHome smart shot

The ReturnHome smart shot presents a number of reliability and safety
issues. As such, its use is being discontinued and we're using
ArduCopter RTL mode instead.  If anything still happens to call the
return home smart shot, it will immediately change to the ArduCopter RTL
mode.
This commit is contained in:
Matt 2017-12-16 11:21:11 -05:00
parent 276efaa94a
commit 879f8352a3

View File

@ -76,6 +76,13 @@ class returnHomeShot():
# 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
##########################################################
# grab a copy of home
self.homeLocation = self.shotmgr.getHomeLocation()
@ -253,7 +260,7 @@ class returnHomeShot():
def handleButton(self, button, event):
# any Pause button press or release should get out of RTL
if button == btn_msg.ButtonLoiter and event == btn_msg.Press:
if button == btn_msg.ButtonLoiter and event == btn_msg.ClickRelease:
#exit to fly
self.shotmgr.enterShot(shots.APP_SHOT_NONE)