diff --git a/Scripts/PARACHUTE LANDING APPROACH.py b/Scripts/PARACHUTE LANDING APPROACH.py index ea4f7d55b9..810d89938d 100644 --- a/Scripts/PARACHUTE LANDING APPROACH.py +++ b/Scripts/PARACHUTE LANDING APPROACH.py @@ -1,4 +1,5 @@ -approach_azimuth = 180 +from __future__ import print_function +approach_azimuth = 180 parachute_deploy_altitude = 40 @@ -40,34 +41,34 @@ hdop = cs.gpshdop if satellites < 6: - print'GPS FAILED. NO MISSION CREATED. WAIT FOR BETTER GPS' - print '' + print('GPS FAILED. NO MISSION CREATED. WAIT FOR BETTER GPS') + print('') elif hdop > 4: - print'GPS FAILED. NO MISSION CREATED. WAIT FOR BETTER GPS.' - print '' + print('GPS FAILED. NO MISSION CREATED. WAIT FOR BETTER GPS.') + print('') else: - print'GPS PASSED.' - print '' + print('GPS PASSED.') + print('') if descent_delta < 0: - print 'CURRENT ALTITUDE BELOW PARACHUTE DEPLOY ALTITUDE' - print 'NO MISSION CREATED' + print('CURRENT ALTITUDE BELOW PARACHUTE DEPLOY ALTITUDE') + print('NO MISSION CREATED') elif parachute_deploy_altitude < 20: - print 'PARACHUTE DEPLOY ALTITUDE LESS THAN 20 METERS' - print 'NO MISSION CREATED' + print('PARACHUTE DEPLOY ALTITUDE LESS THAN 20 METERS') + print('NO MISSION CREATED') elif parachute_deploy_altitude > 100: - print 'PARACHUTE DEPLOY ALTITUDE MORE THAN 100 METERS' - print 'NO MISSION CREATED' + print('PARACHUTE DEPLOY ALTITUDE MORE THAN 100 METERS') + print('NO MISSION CREATED') elif parachute_deploy_distance_from_home > 100: - print 'PARACHUTE DEPLOY DISTANCE IS MORE THAN 100 FROM HOME' - print 'NO MISSION CREATED' + print('PARACHUTE DEPLOY DISTANCE IS MORE THAN 100 FROM HOME') + print('NO MISSION CREATED') else: @@ -113,7 +114,6 @@ Script.Sleep(1000) MAV.setWPACK(); #final ack Script.Sleep(1000) - print 'AUTOGENERATED LANDING APPROACH MISSION' + print('AUTOGENERATED LANDING APPROACH MISSION') - diff --git a/Scripts/TAKEOFF.py b/Scripts/TAKEOFF.py index 1cd231e60f..8411cbaa3b 100644 --- a/Scripts/TAKEOFF.py +++ b/Scripts/TAKEOFF.py @@ -1,4 +1,5 @@ -launch_altitude = 100 +from __future__ import print_function +launch_altitude = 100 cruise_altitude = 200 @@ -40,29 +41,29 @@ hdop = cs.gpshdop if satellites < 6: - print'GPS FAILED. NO MISSION CREATED. WAIT FOR BETTER GPS' - print '' + print('GPS FAILED. NO MISSION CREATED. WAIT FOR BETTER GPS') + print('') elif hdop > 4: - print'GPS FAILED. NO MISSION CREATED. WAIT FOR BETTER GPS.' - print '' + print('GPS FAILED. NO MISSION CREATED. WAIT FOR BETTER GPS.') + print('') else: - print'GPS PASSED.' - print '' + print('GPS PASSED.') + print('') if launch_altitude < 50: - print 'LAUNCH ALTITUDE LESS THAN 50 METERS' - print 'NO MISSION CREATED' + print('LAUNCH ALTITUDE LESS THAN 50 METERS') + print('NO MISSION CREATED') elif launch_altitude >100: - print 'LAUNCH ALTITUDE GREATER THAN 100 METERS' - print 'NO MISSION CREATED' + print('LAUNCH ALTITUDE GREATER THAN 100 METERS') + print('NO MISSION CREATED') elif cruise_altitude < launch_altitude: - print 'CRUISE ALTITUDE LESS THAN LAUNCH ALTITUDE' - print 'NO MISSION CREATED' + print('CRUISE ALTITUDE LESS THAN LAUNCH ALTITUDE') + print('NO MISSION CREATED') else: @@ -119,4 +120,4 @@ MAV.setWP(wp4,5,MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT); #upload wp4 MAV.setWPCurrent(1); #restart mission to waypoint 0 MAV.setWPACK(); #final ack - print 'AUTOGENERATED TAKEOFF MISSION' \ No newline at end of file + print('AUTOGENERATED TAKEOFF MISSION') diff --git a/Scripts/cubeorange.py b/Scripts/cubeorange.py index eb5f8e4bed..9fa1b7529d 100644 --- a/Scripts/cubeorange.py +++ b/Scripts/cubeorange.py @@ -1,4 +1,5 @@ - +from __future__ import print_function + import clr import MissionPlanner clr.AddReference("MAVLink") @@ -9,7 +10,7 @@ import MAVLink -print 'Start Script' +print('Start Script') MAV.setParam("INS_ACC_ID", 0, True); MAV.setParam("INS_ACC2_ID", 0, True); @@ -19,4 +20,4 @@ MAV.setParam("INS_ACC2_ID", 2883874, True); MAV.setParam("INS_ACC3_ID", 3015690, True); -print 'Done' +print('Done') diff --git a/Scripts/datetime.py b/Scripts/datetime.py index fa78cf7da9..deb417ede4 100644 --- a/Scripts/datetime.py +++ b/Scripts/datetime.py @@ -1,3 +1,4 @@ +from __future__ import print_function c# import System c# @@ -5,6 +6,6 @@ st = dt.ToString("yyyy-MM-ddTHH:mm:ss.fff") + ' setting wp 1' # python -print st +print(st) # c# System.Console.WriteLine(st) diff --git a/Scripts/example1.py b/Scripts/example1.py index 10b84c2e5a..e92438dbf9 100644 --- a/Scripts/example1.py +++ b/Scripts/example1.py @@ -1,4 +1,5 @@ -# cs.???? = currentstate, any variable on the status tab in the planner can be used. +from __future__ import print_function +# cs.???? = currentstate, any variable on the status tab in the planner can be used. # Script = options are # Script.Sleep(ms) # Script.ChangeParam(name,value) @@ -8,24 +9,24 @@ # Script.SendRC(channel,pwm,sendnow) # -print 'Start Script' +print('Start Script') for chan in range(1,9): Script.SendRC(chan,1500,False) Script.SendRC(3,Script.GetParam('RC3_MIN'),True) Script.Sleep(5000) while cs.lat == 0: - print 'Waiting for GPS' + print('Waiting for GPS') Script.Sleep(1000) -print 'Got GPS' +print('Got GPS') jo = 10 * 13 -print jo +print(jo) Script.SendRC(3,1000,False) Script.SendRC(4,2000,True) cs.messages.Clear() Script.WaitFor('ARMING MOTORS',30000) Script.SendRC(4,1500,True) -print 'Motors Armed!' +print('Motors Armed!') Script.SendRC(3,1700,True) while cs.alt < 50: @@ -55,4 +56,4 @@ Script.WaitFor('DISARMING MOTORS',30000) Script.SendRC(4,1500,True) -print 'Roll complete' \ No newline at end of file +print('Roll complete') diff --git a/Scripts/example10.py b/Scripts/example10.py index e31278d6b6..6c7a7da1fb 100644 --- a/Scripts/example10.py +++ b/Scripts/example10.py @@ -1,11 +1,12 @@ -import clr +from __future__ import print_function +import clr import MissionPlanner clr.AddReference("MAVLink") from System import Func, Action import MAVLink def OtherMethod(message): - print "got HB"; + print("got HB"); return True def MyMethod(message): @@ -16,11 +17,11 @@ def MyMethod(message): def MyPacketHandler(o, message): try: if message.msgid == MAVLink.MAVLINK_MSG_ID.STATUSTEXT.value__: - print "STATUSTEXT from MyPacketHandler " + str(message.sysid) + " " + str(message.compid) - print dir(message) + print("STATUSTEXT from MyPacketHandler " + str(message.sysid) + " " + str(message.compid)) + print(dir(message)) print(bytes(message.data.text)) except Exception as inst: - print inst + print(inst) sub = MAV.SubscribeToPacketType(MAVLink.MAVLINK_MSG_ID.HEARTBEAT.value__, Func[MAVLink.MAVLinkMessage, bool] (OtherMethod)) sub2 = MAV.SubscribeToPacketType(MAVLink.MAVLINK_MSG_ID.STATUSTEXT, Func[MAVLink.MAVLinkMessage, @@ -32,4 +33,4 @@ def MyPacketHandler(o, message): import time while True: - time.sleep(1) \ No newline at end of file + time.sleep(1) diff --git a/Scripts/example2.py b/Scripts/example2.py index 79ba2b1ef4..708d226e47 100644 --- a/Scripts/example2.py +++ b/Scripts/example2.py @@ -1,4 +1,5 @@ - +from __future__ import print_function + import clr import MissionPlanner clr.AddReference("MAVLink") @@ -9,11 +10,11 @@ import MAVLink -print 'Start Script' +print('Start Script') def OtherMethod(message): - print "got HB"; - print dir(message.data) + print("got HB"); + print(dir(message.data)) return True sub = MAV.SubscribeToPacketType(MAVLink.MAVLINK_MSG_ID.HEARTBEAT.value__, Func[MAVLink.MAVLinkMessage, bool] (OtherMethod)) diff --git a/Scripts/example3.py b/Scripts/example3.py index c881d53bf0..8a27636ee9 100644 --- a/Scripts/example3.py +++ b/Scripts/example3.py @@ -1,4 +1,5 @@ -import sys +from __future__ import print_function +import sys import math import clr import time @@ -25,10 +26,10 @@ def gps_distance(lat1, lon1, lat2, lon2): c = 2.0 * atan2(sqrt(a), sqrt(1.0-a)) return radius_of_earth * c -print __name__ +print(__name__) # main program -print "Start script" +print("Start script") ######Mission variables###### dist_tolerance = 15 #(m) ber_tolerance = 45 #heading tolerance @@ -43,7 +44,7 @@ def gps_distance(lat1, lon1, lat2, lon2): target = (-35, 117.98) # gps pos of target in degrees time.sleep(5) # wait 10 seconds before starting -print 'Starting Mission' +print('Starting Mission') Script.ChangeMode("Guided") # changes mode to "Guided" item = MissionPlanner.Utilities.Locationwp() # creating waypoint @@ -51,15 +52,15 @@ def gps_distance(lat1, lon1, lat2, lon2): Locationwp.lat.SetValue(item,target[0]) # sets latitude Locationwp.lng.SetValue(item,target[1]) # sets longitude Locationwp.alt.SetValue(item,alt) # sets altitude -print 'Drop zone set' +print('Drop zone set') MAV.setGuidedModeWP(item) # tells UAV "go to" the set lat/long @ alt -print 'Going to DZ' +print('Going to DZ') Good = True while Good == True: ground_speed = cs.groundspeed alt = cs.alt wp_dist = gps_distance(cs.lat ,cs.lng, math.radians(target[0]), math.radians(target[1])) - print wp_dist + print(wp_dist) ber_error = cs.ber_error fall_time = ((2 * alt) / gravity) ** (0.5) fall_dist = ground_speed * fall_time @@ -69,12 +70,12 @@ def gps_distance(lat1, lon1, lat2, lon2): if (math.fabs(ber_error) <= ber_tolerance): ######Payload Release###### Script.SendRC(payload_servo,1900,True) - print 'Bombs away!' + print('Bombs away!') else: - print 'Heading outside of threshold, go around!' + print('Heading outside of threshold, go around!') Good = False else: - print 'Outside of threshold!' + print('Outside of threshold!') time.sleep (1.0) #sleep for a second #Broken out of the loop as Bearing was not right - print 'Bearing was out of tolerance for the Drop - Start run again' + print('Bearing was out of tolerance for the Drop - Start run again') diff --git a/Scripts/example4 wp.py b/Scripts/example4 wp.py index 99f797c155..176ab006dc 100644 --- a/Scripts/example4 wp.py +++ b/Scripts/example4 wp.py @@ -1,4 +1,5 @@ -import sys +from __future__ import print_function +import sys import math import clr import time @@ -24,22 +25,19 @@ wp2 = Locationwp().Set(-35,117.89,50, id) wp3 = Locationwp().Set(-35,117.85,20, id) -print "set wp total" +print("set wp total") MAV.setWPTotal(5) -print "upload home - reset on arm" +print("upload home - reset on arm") MAV.setWP(home,0,MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT); -print "upload to" +print("upload to") MAV.setWP(to,1,MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT); -print "upload wp1" +print("upload wp1") MAV.setWP(wp1,2,MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT); -print "upload wp2" +print("upload wp2") MAV.setWP(wp2,3,MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT); -print "upload wp3" +print("upload wp3") MAV.setWP(wp3,4,MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT); -print "final ack" +print("final ack") MAV.setWPACK(); -print "done" - - - +print("done") diff --git a/Scripts/example5 inject data.py b/Scripts/example5 inject data.py index 3449bd3e84..d11a6fcfa3 100644 --- a/Scripts/example5 inject data.py +++ b/Scripts/example5 inject data.py @@ -1,4 +1,5 @@ - +from __future__ import print_function + import clr import MissionPlanner clr.AddReference("MAVLink") @@ -6,8 +7,8 @@ from System import Array import MAVLink -print 'Start Script' +print('Start Script') key = Array[Byte]([0x13, 0x00, 0x00, 0x00, 0x08, 0x00]) -MAV.BaseStream.Write(key,0,len(key)) \ No newline at end of file +MAV.BaseStream.Write(key,0,len(key)) diff --git a/Scripts/example6.py b/Scripts/example6.py index 252cccbce2..a6387326e8 100644 --- a/Scripts/example6.py +++ b/Scripts/example6.py @@ -1,4 +1,5 @@ -# from http://diydrones.com/forum/topics/mission-planner-python-script?commentId=705844%3AComment%3A2035437&xg_source=msg_com_forum +from __future__ import print_function +# from http://diydrones.com/forum/topics/mission-planner-python-script?commentId=705844%3AComment%3A2035437&xg_source=msg_com_forum import socket import sys @@ -22,22 +23,22 @@ rsock = socket.socket(socket.AF_INET,socket.SOCK_DGRAM) -print 'Sockets created' +print('Sockets created') # Bind socket to local host and port try: rsock.bind((HOST,RPORT)) -except socket.error, msg: +except socket.error as msg: #print 'Bind failed. Error Code:' sys.stderr.write("[ERROR] %s\n" % msg[1]) rsock.close() sys.exit() -print 'Receive Socket bind complete on ' + str(RPORT) +print('Receive Socket bind complete on ' + str(RPORT)) -print 'Starting Follow' +print('Starting Follow') Script.ChangeMode("Guided") # changes mode to "Guided" -print 'Guided Mode' +print('Guided Mode') #keep talking with the Mission Planner server while 1: @@ -101,8 +102,8 @@ #MissionPlanner.Utilities.Locationwp.groundcourse.SetValue(item,float_heading) MissionPlanner.Utilities.Locationwp.alt.SetValue(item,float_alt) #Can only use lat,lng, or alt MAV.setGuidedModeWP(item) #set waypoint - print 'Waypoint Sent' - print time.strftime('%X %x %Z') + print('Waypoint Sent') + print(time.strftime('%X %x %Z')) # exit rsock.close() -print 'Script End' +print('Script End') diff --git a/Scripts/example7.py b/Scripts/example7.py index 2c43396f2e..bebb70f5ee 100644 --- a/Scripts/example7.py +++ b/Scripts/example7.py @@ -1,4 +1,5 @@ -import sys +from __future__ import print_function +import sys import math import clr import time @@ -6,7 +7,6 @@ import MissionPlanner clr.AddReference("MissionPlanner.Utilities") # includes the Utilities class -print 'Start Script' +print('Start Script') MissionPlanner.MainV2.instance.FlightPlanner.BUT_read_Click(MissionPlanner.MainV2.instance.FlightPlanner,null) - diff --git a/Scripts/example8 - speech.py b/Scripts/example8 - speech.py index 2492eb3dcb..00d9839edb 100644 --- a/Scripts/example8 - speech.py +++ b/Scripts/example8 - speech.py @@ -1,4 +1,5 @@ -import sys +from __future__ import print_function +import sys import math import clr import time @@ -6,14 +7,11 @@ import MissionPlanner clr.AddReference("MissionPlanner.Utilities") # includes the Utilities class -print 'Start Script' +print('Start Script') MissionPlanner.MainV2.speechEnable = True while True: - print 'speech ...' + print('speech ...') MissionPlanner.MainV2.speechEngine.SpeakAsync("test " + cs.roll.ToString()) time.sleep(1) - - - diff --git a/Scripts/example9 - sitl.py b/Scripts/example9 - sitl.py index 1317969ad2..10119a49c4 100644 --- a/Scripts/example9 - sitl.py +++ b/Scripts/example9 - sitl.py @@ -14,12 +14,12 @@ from System.Diagnostics import Process for i in range(20): - workdir = 'C:\Users\michael\Documents\Mission Planner\sitl\d' + str(i) + workdir = r'C:\Users\michael\Documents\Mission Planner\sitl\d' + str(i) if not os.path.exists(workdir): os.makedirs(workdir) proc = Process() proc.StartInfo.WorkingDirectory = workdir - proc.StartInfo.FileName ='C:\Users\michael\Documents\Mission Planner\sitl\ArduCopter.exe' + proc.StartInfo.FileName = r'C:\Users\michael\Documents\Mission Planner\sitl\ArduCopter.exe' proc.StartInfo.Arguments = ' -M+ -s1 --serial0 tcp:0 --defaults ..\default_params\copter.parm --instance ' + str(i) + ' --home -35.363261,'+ str(149.165330 + 0.000001 * i) +',584,353' proc.Start() diff --git a/Scripts/rc - heli.py b/Scripts/rc - heli.py index 074f8823c3..037f22bba7 100644 --- a/Scripts/rc - heli.py +++ b/Scripts/rc - heli.py @@ -1,4 +1,5 @@ -import sys +from __future__ import print_function +import sys import math import clr import time @@ -12,17 +13,16 @@ clr.AddReference("MAVLink") # includes the Utilities class import MAVLink -print 'Start Script' +print('Start Script') Script.SendRC(3,1600,False) Script.SendRC(8,1000,True) -print 'sent throttle down' +print('sent throttle down') MAV.doARM(True); -print 'sent arm' +print('sent arm') Script.SendRC(8,2000,True) -print 'sent throtle up' +print('sent throtle up') Script.ChangeMode("Guided") -print 'sent guided' +print('sent guided') MAV.doCommand(MAVLink.MAV_CMD.TAKEOFF, 0, 0, 0, 0, 0, 0, 100); -print 'sent takeoff' - +print('sent takeoff') diff --git a/Scripts/rc.py b/Scripts/rc.py index 5d1b555859..edcd2ba703 100644 --- a/Scripts/rc.py +++ b/Scripts/rc.py @@ -1,9 +1,10 @@ - +from __future__ import print_function -print 'Start Script' + +print('Start Script') for chan in range(1,9): Script.SendRC(chan,1500,False) Script.SendRC(3,1500,True) Script.Sleep(1000) -Script.SendRC(3,1100,True) \ No newline at end of file +Script.SendRC(3,1100,True) diff --git a/Scripts/ui.py b/Scripts/ui.py index 9338f28d35..1df92f828d 100644 --- a/Scripts/ui.py +++ b/Scripts/ui.py @@ -1,3 +1,4 @@ +from __future__ import print_function #!/usr/bin/ipy import clr @@ -12,16 +13,16 @@ from System.Windows.Forms import Application, Form, Label from System.Drawing import Size, Point, Font, Size -print "MissionPlanner.Drawing" in [assembly.GetName().Name for assembly in clr.References] -print "System.Drawing" in [assembly.GetName().Name for assembly in clr.References] +print("MissionPlanner.Drawing" in [assembly.GetName().Name for assembly in clr.References]) +print("System.Drawing" in [assembly.GetName().Name for assembly in clr.References]) for index, item in enumerate(clr.References): if item.GetName().Name == "System.Drawing": drawing = item font = drawing.GetType("System.Drawing.Font") -print dir(font) +print(dir(font)) font = System.Activator.CreateInstance(font, "Arial", 12) -print "dir ", dir(font) +print("dir ", dir(font)) #################################### # GUI Iform CODE STARTS HERE # #################################### diff --git a/Scripts/wipe.py b/Scripts/wipe.py index cc00ed2eb9..cf50fae639 100644 --- a/Scripts/wipe.py +++ b/Scripts/wipe.py @@ -1,4 +1,5 @@ -# cs.???? = currentstate, any variable on the status tab in the planner can be used. +from __future__ import print_function +# cs.???? = currentstate, any variable on the status tab in the planner can be used. # Script = options are # Script.Sleep(ms) # Script.ChangeParam(name,value) @@ -8,17 +9,17 @@ # Script.SendRC(channel,pwm,sendnow) # -print 'Start Script' +print('Start Script') mrev = Script.GetParam("SYSID_SW_MREV") fmtv = Script.GetParam("FORMAT_VERSION") if mrev > 0: - print Script.ChangeParam("SYSID_SW_MREV",0) + print(Script.ChangeParam("SYSID_SW_MREV",0)) if fmtv > 0: - print Script.ChangeParam("FORMAT_VERSION",0) + print(Script.ChangeParam("FORMAT_VERSION",0)) Script.Sleep(1) MAV.doReboot() -print 'Reset complete' \ No newline at end of file +print('Reset complete')