Skip to content

Commit d8cca69

Browse files
cclausspeterbarker
authored andcommitted
Modernize Python 2 code to get ready for Python 3
1 parent 754ce62 commit d8cca69

File tree

12 files changed

+572
-563
lines changed

12 files changed

+572
-563
lines changed

.travis.yml

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@ env:
66
- SITL_RATE=200
77

88
python:
9-
- 2.7.13
9+
- 2.7
1010
- 3.6
1111

1212
before_install:
@@ -17,10 +17,10 @@ install:
1717
- pip install flake8
1818

1919
before_script:
20-
# --exit-zero means that flake8 will not stop the build
21-
# 127 characters is the width of a GitHub editor
22-
- flake8 . --count --exit-zero --max-line-length=127 --select=E999 --statistics # syntax errors
23-
- flake8 . --count --exit-zero --max-line-length=127 --statistics
20+
# stop the build if there are Python syntax errors or undefined names
21+
- flake8 . --count --select=E901,E999,F821,F822,F823 --show-source --statistics
22+
# exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide
23+
- flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics
2424

2525
script:
2626
- nosetests --debug=nose,nose.importer --debug-log=nose_debug -svx dronekit.test.unit
@@ -41,7 +41,6 @@ notifications:
4141
matrix:
4242
allow_failures:
4343
- python: 3.6
44-
fast_finish: true
4544

4645
branches:
4746
only:

examples/channel_overrides/channel_overrides.py

Lines changed: 30 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
1818
Full documentation is provided at http://python.dronekit.io/examples/channel_overrides.html
1919
"""
20+
from __future__ import print_function
2021
from dronekit import connect
2122

2223

@@ -39,61 +40,61 @@
3940

4041

4142
# Connect to the Vehicle
42-
print 'Connecting to vehicle on: %s' % connection_string
43+
print('Connecting to vehicle on: %s' % connection_string)
4344
vehicle = connect(connection_string, wait_ready=True)
4445

4546
# Get all original channel values (before override)
46-
print "Channel values from RC Tx:", vehicle.channels
47+
print("Channel values from RC Tx:", vehicle.channels)
4748

4849
# Access channels individually
49-
print "Read channels individually:"
50-
print " Ch1: %s" % vehicle.channels['1']
51-
print " Ch2: %s" % vehicle.channels['2']
52-
print " Ch3: %s" % vehicle.channels['3']
53-
print " Ch4: %s" % vehicle.channels['4']
54-
print " Ch5: %s" % vehicle.channels['5']
55-
print " Ch6: %s" % vehicle.channels['6']
56-
print " Ch7: %s" % vehicle.channels['7']
57-
print " Ch8: %s" % vehicle.channels['8']
58-
print "Number of channels: %s" % len(vehicle.channels)
50+
print("Read channels individually:")
51+
print(" Ch1: %s" % vehicle.channels['1'])
52+
print(" Ch2: %s" % vehicle.channels['2'])
53+
print(" Ch3: %s" % vehicle.channels['3'])
54+
print(" Ch4: %s" % vehicle.channels['4'])
55+
print(" Ch5: %s" % vehicle.channels['5'])
56+
print(" Ch6: %s" % vehicle.channels['6'])
57+
print(" Ch7: %s" % vehicle.channels['7'])
58+
print(" Ch8: %s" % vehicle.channels['8'])
59+
print("Number of channels: %s" % len(vehicle.channels))
5960

6061

6162
# Override channels
62-
print "\nChannel overrides: %s" % vehicle.channels.overrides
63+
print("\nChannel overrides: %s" % vehicle.channels.overrides)
6364

64-
print "Set Ch2 override to 200 (indexing syntax)"
65+
print("Set Ch2 override to 200 (indexing syntax)")
6566
vehicle.channels.overrides['2'] = 200
66-
print " Channel overrides: %s" % vehicle.channels.overrides
67-
print " Ch2 override: %s" % vehicle.channels.overrides['2']
67+
print(" Channel overrides: %s" % vehicle.channels.overrides)
68+
print(" Ch2 override: %s" % vehicle.channels.overrides['2'])
6869

69-
print "Set Ch3 override to 300 (dictionary syntax)"
70+
print("Set Ch3 override to 300 (dictionary syntax)")
7071
vehicle.channels.overrides = {'3':300}
71-
print " Channel overrides: %s" % vehicle.channels.overrides
72+
print(" Channel overrides: %s" % vehicle.channels.overrides)
7273

73-
print "Set Ch1-Ch8 overrides to 110-810 respectively"
74+
print("Set Ch1-Ch8 overrides to 110-810 respectively")
7475
vehicle.channels.overrides = {'1': 110, '2': 210,'3': 310,'4':4100, '5':510,'6':610,'7':710,'8':810}
75-
print " Channel overrides: %s" % vehicle.channels.overrides
76+
print(" Channel overrides: %s" % vehicle.channels.overrides)
7677

7778

7879
# Clear override by setting channels to None
79-
print "\nCancel Ch2 override (indexing syntax)"
80+
print("\nCancel Ch2 override (indexing syntax)")
8081
vehicle.channels.overrides['2'] = None
81-
print " Channel overrides: %s" % vehicle.channels.overrides
82+
print(" Channel overrides: %s" % vehicle.channels.overrides)
8283

83-
print "Clear Ch3 override (del syntax)"
84+
print("Clear Ch3 override (del syntax)")
8485
del vehicle.channels.overrides['3']
85-
print " Channel overrides: %s" % vehicle.channels.overrides
86+
print(" Channel overrides: %s" % vehicle.channels.overrides)
8687

87-
print "Clear Ch5, Ch6 override and set channel 3 to 500 (dictionary syntax)"
88+
print("Clear Ch5, Ch6 override and set channel 3 to 500 (dictionary syntax)")
8889
vehicle.channels.overrides = {'5':None, '6':None,'3':500}
89-
print " Channel overrides: %s" % vehicle.channels.overrides
90+
print(" Channel overrides: %s" % vehicle.channels.overrides)
9091

91-
print "Clear all overrides"
92+
print("Clear all overrides")
9293
vehicle.channels.overrides = {}
93-
print " Channel overrides: %s" % vehicle.channels.overrides
94+
print(" Channel overrides: %s" % vehicle.channels.overrides)
9495

9596
#Close vehicle object before exiting script
96-
print "\nClose vehicle object"
97+
print("\nClose vehicle object")
9798
vehicle.close()
9899

99100
# Shut down simulator if it was started.

examples/create_attribute/create_attribute.py

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
1515
Full documentation is provided at http://python.dronekit.io/examples/create_attribute.html
1616
"""
17+
from __future__ import print_function
1718

1819
from dronekit import connect, Vehicle
1920
from my_vehicle import MyVehicle #Our custom vehicle class
@@ -40,25 +41,25 @@
4041

4142

4243
# Connect to the Vehicle
43-
print 'Connecting to vehicle on: %s' % connection_string
44+
print('Connecting to vehicle on: %s' % connection_string)
4445
vehicle = connect(connection_string, wait_ready=True, vehicle_class=MyVehicle)
4546

4647
# Add observer for the custom attribute
4748

4849
def raw_imu_callback(self, attr_name, value):
4950
# attr_name == 'raw_imu'
5051
# value == vehicle.raw_imu
51-
print value
52+
print(value)
5253

5354
vehicle.add_attribute_listener('raw_imu', raw_imu_callback)
5455

55-
print 'Display RAW_IMU messages for 5 seconds and then exit.'
56+
print('Display RAW_IMU messages for 5 seconds and then exit.')
5657
time.sleep(5)
5758

5859
#The message listener can be unset using ``vehicle.remove_message_listener``
5960

6061
#Close vehicle object before exiting script
61-
print "Close vehicle object"
62+
print("Close vehicle object")
6263
vehicle.close()
6364

6465
# Shut down simulator if it was started.

examples/flight_replay/flight_replay.py

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
1111
Full documentation is provided at http://python.dronekit.io/examples/flight_replay.html
1212
"""
13+
from __future__ import print_function
1314

1415
from dronekit import connect, Command, VehicleMode, LocationGlobalRelative
1516
from pymavlink import mavutil
@@ -107,7 +108,7 @@ def arm_and_takeoff(aTargetAltitude):
107108

108109
# Don't try to arm until autopilot is ready
109110
while not vehicle.is_armable:
110-
print " Waiting for vehicle to initialise..."
111+
print(" Waiting for vehicle to initialise...")
111112
time.sleep(1)
112113

113114
# Set mode to GUIDED for arming and takeoff:
@@ -118,10 +119,10 @@ def arm_and_takeoff(aTargetAltitude):
118119
# Confirm vehicle armed before attempting to take off
119120
while not vehicle.armed:
120121
vehicle.armed = True
121-
print " Waiting for arming..."
122+
print(" Waiting for arming...")
122123
time.sleep(1)
123124

124-
print " Taking off!"
125+
print(" Taking off!")
125126
vehicle.simple_takeoff(aTargetAltitude) # Take off to target altitude
126127

127128
# Wait until the vehicle reaches a safe height
@@ -130,16 +131,16 @@ def arm_and_takeoff(aTargetAltitude):
130131
requiredAlt = aTargetAltitude*0.95
131132
#Break and return from function just below target altitude.
132133
if vehicle.location.global_relative_frame.alt>=requiredAlt:
133-
print " Reached target altitude of ~%f" % (aTargetAltitude)
134+
print(" Reached target altitude of ~%f" % (aTargetAltitude))
134135
break
135-
print " Altitude: %f < %f" % (vehicle.location.global_relative_frame.alt,
136-
requiredAlt)
136+
print(" Altitude: %f < %f" % (vehicle.location.global_relative_frame.alt,
137+
requiredAlt))
137138
time.sleep(1)
138139

139140

140141
print("Generating waypoints from tlog...")
141142
messages = position_messages_from_tlog(args.tlog)
142-
print " Generated %d waypoints from tlog" % len(messages)
143+
print(" Generated %d waypoints from tlog" % len(messages))
143144
if len(messages) == 0:
144145
print("No position messages found in log")
145146
exit(0)
@@ -157,7 +158,7 @@ def arm_and_takeoff(aTargetAltitude):
157158
connection_string = sitl.connection_string()
158159

159160
# Connect to the Vehicle
160-
print 'Connecting to vehicle on: %s' % connection_string
161+
print('Connecting to vehicle on: %s' % connection_string)
161162
vehicle = connect(connection_string, wait_ready=True)
162163

163164

@@ -168,8 +169,7 @@ def arm_and_takeoff(aTargetAltitude):
168169

169170
cmds = vehicle.commands
170171
cmds.clear()
171-
for i in xrange(0, len(messages)):
172-
pt = messages[i]
172+
for pt in messages:
173173
#print "Point: %d %d" % (pt.lat, pt.lon,)
174174
lat = pt.lat
175175
lon = pt.lon
@@ -189,11 +189,11 @@ def arm_and_takeoff(aTargetAltitude):
189189
print("Uploading %d waypoints to vehicle..." % len(messages))
190190
cmds.upload()
191191

192-
print "Arm and Takeoff"
192+
print("Arm and Takeoff")
193193
arm_and_takeoff(30)
194194

195195

196-
print "Starting mission"
196+
print("Starting mission")
197197

198198
# Reset mission set to first (0) waypoint
199199
vehicle.commands.next=0
@@ -207,20 +207,20 @@ def arm_and_takeoff(aTargetAltitude):
207207
time_start = time.time()
208208
while time.time() - time_start < 60:
209209
nextwaypoint=vehicle.commands.next
210-
print 'Distance to waypoint (%s): %s' % (nextwaypoint, distance_to_current_waypoint())
210+
print('Distance to waypoint (%s): %s' % (nextwaypoint, distance_to_current_waypoint()))
211211

212212
if nextwaypoint==len(messages):
213-
print "Exit 'standard' mission when start heading to final waypoint"
213+
print("Exit 'standard' mission when start heading to final waypoint")
214214
break;
215215
time.sleep(1)
216216

217-
print 'Return to launch'
217+
print('Return to launch')
218218
while (vehicle.mode.name != "RTL"):
219219
vehicle.mode = VehicleMode("RTL")
220220
time.sleep(0.1)
221221

222222
#Close vehicle object before exiting script
223-
print "Close vehicle object"
223+
print("Close vehicle object")
224224
vehicle.close()
225225

226226
# Shut down simulator if it was started.

examples/follow_me/follow_me.py

Lines changed: 14 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
1414
Example documentation: http://python.dronekit.io/examples/follow_me.html
1515
"""
16+
from __future__ import print_function
1617

1718
from dronekit import connect, VehicleMode, LocationGlobalRelative
1819
import gps
@@ -38,7 +39,7 @@
3839
connection_string = sitl.connection_string()
3940

4041
# Connect to the Vehicle
41-
print 'Connecting to vehicle on: %s' % connection_string
42+
print('Connecting to vehicle on: %s' % connection_string)
4243
vehicle = connect(connection_string, wait_ready=True)
4344

4445

@@ -48,31 +49,31 @@ def arm_and_takeoff(aTargetAltitude):
4849
Arms vehicle and fly to aTargetAltitude.
4950
"""
5051

51-
print "Basic pre-arm checks"
52+
print("Basic pre-arm checks")
5253
# Don't let the user try to arm until autopilot is ready
5354
while not vehicle.is_armable:
54-
print " Waiting for vehicle to initialise..."
55+
print(" Waiting for vehicle to initialise...")
5556
time.sleep(1)
5657

5758

58-
print "Arming motors"
59+
print("Arming motors")
5960
# Copter should arm in GUIDED mode
6061
vehicle.mode = VehicleMode("GUIDED")
6162
vehicle.armed = True
6263

6364
while not vehicle.armed:
64-
print " Waiting for arming..."
65+
print(" Waiting for arming...")
6566
time.sleep(1)
6667

67-
print "Taking off!"
68+
print("Taking off!")
6869
vehicle.simple_takeoff(aTargetAltitude) # Take off to target altitude
6970

7071
# Wait until the vehicle reaches a safe height before processing the goto (otherwise the command
7172
# after Vehicle.simple_takeoff will execute immediately).
7273
while True:
73-
print " Altitude: ", vehicle.location.global_relative_frame.alt
74+
print(" Altitude: ", vehicle.location.global_relative_frame.alt)
7475
if vehicle.location.global_relative_frame.alt>=aTargetAltitude*0.95: #Trigger just below target alt.
75-
print "Reached target altitude"
76+
print("Reached target altitude")
7677
break
7778
time.sleep(1)
7879

@@ -88,17 +89,17 @@ def arm_and_takeoff(aTargetAltitude):
8889
while True:
8990

9091
if vehicle.mode.name != "GUIDED":
91-
print "User has changed flight modes - aborting follow-me"
92+
print("User has changed flight modes - aborting follow-me")
9293
break
9394

9495
# Read the GPS state from the laptop
95-
gpsd.next()
96+
next(gpsd)
9697

9798
# Once we have a valid location (see gpsd documentation) we can start moving our vehicle around
9899
if (gpsd.valid & gps.LATLON_SET) != 0:
99100
altitude = 30 # in meters
100101
dest = LocationGlobalRelative(gpsd.fix.latitude, gpsd.fix.longitude, altitude)
101-
print "Going to: %s" % dest
102+
print("Going to: %s" % dest)
102103

103104
# A better implementation would only send new waypoints if the position had changed significantly
104105
vehicle.simple_goto(dest)
@@ -108,11 +109,11 @@ def arm_and_takeoff(aTargetAltitude):
108109
time.sleep(2)
109110

110111
except socket.error:
111-
print "Error: gpsd service does not seem to be running, plug in USB GPS or run run-fake-gps.sh"
112+
print("Error: gpsd service does not seem to be running, plug in USB GPS or run run-fake-gps.sh")
112113
sys.exit(1)
113114

114115
#Close vehicle object before exiting script
115-
print "Close vehicle object"
116+
print("Close vehicle object")
116117
vehicle.close()
117118

118119
# Shut down simulator if it was started.

examples/gcs/microgcs.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
"""
55
© Copyright 2015-2016, 3D Robotics.
66
"""
7+
from __future__ import print_function
78
#
89
# This is a small example of the python drone API - an ultra minimal GCS
910
#
@@ -32,7 +33,7 @@
3233
connection_string = sitl.connection_string()
3334

3435
# Connect to the Vehicle
35-
print 'Connecting to vehicle on: %s' % connection_string
36+
print('Connecting to vehicle on: %s' % connection_string)
3637
vehicle = connect(connection_string, wait_ready=True)
3738

3839
def setMode(mode):

0 commit comments

Comments
 (0)