Skip to content

Commit c633a5c

Browse files
cclaussmrpollo
cclauss
authored andcommitted
Python 3: define basestring, use bytes.decode() (#705)
* Run flake8 tests against both Python 2 and 3 * Python 3: from past.builtins import basestring * Python 3: from __future__ import print_function * Update simple_goto.py * flake8 --max-line-length=127 * Python 3: from __future__ import print_function * Separate flak8 run just for syntax errors
1 parent 4d05c05 commit c633a5c

File tree

4 files changed

+92
-80
lines changed

4 files changed

+92
-80
lines changed

.travis.yml

Lines changed: 15 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,5 @@
1+
language: python
2+
13
env:
24
global:
35
- SITL_SPEEDUP=10
@@ -7,18 +9,26 @@ python:
79
- 2.7.13
810
- 3.6
911

12+
before_install:
13+
- pip install --upgrade pip
14+
1015
install:
11-
- 'pip install -r requirements.txt'
16+
- pip install -r requirements.txt
17+
- pip install flake8
18+
19+
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
1224

1325
script:
14-
- 'nosetests --debug=nose,nose.importer --debug-log=nose_debug -svx dronekit.test.unit'
15-
- 'nosetests --debug=nose,nose.importer --debug-log=nose_debug -svx dronekit.test.sitl'
26+
- nosetests --debug=nose,nose.importer --debug-log=nose_debug -svx dronekit.test.unit
27+
- nosetests --debug=nose,nose.importer --debug-log=nose_debug -svx dronekit.test.sitl
1628

1729
git:
1830
depth: 10
1931

20-
language: python
21-
2232
notifications:
2333
email: false
2434
webhooks:

dronekit/__init__.py

Lines changed: 19 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -31,23 +31,26 @@
3131
"""
3232

3333
from __future__ import print_function
34-
import monotonic
35-
import time
36-
import socket
37-
import sys
34+
import collections
35+
import copy
36+
import math
3837
import os
38+
import struct
3939
import platform
40-
import re
41-
from dronekit.util import errprinter
42-
from pymavlink import mavutil, mavwp
4340
from queue import Queue, Empty
41+
import re
42+
import socket
43+
import sys
44+
import threading
4445
from threading import Thread
46+
import time
4547
import types
46-
import threading
47-
import math
48-
import struct
49-
import copy
50-
import collections
48+
49+
import monotonic
50+
from past.builtins import basestring
51+
from dronekit.util import errprinter
52+
53+
from pymavlink import mavutil, mavwp
5154
from pymavlink.dialects.v10 import ardupilotmega
5255

5356

@@ -88,7 +91,8 @@ def __init__(self, pitch, yaw, roll):
8891
self.roll = roll
8992

9093
def __str__(self):
91-
return "Attitude:pitch=%s,yaw=%s,roll=%s" % (self.pitch, self.yaw, self.roll)
94+
fmt = '{}:pitch={pitch},yaw={yaw},roll={roll}'
95+
return fmt.format(self.__class__.__name__, **vars(self))
9296

9397

9498
class LocationGlobal(object):
@@ -2747,7 +2751,7 @@ def __len__(self):
27472751

27482752
def __getitem__(self, index):
27492753
if isinstance(index, slice):
2750-
return [self[ii] for ii in xrange(*index.indices(len(self)))]
2754+
return [self[ii] for ii in range(*index.indices(len(self)))]
27512755
elif isinstance(index, int):
27522756
item = self._vehicle._wploader.wp(index + 1)
27532757
if not item:
@@ -2835,7 +2839,7 @@ def connect(ip,
28352839

28362840
@vehicle.on_message('STATUSTEXT')
28372841
def listener(self, name, m):
2838-
status_printer(re.sub(r'(^|\n)', '>>> ', m.text.rstrip()))
2842+
status_printer(re.sub(r'(^|\n)', '>>> ', m.text.decode('utf-8').rstrip()))
28392843

28402844
if _initialize:
28412845
vehicle.initialize(rate=rate, heartbeat_timeout=heartbeat_timeout)

examples/drone_delivery/drone_delivery.py

Lines changed: 27 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -3,39 +3,39 @@
33

44
"""
55
© Copyright 2015-2016, 3D Robotics.
6-
drone_delivery.py:
6+
drone_delivery.py:
77
88
A CherryPy based web application that displays a mapbox map to let you view the current vehicle position and send the vehicle commands to fly to a particular latitude and longitude.
99
1010
Full documentation is provided at http://python.dronekit.io/examples/drone_delivery.html
1111
"""
1212

13+
from __future__ import print_function
1314
import os
1415
import simplejson
1516
import time
16-
from pymavlink import mavutil
17+
1718
from dronekit import connect, VehicleMode, LocationGlobal, LocationGlobalRelative
1819
import cherrypy
19-
from cherrypy.process import wspbus, plugins
2020
from jinja2 import Environment, FileSystemLoader
2121

22-
#Set up option parsing to get connection string
23-
import argparse
22+
# Set up option parsing to get connection string
23+
import argparse
2424
parser = argparse.ArgumentParser(description='Creates a CherryPy based web application that displays a mapbox map to let you view the current vehicle position and send the vehicle commands to fly to a particular latitude and longitude. Will start and connect to SITL if no connection string specified.')
25-
parser.add_argument('--connect',
26-
help="vehicle connection target string. If not specified, SITL is automatically started and used.")
25+
parser.add_argument('--connect',
26+
help="vehicle connection target string. If not specified, SITL is automatically started and used.")
2727
args = parser.parse_args()
2828

29-
connection_string=args.connect
29+
connection_string = args.connect
3030

31-
#Start SITL if no connection string specified
31+
# Start SITL if no connection string specified
3232
if not connection_string:
3333
import dronekit_sitl
3434
sitl = dronekit_sitl.start_default()
3535
connection_string = sitl.connection_string()
3636

37-
local_path=os.path.dirname(os.path.abspath(__file__))
38-
print "local path: %s" % local_path
37+
local_path = os.path.dirname(os.path.abspath(__file__))
38+
print("local path: %s" % local_path)
3939

4040

4141
cherrypy_conf = {
@@ -89,11 +89,10 @@ def takeoff(self):
8989
self._log("Taking off")
9090
self.vehicle.simple_takeoff(30.0)
9191

92-
9392
def arm(self, value=True):
9493
if value:
9594
self._log('Waiting for arming...')
96-
self.vehicle.armed = True
95+
self.vehicle.armed = True
9796
while not self.vehicle.armed:
9897
time.sleep(.1)
9998
else:
@@ -104,11 +103,9 @@ def _run_server(self):
104103
# Start web server if enabled
105104
cherrypy.tree.mount(DroneDelivery(self), '/', config=cherrypy_conf)
106105

107-
cherrypy.config.update({
108-
'server.socket_port': 8080,
109-
'server.socket_host': '0.0.0.0',
110-
'log.screen': None
111-
})
106+
cherrypy.config.update({'server.socket_port': 8080,
107+
'server.socket_host': '0.0.0.0',
108+
'log.screen': None})
112109

113110
print('''Server is bound on all addresses, port 8080
114111
You may connect to it using your web broser using a URL looking like this:
@@ -153,28 +150,26 @@ def location_callback(self, vehicle, name, location):
153150
self.current_location = location.global_relative_frame
154151

155152
def _log(self, message):
156-
print "[DEBUG]: {0}".format(message)
153+
print("[DEBUG]: {0}".format(message))
154+
157155

158156
class Templates:
159157
def __init__(self, home_coords):
160158
self.home_coords = home_coords
161159
self.options = self.get_options()
162-
self.environment = Environment(loader=FileSystemLoader( local_path + '/html'))
160+
self.environment = Environment(loader=FileSystemLoader(local_path + '/html'))
163161

164162
def get_options(self):
165-
return {
166-
'width': 670,
163+
return {'width': 670,
167164
'height': 470,
168165
'zoom': 13,
169166
'format': 'png',
170167
'access_token': 'pk.eyJ1Ijoia2V2aW4zZHIiLCJhIjoiY2lrOGoxN2s2MDJzYnR6a3drbTYwdGxmMiJ9.bv5u7QgmcJd6dZfLDGoykw',
171168
'mapid': 'kevin3dr.n56ffjoo',
172169
'home_coords': self.home_coords,
173-
'menu': [
174-
{'name': 'Home', 'location': '/'},
175-
{'name': 'Track', 'location': '/track'},
176-
{'name': 'Command', 'location': '/command'}
177-
],
170+
'menu': [{'name': 'Home', 'location': '/'},
171+
{'name': 'Track', 'location': '/track'},
172+
{'name': 'Command', 'location': '/command'}],
178173
'current_url': '/',
179174
'json': ''
180175
}
@@ -198,9 +193,10 @@ def command(self, current_coords):
198193
return self.get_template('command')
199194

200195
def get_template(self, file_name):
201-
template = self.environment.get_template( file_name + '.html')
196+
template = self.environment.get_template(file_name + '.html')
202197
return template.render(options=self.options)
203198

199+
204200
class DroneDelivery(object):
205201
def __init__(self, drone):
206202
self.drone = drone
@@ -230,13 +226,13 @@ def track(self, lat=None, lon=None):
230226

231227

232228
# Connect to the Vehicle
233-
print 'Connecting to vehicle on: %s' % connection_string
229+
print('Connecting to vehicle on: %s' % connection_string)
234230
vehicle = connect(connection_string, wait_ready=True)
235231

236-
print 'Launching Drone...'
232+
print('Launching Drone...')
237233
Drone().launch()
238234

239-
print 'Waiting for cherrypy engine...'
235+
print('Waiting for cherrypy engine...')
240236
cherrypy.engine.block()
241237

242238
if not args.connect:

examples/simple_goto/simple_goto.py

Lines changed: 31 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -10,30 +10,31 @@
1010
Full documentation is provided at http://python.dronekit.io/examples/simple_goto.html
1111
"""
1212

13-
from dronekit import connect, VehicleMode, LocationGlobalRelative
13+
from __future__ import print_function
1414
import time
15+
from dronekit import connect, VehicleMode, LocationGlobalRelative
1516

1617

17-
#Set up option parsing to get connection string
18-
import argparse
18+
# Set up option parsing to get connection string
19+
import argparse
1920
parser = argparse.ArgumentParser(description='Commands vehicle using vehicle.simple_goto.')
20-
parser.add_argument('--connect',
21-
help="Vehicle connection target string. If not specified, SITL automatically started and used.")
21+
parser.add_argument('--connect',
22+
help="Vehicle connection target string. If not specified, SITL automatically started and used.")
2223
args = parser.parse_args()
2324

2425
connection_string = args.connect
2526
sitl = None
2627

2728

28-
#Start SITL if no connection string specified
29+
# Start SITL if no connection string specified
2930
if not connection_string:
3031
import dronekit_sitl
3132
sitl = dronekit_sitl.start_default()
3233
connection_string = sitl.connection_string()
3334

3435

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

3940

@@ -42,62 +43,63 @@ def arm_and_takeoff(aTargetAltitude):
4243
Arms vehicle and fly to aTargetAltitude.
4344
"""
4445

45-
print "Basic pre-arm checks"
46+
print("Basic pre-arm checks")
4647
# Don't try to arm until autopilot is ready
4748
while not vehicle.is_armable:
48-
print " Waiting for vehicle to initialise..."
49+
print(" Waiting for vehicle to initialise...")
4950
time.sleep(1)
5051

51-
52-
print "Arming motors"
52+
print("Arming motors")
5353
# Copter should arm in GUIDED mode
5454
vehicle.mode = VehicleMode("GUIDED")
55-
vehicle.armed = True
55+
vehicle.armed = True
5656

5757
# Confirm vehicle armed before attempting to take off
58-
while not vehicle.armed:
59-
print " Waiting for arming..."
58+
while not vehicle.armed:
59+
print(" Waiting for arming...")
6060
time.sleep(1)
6161

62-
print "Taking off!"
63-
vehicle.simple_takeoff(aTargetAltitude) # Take off to target altitude
62+
print("Taking off!")
63+
vehicle.simple_takeoff(aTargetAltitude) # Take off to target altitude
6464

65-
# Wait until the vehicle reaches a safe height before processing the goto (otherwise the command
66-
# after Vehicle.simple_takeoff will execute immediately).
65+
# Wait until the vehicle reaches a safe height before processing the goto
66+
# (otherwise the command after Vehicle.simple_takeoff will execute
67+
# immediately).
6768
while True:
68-
print " Altitude: ", vehicle.location.global_relative_frame.alt
69-
#Break and return from function just below target altitude.
70-
if vehicle.location.global_relative_frame.alt>=aTargetAltitude*0.95:
71-
print "Reached target altitude"
69+
print(" Altitude: ", vehicle.location.global_relative_frame.alt)
70+
# Break and return from function just below target altitude.
71+
if vehicle.location.global_relative_frame.alt >= aTargetAltitude * 0.95:
72+
print("Reached target altitude")
7273
break
7374
time.sleep(1)
7475

76+
7577
arm_and_takeoff(10)
7678

77-
print "Set default/target airspeed to 3"
79+
print("Set default/target airspeed to 3")
7880
vehicle.airspeed = 3
7981

80-
print "Going towards first point for 30 seconds ..."
82+
print("Going towards first point for 30 seconds ...")
8183
point1 = LocationGlobalRelative(-35.361354, 149.165218, 20)
8284
vehicle.simple_goto(point1)
8385

8486
# sleep so we can see the change in map
8587
time.sleep(30)
8688

87-
print "Going towards second point for 30 seconds (groundspeed set to 10 m/s) ..."
89+
print("Going towards second point for 30 seconds (groundspeed set to 10 m/s) ...")
8890
point2 = LocationGlobalRelative(-35.363244, 149.168801, 20)
8991
vehicle.simple_goto(point2, groundspeed=10)
9092

9193
# sleep so we can see the change in map
9294
time.sleep(30)
9395

94-
print "Returning to Launch"
96+
print("Returning to Launch")
9597
vehicle.mode = VehicleMode("RTL")
9698

97-
#Close vehicle object before exiting script
98-
print "Close vehicle object"
99+
# Close vehicle object before exiting script
100+
print("Close vehicle object")
99101
vehicle.close()
100102

101103
# Shut down simulator if it was started.
102-
if sitl is not None:
104+
if sitl:
103105
sitl.stop()

0 commit comments

Comments
 (0)