From b41d4cb521c2c0fa1a8015c99bcba0ef90b0eaf7 Mon Sep 17 00:00:00 2001 From: cclauss Date: Fri, 7 Oct 2016 22:18:07 +0200 Subject: [PATCH 1/4] Python 3: define basestring, use bytes.decode() --- dronekit/__init__.py | 10 ++++++++-- requirements.txt | 2 +- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index 7d98364f4..7da4e9ba1 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -49,6 +49,11 @@ import collections from pymavlink.dialects.v10 import ardupilotmega +try: + basestring # Python 2 +except NameError: # Python 3 + basestring = (str, bytes) + class APIException(Exception): """ @@ -87,7 +92,8 @@ def __init__(self, pitch, yaw, roll): self.roll = roll def __str__(self): - return "Attitude:pitch=%s,yaw=%s,roll=%s" % (self.pitch, self.yaw, self.roll) + fmt = '{}:pitch={pitch},yaw={yaw},roll={roll}' + return fmt.format(self.__class__.__name__, **vars(self)) class LocationGlobal(object): @@ -2822,7 +2828,7 @@ def connect(ip, @vehicle.on_message('STATUSTEXT') def listener(self, name, m): - status_printer(re.sub(r'(^|\n)', '>>> ', m.text.rstrip())) + status_printer(re.sub(r'(^|\n)', '>>> ', m.text.decode('utf-8').rstrip())) if _initialize: vehicle.initialize(rate=rate, heartbeat_timeout=heartbeat_timeout) diff --git a/requirements.txt b/requirements.txt index 7a7076abe..2ef214d36 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,4 +1,4 @@ -pymavlink==2.0.6 +pymavlink==2.0.8 monotonic==1.2 future==0.15.2 nose==1.3.7 From be9e960c44f43384bcb13998a586a709657ac6d9 Mon Sep 17 00:00:00 2001 From: cclauss Date: Fri, 7 Oct 2016 23:49:55 +0200 Subject: [PATCH 2/4] Add flake8 --exit-zero to the Travis CI process --- .travis.yml | 6 ++++ examples/simple_goto/simple_goto.py | 53 ++++++++++++++--------------- 2 files changed, 32 insertions(+), 27 deletions(-) mode change 100644 => 100755 examples/simple_goto/simple_goto.py diff --git a/.travis.yml b/.travis.yml index b8495e401..0d6a1e209 100644 --- a/.travis.yml +++ b/.travis.yml @@ -9,6 +9,12 @@ python: install: - 'pip install -r requirements.txt' + - pip install flake8 + +before_script: + # --exit-zero means that flake8 will not stop the build + # 127 characters is the width of a GitHub editor + flake8 . --count --exit-zero --max-line-length=127 --statistics script: - 'nosetests --debug=nose,nose.importer --debug-log=nose_debug -svx dronekit.test.unit' diff --git a/examples/simple_goto/simple_goto.py b/examples/simple_goto/simple_goto.py old mode 100644 new mode 100755 index b38e3b2d7..f19138b68 --- a/examples/simple_goto/simple_goto.py +++ b/examples/simple_goto/simple_goto.py @@ -14,18 +14,18 @@ import time -#Set up option parsing to get connection string -import argparse +# Set up option parsing to get connection string +import argparse parser = argparse.ArgumentParser(description='Commands vehicle using vehicle.simple_goto.') -parser.add_argument('--connect', - help="Vehicle connection target string. If not specified, SITL automatically started and used.") +parser.add_argument('--connect', + help="Vehicle connection target string. If not specified, SITL automatically started and used.") args = parser.parse_args() connection_string = args.connect sitl = None -#Start SITL if no connection string specified +# Start SITL if no connection string specified if not connection_string: import dronekit_sitl sitl = dronekit_sitl.start_default() @@ -33,7 +33,7 @@ # Connect to the Vehicle -print 'Connecting to vehicle on: %s' % connection_string +print('Connecting to vehicle on: %s' % connection_string) vehicle = connect(connection_string, wait_ready=True) @@ -42,62 +42,61 @@ def arm_and_takeoff(aTargetAltitude): Arms vehicle and fly to aTargetAltitude. """ - print "Basic pre-arm checks" + print("Basic pre-arm checks") # Don't try to arm until autopilot is ready while not vehicle.is_armable: - print " Waiting for vehicle to initialise..." + print(" Waiting for vehicle to initialise...") time.sleep(1) - - print "Arming motors" + print("Arming motors") # Copter should arm in GUIDED mode vehicle.mode = VehicleMode("GUIDED") - vehicle.armed = True + vehicle.armed = True # Confirm vehicle armed before attempting to take off - while not vehicle.armed: - print " Waiting for arming..." + while not vehicle.armed: + print(" Waiting for arming...") time.sleep(1) - print "Taking off!" - vehicle.simple_takeoff(aTargetAltitude) # Take off to target altitude + print("Taking off!") + vehicle.simple_takeoff(aTargetAltitude) # Take off to target altitude - # Wait until the vehicle reaches a safe height before processing the goto (otherwise the command + # Wait until the vehicle reaches a safe height before processing the goto (otherwise the command # after Vehicle.simple_takeoff will execute immediately). while True: - print " Altitude: ", vehicle.location.global_relative_frame.alt - #Break and return from function just below target altitude. - if vehicle.location.global_relative_frame.alt>=aTargetAltitude*0.95: - print "Reached target altitude" + print(" Altitude: ", vehicle.location.global_relative_frame.alt) + # Break and return from function just below target altitude. + if vehicle.location.global_relative_frame.alt >= aTargetAltitude*0.95: + print("Reached target altitude") break time.sleep(1) arm_and_takeoff(10) -print "Set default/target airspeed to 3" +print("Set default/target airspeed to 3") vehicle.airspeed = 3 -print "Going towards first point for 30 seconds ..." +print("Going towards first point for 30 seconds ...") point1 = LocationGlobalRelative(-35.361354, 149.165218, 20) vehicle.simple_goto(point1) # sleep so we can see the change in map time.sleep(30) -print "Going towards second point for 30 seconds (groundspeed set to 10 m/s) ..." +print("Going towards second point for 30 seconds (groundspeed set to 10 m/s) ...") point2 = LocationGlobalRelative(-35.363244, 149.168801, 20) vehicle.simple_goto(point2, groundspeed=10) # sleep so we can see the change in map time.sleep(30) -print "Returning to Launch" +print("Returning to Launch") vehicle.mode = VehicleMode("RTL") -#Close vehicle object before exiting script -print "Close vehicle object" +# Close vehicle object before exiting script +print("Close vehicle object") vehicle.close() # Shut down simulator if it was started. -if sitl is not None: +if sitl: sitl.stop() From a18e51832961222932b6354354686e8c76bacfce Mon Sep 17 00:00:00 2001 From: cclauss Date: Sat, 8 Oct 2016 06:09:56 +0200 Subject: [PATCH 3/4] Flake8 select only the most vital issues --- .travis.yml | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 0d6a1e209..1e70ee59f 100644 --- a/.travis.yml +++ b/.travis.yml @@ -14,7 +14,16 @@ install: before_script: # --exit-zero means that flake8 will not stop the build # 127 characters is the width of a GitHub editor - flake8 . --count --exit-zero --max-line-length=127 --statistics + # E703 statement ends with a semicolon + # E711 comparison to None should be 'if cond is None:' + # E712 comparison to False should be 'if cond is False:' or 'if not cond:' + # E713 test for membership should be 'not in' + # E999 SyntaxError: invalid syntax + # F401 'socket' imported but unused + # F403 'from dronekit import *' used; unable to detect undefined names + # F811 redefinition of unused 'types' from line 45 + # F821 undefined name 'xrange' + flake8 . --count --exit-zero --max-line-length=127 --select=E703,E711,E712,E713,E999,F401,F403,F811,F821 --statistics script: - 'nosetests --debug=nose,nose.importer --debug-log=nose_debug -svx dronekit.test.unit' From 70b03785667b68fedf34a83fac036863fe68d487 Mon Sep 17 00:00:00 2001 From: cclauss Date: Sat, 8 Oct 2016 06:23:59 +0200 Subject: [PATCH 4/4] xrange --> range --- dronekit/__init__.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index 7da4e9ba1..7291fd17f 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -2740,7 +2740,7 @@ def __len__(self): def __getitem__(self, index): if isinstance(index, slice): - return [self[ii] for ii in xrange(*index.indices(len(self)))] + return [self[ii] for ii in range(*index.indices(len(self)))] elif isinstance(index, int): item = self._vehicle._wploader.wp(index + 1) if not item: