Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 15 additions & 0 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,21 @@ 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
# 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'
Expand Down
12 changes: 9 additions & 3 deletions dronekit/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
"""
Expand Down Expand Up @@ -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):
Expand Down Expand Up @@ -2734,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:
Expand Down Expand Up @@ -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)
Expand Down
53 changes: 26 additions & 27 deletions examples/simple_goto/simple_goto.py
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -14,26 +14,26 @@
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()
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 +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()
2 changes: 1 addition & 1 deletion requirements.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
pymavlink==2.0.6
pymavlink==2.0.8
monotonic==1.2
future==0.15.2
nose==1.3.7
Expand Down