Skip to content

Commit

Permalink
Python 3: define basestring, use bytes.decode() (#705)
Browse files Browse the repository at this point in the history
* 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
  • Loading branch information
cclauss authored and mrpollo committed Apr 21, 2017
1 parent 4d05c05 commit c633a5c
Show file tree
Hide file tree
Showing 4 changed files with 92 additions and 80 deletions.
20 changes: 15 additions & 5 deletions .travis.yml
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
language: python

env:
global:
- SITL_SPEEDUP=10
Expand All @@ -7,18 +9,26 @@ python:
- 2.7.13
- 3.6

before_install:
- pip install --upgrade pip

install:
- 'pip install -r requirements.txt'
- 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 --select=E999 --statistics # syntax errors
- flake8 . --count --exit-zero --max-line-length=127 --statistics

script:
- 'nosetests --debug=nose,nose.importer --debug-log=nose_debug -svx dronekit.test.unit'
- 'nosetests --debug=nose,nose.importer --debug-log=nose_debug -svx dronekit.test.sitl'
- nosetests --debug=nose,nose.importer --debug-log=nose_debug -svx dronekit.test.unit
- nosetests --debug=nose,nose.importer --debug-log=nose_debug -svx dronekit.test.sitl

git:
depth: 10

language: python

notifications:
email: false
webhooks:
Expand Down
34 changes: 19 additions & 15 deletions dronekit/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,23 +31,26 @@
"""

from __future__ import print_function
import monotonic
import time
import socket
import sys
import collections
import copy
import math
import os
import struct
import platform
import re
from dronekit.util import errprinter
from pymavlink import mavutil, mavwp
from queue import Queue, Empty
import re
import socket
import sys
import threading
from threading import Thread
import time
import types
import threading
import math
import struct
import copy
import collections

import monotonic
from past.builtins import basestring
from dronekit.util import errprinter

from pymavlink import mavutil, mavwp
from pymavlink.dialects.v10 import ardupilotmega


Expand Down Expand Up @@ -88,7 +91,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):
Expand Down Expand Up @@ -2747,7 +2751,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:
Expand Down Expand Up @@ -2835,7 +2839,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)
Expand Down
58 changes: 27 additions & 31 deletions examples/drone_delivery/drone_delivery.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,39 +3,39 @@

"""
© Copyright 2015-2016, 3D Robotics.
drone_delivery.py:
drone_delivery.py:
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.
Full documentation is provided at http://python.dronekit.io/examples/drone_delivery.html
"""

from __future__ import print_function
import os
import simplejson
import time
from pymavlink import mavutil

from dronekit import connect, VehicleMode, LocationGlobal, LocationGlobalRelative
import cherrypy
from cherrypy.process import wspbus, plugins
from jinja2 import Environment, FileSystemLoader

#Set up option parsing to get connection string
import argparse
# Set up option parsing to get connection string
import argparse
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.')
parser.add_argument('--connect',
help="vehicle connection target string. If not specified, SITL is automatically started and used.")
parser.add_argument('--connect',
help="vehicle connection target string. If not specified, SITL is automatically started and used.")
args = parser.parse_args()

connection_string=args.connect
connection_string = args.connect

#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()
connection_string = sitl.connection_string()

local_path=os.path.dirname(os.path.abspath(__file__))
print "local path: %s" % local_path
local_path = os.path.dirname(os.path.abspath(__file__))
print("local path: %s" % local_path)


cherrypy_conf = {
Expand Down Expand Up @@ -89,11 +89,10 @@ def takeoff(self):
self._log("Taking off")
self.vehicle.simple_takeoff(30.0)


def arm(self, value=True):
if value:
self._log('Waiting for arming...')
self.vehicle.armed = True
self.vehicle.armed = True
while not self.vehicle.armed:
time.sleep(.1)
else:
Expand All @@ -104,11 +103,9 @@ def _run_server(self):
# Start web server if enabled
cherrypy.tree.mount(DroneDelivery(self), '/', config=cherrypy_conf)

cherrypy.config.update({
'server.socket_port': 8080,
'server.socket_host': '0.0.0.0',
'log.screen': None
})
cherrypy.config.update({'server.socket_port': 8080,
'server.socket_host': '0.0.0.0',
'log.screen': None})

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

def _log(self, message):
print "[DEBUG]: {0}".format(message)
print("[DEBUG]: {0}".format(message))


class Templates:
def __init__(self, home_coords):
self.home_coords = home_coords
self.options = self.get_options()
self.environment = Environment(loader=FileSystemLoader( local_path + '/html'))
self.environment = Environment(loader=FileSystemLoader(local_path + '/html'))

def get_options(self):
return {
'width': 670,
return {'width': 670,
'height': 470,
'zoom': 13,
'format': 'png',
'access_token': 'pk.eyJ1Ijoia2V2aW4zZHIiLCJhIjoiY2lrOGoxN2s2MDJzYnR6a3drbTYwdGxmMiJ9.bv5u7QgmcJd6dZfLDGoykw',
'mapid': 'kevin3dr.n56ffjoo',
'home_coords': self.home_coords,
'menu': [
{'name': 'Home', 'location': '/'},
{'name': 'Track', 'location': '/track'},
{'name': 'Command', 'location': '/command'}
],
'menu': [{'name': 'Home', 'location': '/'},
{'name': 'Track', 'location': '/track'},
{'name': 'Command', 'location': '/command'}],
'current_url': '/',
'json': ''
}
Expand All @@ -198,9 +193,10 @@ def command(self, current_coords):
return self.get_template('command')

def get_template(self, file_name):
template = self.environment.get_template( file_name + '.html')
template = self.environment.get_template(file_name + '.html')
return template.render(options=self.options)


class DroneDelivery(object):
def __init__(self, drone):
self.drone = drone
Expand Down Expand Up @@ -230,13 +226,13 @@ def track(self, lat=None, lon=None):


# 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)

print 'Launching Drone...'
print('Launching Drone...')
Drone().launch()

print 'Waiting for cherrypy engine...'
print('Waiting for cherrypy engine...')
cherrypy.engine.block()

if not args.connect:
Expand Down
60 changes: 31 additions & 29 deletions examples/simple_goto/simple_goto.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,30 +10,31 @@
Full documentation is provided at http://python.dronekit.io/examples/simple_goto.html
"""

from dronekit import connect, VehicleMode, LocationGlobalRelative
from __future__ import print_function
import time
from dronekit import connect, VehicleMode, LocationGlobalRelative


#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()
connection_string = sitl.connection_string()


# 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)


Expand All @@ -42,62 +43,63 @@ 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
# after Vehicle.simple_takeoff will execute immediately).
# 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()

0 comments on commit c633a5c

Please sign in to comment.