mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 02:55:07 +08:00
Use print() function in both Python 2 and Python 3
Legacy __print__ statements are syntax errors in Python 3 but __print()__ function works as expected in both Python 2 and Python 3.
This commit is contained in:
+8
-7
@@ -41,6 +41,7 @@ Usage: python fetch_file.py [-l] [-f] [-d device] [-s speed] [-o out_path] path
|
|||||||
\t-s\tSerial baudrate
|
\t-s\tSerial baudrate
|
||||||
\t-o\tOutput path
|
\t-o\tOutput path
|
||||||
\tpath\tPath to list/fetch, if ends with "/" then directory will be fetched recursively"""
|
\tpath\tPath to list/fetch, if ends with "/" then directory will be fetched recursively"""
|
||||||
|
from __future__ import print_function
|
||||||
|
|
||||||
__author__ = "Anton Babushkin"
|
__author__ = "Anton Babushkin"
|
||||||
__version__ = "1.1"
|
__version__ = "1.1"
|
||||||
@@ -82,7 +83,7 @@ def _ls_dir(ser, dir, timeout):
|
|||||||
return res
|
return res
|
||||||
|
|
||||||
def _get_file(ser, fn, fn_out, force, timeout):
|
def _get_file(ser, fn, fn_out, force, timeout):
|
||||||
print "Get %s:" % fn,
|
print("Get %s:" % fn, end=' ')
|
||||||
if not force:
|
if not force:
|
||||||
# Check if file already exists with the same size
|
# Check if file already exists with the same size
|
||||||
try:
|
try:
|
||||||
@@ -90,7 +91,7 @@ def _get_file(ser, fn, fn_out, force, timeout):
|
|||||||
except:
|
except:
|
||||||
pass
|
pass
|
||||||
else:
|
else:
|
||||||
print "already fetched, skip"
|
print("already fetched, skip")
|
||||||
return
|
return
|
||||||
|
|
||||||
cmd = "dumpfile " + fn
|
cmd = "dumpfile " + fn
|
||||||
@@ -112,7 +113,7 @@ def _get_file(ser, fn, fn_out, force, timeout):
|
|||||||
sys.stdout.write(".")
|
sys.stdout.write(".")
|
||||||
sys.stdout.flush()
|
sys.stdout.flush()
|
||||||
fout.write(buf)
|
fout.write(buf)
|
||||||
print " done"
|
print(" done")
|
||||||
fout.close()
|
fout.close()
|
||||||
os.rename(fn_out_part, fn_out)
|
os.rename(fn_out_part, fn_out)
|
||||||
else:
|
else:
|
||||||
@@ -133,13 +134,13 @@ def _get_files_in_dir(ser, path, path_out, force, timeout):
|
|||||||
_get_file(ser, path_fn, path_fn_out, force, timeout)
|
_get_file(ser, path_fn, path_fn_out, force, timeout)
|
||||||
|
|
||||||
def _usage():
|
def _usage():
|
||||||
print """Usage: python fetch_file.py [-l] [-f] [-d device] [-s speed] [-o out_path] path
|
print("""Usage: python fetch_file.py [-l] [-f] [-d device] [-s speed] [-o out_path] path
|
||||||
\t-l\tList files
|
\t-l\tList files
|
||||||
\t-f\tOverwrite existing files
|
\t-f\tOverwrite existing files
|
||||||
\t-d\tSerial device
|
\t-d\tSerial device
|
||||||
\t-s\tSerial baudrate
|
\t-s\tSerial baudrate
|
||||||
\t-o\tOutput path
|
\t-o\tOutput path
|
||||||
\tpath\tPath to list/fetch, if ends with "/" then directory will be fetched recursively"""
|
\tpath\tPath to list/fetch, if ends with "/" then directory will be fetched recursively""")
|
||||||
|
|
||||||
def _main():
|
def _main():
|
||||||
dev = "/dev/tty.usbmodem1"
|
dev = "/dev/tty.usbmodem1"
|
||||||
@@ -185,7 +186,7 @@ def _main():
|
|||||||
try:
|
try:
|
||||||
if cmd == "ls":
|
if cmd == "ls":
|
||||||
# List directory
|
# List directory
|
||||||
print _ls_dir_raw(ser, path, timeout)
|
print(_ls_dir_raw(ser, path, timeout))
|
||||||
elif cmd == "get":
|
elif cmd == "get":
|
||||||
# Get file(s)
|
# Get file(s)
|
||||||
if path.endswith("/"):
|
if path.endswith("/"):
|
||||||
@@ -199,7 +200,7 @@ def _main():
|
|||||||
path_out = os.path.split(path)[1]
|
path_out = os.path.split(path)[1]
|
||||||
_get_file(ser, path, os.path.split(path)[1], force, timeout)
|
_get_file(ser, path, os.path.split(path)[1], force, timeout)
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
print e
|
print(e)
|
||||||
|
|
||||||
ser.close()
|
ser.close()
|
||||||
|
|
||||||
|
|||||||
+14
-13
@@ -30,6 +30,7 @@
|
|||||||
# Parts included from https://github.com/PX4/flight_review/
|
# Parts included from https://github.com/PX4/flight_review/
|
||||||
|
|
||||||
|
|
||||||
|
from __future__ import print_function
|
||||||
import os, sys, time, datetime, piexif
|
import os, sys, time, datetime, piexif
|
||||||
from pyulog import *
|
from pyulog import *
|
||||||
from pyulog.px4 import *
|
from pyulog.px4 import *
|
||||||
@@ -38,9 +39,9 @@ from fractions import Fraction
|
|||||||
|
|
||||||
|
|
||||||
if(len(sys.argv)) < 3:
|
if(len(sys.argv)) < 3:
|
||||||
print "Usage: python geotag_images_ulog.py [logfile] [image dir]"
|
print("Usage: python geotag_images_ulog.py [logfile] [image dir]")
|
||||||
print "Example: python geotag_images_ulog.py mylog.ulg ./images"
|
print("Example: python geotag_images_ulog.py mylog.ulg ./images")
|
||||||
print len(sys.argv)
|
print(len(sys.argv))
|
||||||
sys.exit()
|
sys.exit()
|
||||||
|
|
||||||
logfile = sys.argv[1]
|
logfile = sys.argv[1]
|
||||||
@@ -189,13 +190,13 @@ for f in reversed(files):
|
|||||||
timestamp = time.mktime(datetime.datetime.strptime(timestring, "%Y:%m:%d %H:%M:%S").timetuple())
|
timestamp = time.mktime(datetime.datetime.strptime(timestring, "%Y:%m:%d %H:%M:%S").timetuple())
|
||||||
if first == 0:
|
if first == 0:
|
||||||
first = timestamp
|
first = timestamp
|
||||||
print "Calibrating on",f,"as last image on",timestring
|
print("Calibrating on",f,"as last image on",timestring)
|
||||||
print ""
|
print("")
|
||||||
print "[filename] [offset] [trigger seq] [lat] [lng] [alt]"
|
print("[filename] [offset] [trigger seq] [lat] [lng] [alt]")
|
||||||
|
|
||||||
offset = first - timestamp
|
offset = first - timestamp
|
||||||
print(f),
|
print((f), end=' ')
|
||||||
print(offset),
|
print((offset), end=' ')
|
||||||
if not offset in offsets:
|
if not offset in offsets:
|
||||||
offset += 1
|
offset += 1
|
||||||
|
|
||||||
@@ -203,9 +204,9 @@ for f in reversed(files):
|
|||||||
offset += 1
|
offset += 1
|
||||||
|
|
||||||
if offset in offsets:
|
if offset in offsets:
|
||||||
print(offsets[offset]),
|
print((offsets[offset]), end=' ')
|
||||||
print(camera_capture.data['lat'][offsets[offset]]),
|
print((camera_capture.data['lat'][offsets[offset]]), end=' ')
|
||||||
print(camera_capture.data['lon'][offsets[offset]]),
|
print((camera_capture.data['lon'][offsets[offset]]), end=' ')
|
||||||
print(camera_capture.data['alt'][offsets[offset]])
|
print(camera_capture.data['alt'][offsets[offset]])
|
||||||
|
|
||||||
lat = camera_capture.data['lat'][offsets[offset]]
|
lat = camera_capture.data['lat'][offsets[offset]]
|
||||||
@@ -232,7 +233,7 @@ for f in reversed(files):
|
|||||||
exif_bytes = piexif.dump(exif_dict)
|
exif_bytes = piexif.dump(exif_dict)
|
||||||
piexif.insert(exif_bytes, f)
|
piexif.insert(exif_bytes, f)
|
||||||
else:
|
else:
|
||||||
print "Could not georeference"
|
print("Could not georeference")
|
||||||
|
|
||||||
|
|
||||||
print "Done"
|
print("Done")
|
||||||
|
|||||||
@@ -33,6 +33,7 @@ Example invocations.
|
|||||||
Compilation database setup:
|
Compilation database setup:
|
||||||
http://clang.llvm.org/docs/HowToSetupToolingForLLVM.html
|
http://clang.llvm.org/docs/HowToSetupToolingForLLVM.html
|
||||||
"""
|
"""
|
||||||
|
from __future__ import print_function
|
||||||
|
|
||||||
import argparse
|
import argparse
|
||||||
import json
|
import json
|
||||||
@@ -54,7 +55,7 @@ def find_compilation_database(path):
|
|||||||
result = './'
|
result = './'
|
||||||
while not os.path.isfile(os.path.join(result, path)):
|
while not os.path.isfile(os.path.join(result, path)):
|
||||||
if os.path.realpath(result) == '/':
|
if os.path.realpath(result) == '/':
|
||||||
print 'Error: could not find compilation database.'
|
print('Error: could not find compilation database.')
|
||||||
sys.exit(1)
|
sys.exit(1)
|
||||||
result += '../'
|
result += '../'
|
||||||
return os.path.realpath(result)
|
return os.path.realpath(result)
|
||||||
@@ -168,9 +169,9 @@ def main():
|
|||||||
if args.checks:
|
if args.checks:
|
||||||
invocation.append('-checks=' + args.checks)
|
invocation.append('-checks=' + args.checks)
|
||||||
invocation.append('-')
|
invocation.append('-')
|
||||||
print subprocess.check_output(invocation)
|
print(subprocess.check_output(invocation))
|
||||||
except:
|
except:
|
||||||
print >>sys.stderr, "Unable to run clang-tidy."
|
print("Unable to run clang-tidy.", file=sys.stderr)
|
||||||
sys.exit(1)
|
sys.exit(1)
|
||||||
|
|
||||||
# Load the database and extract all files.
|
# Load the database and extract all files.
|
||||||
@@ -208,18 +209,18 @@ def main():
|
|||||||
except KeyboardInterrupt:
|
except KeyboardInterrupt:
|
||||||
# This is a sad hack. Unfortunately subprocess goes
|
# This is a sad hack. Unfortunately subprocess goes
|
||||||
# bonkers with ctrl-c and we start forking merrily.
|
# bonkers with ctrl-c and we start forking merrily.
|
||||||
print '\nCtrl-C detected, goodbye.'
|
print('\nCtrl-C detected, goodbye.')
|
||||||
if args.fix:
|
if args.fix:
|
||||||
shutil.rmtree(tmpdir)
|
shutil.rmtree(tmpdir)
|
||||||
os.kill(0, 9)
|
os.kill(0, 9)
|
||||||
|
|
||||||
if args.fix:
|
if args.fix:
|
||||||
print 'Applying fixes ...'
|
print('Applying fixes ...')
|
||||||
apply_fixes(args, tmpdir)
|
apply_fixes(args, tmpdir)
|
||||||
|
|
||||||
global tidy_failures
|
global tidy_failures
|
||||||
if tidy_failures > 0:
|
if tidy_failures > 0:
|
||||||
print >>sys.stderr, "clang-tidy errors: ", tidy_failures
|
print("clang-tidy errors: ", tidy_failures, file=sys.stderr)
|
||||||
sys.exit(1)
|
sys.exit(1)
|
||||||
|
|
||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
|
|||||||
@@ -15,6 +15,7 @@
|
|||||||
# Settings
|
# Settings
|
||||||
################################################################################################
|
################################################################################################
|
||||||
|
|
||||||
|
from __future__ import print_function
|
||||||
connection_string = '127.0.0.1:14540'
|
connection_string = '127.0.0.1:14540'
|
||||||
|
|
||||||
import_mission_filename = 'VTOL_TAKEOFF.mission'
|
import_mission_filename = 'VTOL_TAKEOFF.mission'
|
||||||
@@ -58,22 +59,22 @@ elapsed_time = time.time() - start_time
|
|||||||
|
|
||||||
|
|
||||||
# Connect to the Vehicle
|
# Connect to the Vehicle
|
||||||
print "Connecting"
|
print("Connecting")
|
||||||
vehicle = connect(connection_string, wait_ready=True)
|
vehicle = connect(connection_string, wait_ready=True)
|
||||||
|
|
||||||
while not vehicle.system_status.state == "STANDBY" or vehicle.gps_0.fix_type < 3:
|
while not vehicle.system_status.state == "STANDBY" or vehicle.gps_0.fix_type < 3:
|
||||||
if time.time() - start_time > 20:
|
if time.time() - start_time > 20:
|
||||||
print "FAILED: SITL did not reach standby with GPS fix within 20 seconds"
|
print("FAILED: SITL did not reach standby with GPS fix within 20 seconds")
|
||||||
sys.exit(98)
|
sys.exit(98)
|
||||||
print "Waiting for vehicle to initialise... %s " % vehicle.system_status.state
|
print("Waiting for vehicle to initialise... %s " % vehicle.system_status.state)
|
||||||
time.sleep(1)
|
time.sleep(1)
|
||||||
|
|
||||||
# Display basic vehicle state
|
# Display basic vehicle state
|
||||||
print " Type: %s" % vehicle._vehicle_type
|
print(" Type: %s" % vehicle._vehicle_type)
|
||||||
print " Armed?: %s" % vehicle.armed
|
print(" Armed?: %s" % vehicle.armed)
|
||||||
print " System status: %s" % vehicle.system_status.state
|
print(" System status: %s" % vehicle.system_status.state)
|
||||||
print " GPS: %s" % vehicle.gps_0
|
print(" GPS: %s" % vehicle.gps_0)
|
||||||
print " Alt: %s" % vehicle.location.global_relative_frame.alt
|
print(" Alt: %s" % vehicle.location.global_relative_frame.alt)
|
||||||
|
|
||||||
|
|
||||||
################################################################################################
|
################################################################################################
|
||||||
@@ -106,7 +107,7 @@ def upload_mission(aFileName):
|
|||||||
#Add new mission to vehicle
|
#Add new mission to vehicle
|
||||||
for command in missionlist:
|
for command in missionlist:
|
||||||
cmds.add(command)
|
cmds.add(command)
|
||||||
print ' Uploaded mission with %s items' % len(missionlist)
|
print(' Uploaded mission with %s items' % len(missionlist))
|
||||||
vehicle.commands.upload()
|
vehicle.commands.upload()
|
||||||
return missionlist
|
return missionlist
|
||||||
|
|
||||||
@@ -128,7 +129,7 @@ def listener(self, name, mission_current):
|
|||||||
if (current_sequence <> mission_current.seq):
|
if (current_sequence <> mission_current.seq):
|
||||||
current_sequence = mission_current.seq;
|
current_sequence = mission_current.seq;
|
||||||
current_sequence_changed = True
|
current_sequence_changed = True
|
||||||
print 'current mission sequence: %s' % mission_current.seq
|
print('current mission sequence: %s' % mission_current.seq)
|
||||||
|
|
||||||
#Create a message listener for mission sequence number
|
#Create a message listener for mission sequence number
|
||||||
@vehicle.on_message('EXTENDED_SYS_STATE')
|
@vehicle.on_message('EXTENDED_SYS_STATE')
|
||||||
@@ -152,9 +153,9 @@ def listener(self, name, home_position):
|
|||||||
|
|
||||||
while not home_position_set:
|
while not home_position_set:
|
||||||
if time.time() - start_time > 30:
|
if time.time() - start_time > 30:
|
||||||
print "FAILED: getting home position 30 seconds"
|
print("FAILED: getting home position 30 seconds")
|
||||||
sys.exit(98)
|
sys.exit(98)
|
||||||
print "Waiting for home position..."
|
print("Waiting for home position...")
|
||||||
time.sleep(1)
|
time.sleep(1)
|
||||||
|
|
||||||
|
|
||||||
@@ -172,9 +173,9 @@ vehicle.armed = True
|
|||||||
|
|
||||||
while not vehicle.system_status.state == "ACTIVE":
|
while not vehicle.system_status.state == "ACTIVE":
|
||||||
if time.time() - start_time > 30:
|
if time.time() - start_time > 30:
|
||||||
print "FAILED: vehicle did not arm within 30 seconds"
|
print("FAILED: vehicle did not arm within 30 seconds")
|
||||||
sys.exit(98)
|
sys.exit(98)
|
||||||
print "Waiting for vehicle to arm..."
|
print("Waiting for vehicle to arm...")
|
||||||
time.sleep(1)
|
time.sleep(1)
|
||||||
|
|
||||||
|
|
||||||
@@ -185,13 +186,13 @@ while (current_sequence < len(missionlist)-1 and elapsed_time < max_execution_ti
|
|||||||
if current_sequence > 0 and current_sequence_changed:
|
if current_sequence > 0 and current_sequence_changed:
|
||||||
|
|
||||||
if missionlist[current_sequence-1].z - alt_acceptance_radius > vehicle.location.global_relative_frame.alt or missionlist[current_sequence-1].z + alt_acceptance_radius < vehicle.location.global_relative_frame.alt:
|
if missionlist[current_sequence-1].z - alt_acceptance_radius > vehicle.location.global_relative_frame.alt or missionlist[current_sequence-1].z + alt_acceptance_radius < vehicle.location.global_relative_frame.alt:
|
||||||
print "waypoint %s out of bounds altitude %s gps altitude: %s" % (current_sequence, missionlist[current_sequence-1].z, vehicle.location.global_relative_frame.alt)
|
print("waypoint %s out of bounds altitude %s gps altitude: %s" % (current_sequence, missionlist[current_sequence-1].z, vehicle.location.global_relative_frame.alt))
|
||||||
mission_failed = True
|
mission_failed = True
|
||||||
current_sequence_changed = False
|
current_sequence_changed = False
|
||||||
elapsed_time = time.time() - start_time
|
elapsed_time = time.time() - start_time
|
||||||
|
|
||||||
if elapsed_time < max_execution_time:
|
if elapsed_time < max_execution_time:
|
||||||
print "Mission items have been executed"
|
print("Mission items have been executed")
|
||||||
|
|
||||||
# wait for the vehicle to have landed
|
# wait for the vehicle to have landed
|
||||||
while (current_landed_state != 1 and elapsed_time < max_execution_time):
|
while (current_landed_state != 1 and elapsed_time < max_execution_time):
|
||||||
@@ -199,7 +200,7 @@ while (current_landed_state != 1 and elapsed_time < max_execution_time):
|
|||||||
elapsed_time = time.time() - start_time
|
elapsed_time = time.time() - start_time
|
||||||
|
|
||||||
if elapsed_time < max_execution_time:
|
if elapsed_time < max_execution_time:
|
||||||
print "Vehicle has landed"
|
print("Vehicle has landed")
|
||||||
|
|
||||||
# Disarm vehicle
|
# Disarm vehicle
|
||||||
vehicle.armed = False
|
vehicle.armed = False
|
||||||
@@ -213,16 +214,16 @@ time.sleep(2)
|
|||||||
|
|
||||||
# Validate time constraint
|
# Validate time constraint
|
||||||
if elapsed_time <= max_execution_time and not mission_failed:
|
if elapsed_time <= max_execution_time and not mission_failed:
|
||||||
print "Mission succesful time elapsed %s" % elapsed_time
|
print("Mission succesful time elapsed %s" % elapsed_time)
|
||||||
sys.exit(0)
|
sys.exit(0)
|
||||||
|
|
||||||
if elapsed_time > max_execution_time:
|
if elapsed_time > max_execution_time:
|
||||||
print "Mission FAILED to execute within %s seconds" % max_execution_time
|
print("Mission FAILED to execute within %s seconds" % max_execution_time)
|
||||||
sys.exit(99)
|
sys.exit(99)
|
||||||
|
|
||||||
if mission_failed:
|
if mission_failed:
|
||||||
print "Mission FAILED out of bounds"
|
print("Mission FAILED out of bounds")
|
||||||
sys.exit(100)
|
sys.exit(100)
|
||||||
|
|
||||||
print "Mission FAILED something strange happened"
|
print("Mission FAILED something strange happened")
|
||||||
sys.exit(101)
|
sys.exit(101)
|
||||||
|
|||||||
@@ -1,5 +1,6 @@
|
|||||||
|
from __future__ import print_function
|
||||||
import sys
|
import sys
|
||||||
print 'Arguments: file - ' + sys.argv[1] + ', length - ' + sys.argv[2]
|
print('Arguments: file - ' + sys.argv[1] + ', length - ' + sys.argv[2])
|
||||||
file = open(sys.argv[1], 'w')
|
file = open(sys.argv[1], 'w')
|
||||||
for i in range(int(sys.argv[2])):
|
for i in range(int(sys.argv[2])):
|
||||||
b = bytearray([i & 0xFF])
|
b = bytearray([i & 0xFF])
|
||||||
|
|||||||
Reference in New Issue
Block a user