Added MamboDrone Code test

This commit is contained in:
ThomasFransolet 2019-07-27 20:04:39 +02:00
parent 8b01e1e10c
commit 0b08ffcf51
81 changed files with 23959 additions and 0 deletions

View File

@ -0,0 +1,105 @@
# Byte-compiled / optimized / DLL files
__pycache__/
*.py[cod]
*$py.class
# C extensions
*.so
# Distribution / packaging
.Python
build/
develop-eggs/
dist/
downloads/
eggs/
.eggs/
lib/
lib64/
parts/
sdist/
var/
wheels/
*.egg-info/
.installed.cfg
*.egg
MANIFEST
# PyInstaller
# Usually these files are written by a python script from a template
# before PyInstaller builds the exe, so as to inject date/other infos into it.
*.manifest
*.spec
# Installer logs
pip-log.txt
pip-delete-this-directory.txt
# Unit test / coverage reports
htmlcov/
.tox/
.coverage
.coverage.*
.cache
nosetests.xml
coverage.xml
*.cover
.hypothesis/
# Translations
*.mo
*.pot
# Django stuff:
*.log
.static_storage/
.media/
local_settings.py
# Flask stuff:
instance/
.webassets-cache
# Scrapy stuff:
.scrapy
# Sphinx documentation
docs/_build/
# PyBuilder
target/
# Jupyter Notebook
.ipynb_checkpoints
# pyenv
.python-version
# celery beat schedule file
celerybeat-schedule
# SageMath parsed files
*.sage.py
# Environments
.env
.venv
env/
venv/
ENV/
env.bak/
venv.bak/
# Spyder project settings
.spyderproject
.spyproject
# Rope project settings
.ropeproject
# mkdocs documentation
/site
# mypy
.mypy_cache/

View File

@ -0,0 +1,21 @@
MIT License
Copyright (c) 2017 amymcgovern
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.

View File

@ -0,0 +1,2 @@
include pyparrot/commandsandsensors/*.xml
include pyparrot/utils/*.sdp

View File

@ -0,0 +1,75 @@
# pyparrot
Python interface for Parrot Drones
pyparrot was designed and implemented by Dr. Amy McGovern to program Parrot Mambo and Parrot Bebop 2
drones using python. This interface was developed to teach K-20 STEM concepts
(programming, math, and more) by programming a drone to fly autonomously.
Anyone can use it who is interested in autonomous drone programming!
# Installation, Quick-start, Documentation, FAQs
Extensive documentation is available at [https://pyparrot.readthedocs.io](https://pyparrot.readthedocs.io)
# Major updates and releases:
* 06/20/2018: Version 1.5.19: Updated the new DroneVisionGUI to not segfault with invalid images
* 06/20/2019: Version 1.5.18 Added the ability for DroneVisionGUI to have two windows, one for video and one for user images. Note that the initial geometry isn't quite right but resizing the window makes it work.
* 04/17/2019: Updated documentation to include workshop slides from April 2019 workshop. Restructured coursework directory to contain AI projects and workshop slides.
* 03/13/2019: Version 1.5.17: Required PCMD commands to be ints (PR from daanzu)
* 03/12/2019: Version 1.5.16: Added a disco fix (PR from proff) and fixed IP address fix (PR from daanzu)
* 03/03/2019: Version 1.5.15: Added disco into wifi connected devices (thank you proff for the PR)
* 03/02/2019: Version 1.5.14: Fixed ffmpeg vision bug where it wasn't properly killing the ffmpeg subprocess
* 03/02/2019: Version 1.5.13: Added removal of old files in images directory by default to ffmpeg vision (can turn it off with a parameter)
* 02/19/2019: Version 1.5.12: Added pull request of wificonnection parameters and added ability to specify IP address (default uses mDNS still)
* 01/25/2019: Version 1.5.11: Added an example of using a cv2.namedWindow to show two vision windows (but it has issues on mac os 10.14 because it isn't a main thread)
* 10/29/2018: Version 1.5.10: Updated the groundcam to not break on disconnect with BLE. Also have updated documentation with slides from workshop and windows FAQs.
* 10/21/2018: Version 1.5.9: Fixed the wifiConnection without mDNS to work for Bebop (mDNS still works on bebop!). Verified that mambo and bebop work now with latest firmware.
* 10/19/2018: Version 1.5.8: Parrot broke mDNS in firmware 3.0.26 (and ftp is still broken). Disabled the groundcam and hard-coded the IP address and ports for the mambo. Long term we want mDNS back. tested backwards compatiblity on older firmware and it works.
* 10/13/2018: Version 1.5.7: Parrot released a security update/firmware upgrade to 3.0.25 that breaks ftp login for Mambo. pyparrot now allows the mambo to still connect without errors but the groundcam will not work until we hear from parrot. Also added example for joystick for the parrot swing from victor804
* 10/05/2018: Version 1.5.6: Removed a bug in the library on pypi where an old file was hanging around
* 09/19/2018: Version 1.5.5: Added joystink demo for swing (thanks Victor804)
* 09/06/2018: Version 1.5.4: Removed wait in indoor mode for bebop 1
* 09/06/2018: Version 1.5.3: Added indoor mode for bebop 1
* 8/30/2018: Version 1.5.2: Updated camera pan_tilt for Bebop 1 (thanks Victor804)
* 8/21/2018: Version 1.5.1: fixed small fix for typo in minidrones (for swing)
* 8/18/2018: Version 1.5.0: major update to suppport parrot swing drones (thank you Victor804). This does break a small backwards compatibility in that you need to import Mambo from Minidrone instead of Mambo. Everything else remains the same.
* 8/9/2018: Version 1.4.31: hard-coded name for vision stream on windows
* 8/9/2018: Version 1.4.30: fixed vision bug in windows using VLC (tempfile issues) and also made fps a parameter for VLC vision
* 7/16/2018: Version 1.4.29: added bebop user sensor callback function to match mambo
* 7/15/2018: Version 1.4.28: added bebop battery state to default state variables (was in the dictionary only before)
* 7/13/2018: Version 1.4.27: updated Mambo() initialization to not require address for wifi mode and also updated groundcam demo for Mambo
* 7/12/2018: Version 1.4.26: added new Bebop commands (mostly setting max limits for the bebop)
* 7/11/2018: Version 1.4.25: fixed groundcam pictures for Mambo
* 7/8/2018: Version 1.4.24: switched tempfile to back to NamedTemporaryFile in DroneVisionGUI due to OS incompatibilities
* 7/8/2018: Version 1.4.23: switched tempfile to SpooledTemporaryFile in DroneVisionGUI to make it faster (uses memory instead of disk)
* 7/6/2018: Version 1.4.22: Added a wait in flat_trim for Bebop until it is received (optional)
* 7/5/2018: Version 1.4.21: Added max_tilt and max_altitude to the Bebop commands.
* 7/4/2018: Version 1.4.20: While move_relative is implemented, it seems to have a firmware bug so DO NOT USE.
* 7/4/2018: Version 1.4.19: Added move_relative command to the Bebop API. For now, only dx, dy, and dradians should be used as there seems to be a bug internal to the firmware on dz.
* 6/17/2018: Version 1.4.18 Added landed button status to the Drone Vision GUI for safety in user code
* 6/16/2018: Version 1.4.17 Added flat trim to mambo also
* 6/16/2018: Version 1.4.16 Added flat trim to bebop
* 6/15/2018: Version 1.4.15 Removed a stray print, updated documentation, cast turn_degrees arguments to an int in Mambo.
* 6/11/2018: Version 1.4.14 Added bebop sdp file to the release on pip
* 6/7/2018: Version 1.4.13 Fixed duration in PCMD to use milliseconds instead of integer seconds
* 6/7/2018: Version 1.4.12 Added an option to fly_direct to allow the command to be sent once
* 6/6/2018: Version 1.4.11 Fixed a stray import statment not fixed from the move to pip
* 5/31/2018: Version 1.4.10 Documentation updated significantly and moved to readthedocs
* 5/30/2018: Version 1.4.7 and 1.4.8 and 1.4.9 fixed scripts location to release find_mambo script and added readthedocs documents
* 5/29/2018: Version 1.4.6 Accepted fixes for Bebop 1 compatibility
* 5/28/2018: Version 1.4.5 Fixed imports for new pypi structure and added xml files to pypi.
* 5/25/2018: Version 1.4.3. Uploaded to pypi so pyparrot can now be installed directory from pip. Updated documentation for new vision.
* 5/23/2018: Updated function (contributed) to download pictures from Mambo's downward facing camera.
* 3/25/2018: Added DroneVisionGUI which is a version of the vision that shows the video stream (for Bebop or Mambo) in real time.
* 2/22/2018: Version 1.3.2. Updated DroneVision to make the vision processing faster. Interface changed to only have the user call open_vision and close_vision (and not start_video_buffering)
* 2/10/2018: Version 1.3.1. Updated DroneVision to work on Windows.
* 2/8/2018: Version 1.3. Vision is working for both the Mambo and Bebop in a general interface called DroneVision. Major documenation updates as well.
* 2/6/2018: Updated Mambo to add speed settings for tilt & vertical. Needed for class.
* 2/4/2018: Unofficial updates to add ffmpeg support to the vision (will make an official release with examples soon)
* 12/09/2017: Version 1.2. Mambo now gives estimated orientation using quaternions. Bebop now streams vision, which is accessible via VLC or other video clients. Coming soon: opencv hooks into the vision.
* 12/02/2017: Version 1.1. Fixed sensors with multiple values for Mambo and Bebop.
* 11/26/2017: Initial release, version 1.0. Working wifi and BLE for Mambo, initial flight for Bebop.
# Programming and using your drones responsibly
It is your job to program and use your drones responsibly! We are not responsible for any losses or damages of your drones or injuries. Please fly safely and obey all laws.

View File

@ -0,0 +1,322 @@
"""
GUI for AI class using drones. Allows you to quickly create a map of
a room with obstacles for navigation and search.
Amy McGovern dramymcgovern@gmail.com
"""
from tkinter import *
import numpy as np
from tkinter import filedialog
import os
import pickle
class DroneGUI:
def __init__(self):
self.root = Tk()
self.room_map = None
self.obstacle_ids = None
self.factor = None
self.obstacle_color = "#7575a3"
self.goal_color = "green"
self.start_color = "red"
self.start_id = 2
self.goal_id = 3
self.obstacle_id = 1
def translate_click(self, event):
"""
Translate the click event into room coordinates and map coordinates
:param event:
:return:
"""
print("clicked at", event.x, event.y)
center_x = event.x
center_y = event.y
# calculate the lower left corner of the box
factor = 10 * self.scale_val
lower_x = int(center_x / factor) * factor
lower_y = int(center_y / factor) * factor
#print("lower x and y are ", lower_x, lower_y)
# translate the click into the map
map_x = int(center_x / self.factor)
map_y = self.room_map.shape[1] - int(center_y / self.factor) - 1
#print("map x and y are ", map_x, map_y)
return (center_x, center_y, lower_x, lower_y, map_x, map_y)
def toggle_obstacle_click(self, event):
"""
Toggle an obstacle with left button clicks
:param event: the tkinter event
:return: nothing
"""
(center_x, center_y, lower_x, lower_y, map_x, map_y) = self.translate_click(event)
if (self.room_map[map_x, map_y] == 0):
self.draw_obstacle(lower_x,lower_y, size=self.factor, color=self.obstacle_color, map_x=map_x, map_y=map_y)
self.room_map[map_x, map_y] = self.obstacle_id
else:
#print("Deleting obstacle ", self.obstacle_ids[map_x, map_y])
self.clear_obstacle(map_x, map_y)
self.room_map[map_x, map_y] = 0
def change_obstacle_type_click(self, event):
"""
Right click brings up a menu to let you choose what kind of obstacle this is
:param event:
:return:
"""
print("In popup menu")
popup_menu = Menu(self.root, tearoff=0)
popup_menu.add_command(label="Set to start", command=lambda: self.draw_start_click(event))
popup_menu.add_command(label="Set to goal", command=lambda: self.draw_goal_click(event))
popup_menu.add_command(label="Remove", command=lambda: self.toggle_obstacle_click(event))
popup_menu.post(event.x, event.y)
def draw_goal_click(self, event):
"""
Draw a green box for a goal at button 1 clicks
:param event:
:return:
"""
(center_x, center_y, lower_x, lower_y, map_x, map_y) = self.translate_click(event)
# clear whatever was there
self.clear_obstacle(map_x, map_y)
self.room_map[map_x, map_y] = 0
# and save the click into the map
self.room_map[map_x, map_y] = self.goal_id
self.draw_obstacle(lower_x,lower_y, self.factor, color=self.goal_color, map_x=map_x, map_y=map_y)
def draw_start_click(self, event):
"""
Draw a red box for the start
:param event:
:return:
"""
(center_x, center_y, lower_x, lower_y, map_x, map_y) = self.translate_click(event)
# clear whatever was there
self.clear_obstacle(map_x, map_y)
self.room_map[map_x, map_y] = 0
# and save the click into the map
self.room_map[map_x, map_y] = self.start_id
self.draw_obstacle(lower_x,lower_y, self.factor, color=self.start_color, map_x=map_x, map_y=map_y)
def draw_obstacle(self, x, y, size, color, map_x, map_y):
# draw the rectangle
obs_id = self.room_canvas.create_rectangle(x, y, x + size, y + size, fill=color)
#print("Obstacle id is ", obs_id)
self.obstacle_ids[map_x, map_y] = obs_id
def clear_obstacle(self, map_x, map_y):
# draw the rectangle
self.room_canvas.delete(self.obstacle_ids[map_x, map_y])
self.obstacle_ids[map_x, map_y] = 0
def set_scale(self):
try:
self.scale_val = int(self.scale.get())
except:
self.scale_val = 1
# set the factor used for drawing translations
self.factor = 10 * self.scale_val
def create_room(self):
"""
Create the window with the room grid
Uses the scale parameter set from the first gui window to decide how big the boxes are (scale must be an int)
Draws a grid with black lines every 10 * scale pixels (e.g. every decimeter) and then draws a thicker
line every meter (e.g. every 10 lines)
:return:
"""
length = float(self.length.get())
height = float(self.height.get())
# initialize the internal map
self.room_map = np.zeros((int(length * 10), int(height * 10)))
self.obstacle_ids = np.zeros((int(length * 10), int(height * 10)), dtype='int')
print(self.room_map.shape)
print("Length is %0.1f and height is %0.1f" % (length, height))
self.set_scale()
self.draw_room(length, height)
def draw_room(self, length, height):
# each pixel is scale * 1 cm so multiply by 100 to get the width/height from the meters
canvas_width = int(length * 100 * self.scale_val)
canvas_height = int(height * 100 * self.scale_val)
# create the blank canvas
room = Toplevel(self.root)
# put the menu into the room
# menu code mostly from
# https://www.python-course.eu/tkinter_menus.php
menu = Menu(room)
room.config(menu=menu)
filemenu = Menu(menu)
menu.add_cascade(label="File", menu=filemenu)
filemenu.add_command(label="Save Map", command=self.save_file_menu)
filemenu.add_separator()
filemenu.add_command(label="Exit", command=self.root.quit)
helpmenu = Menu(menu)
menu.add_cascade(label="Help", menu=helpmenu)
helpmenu.add_command(label="About...", command=self.about_menu)
# draw the room
self.room_canvas = Canvas(room, width=canvas_width, height=canvas_height, bg="#ffffe6")
self.room_canvas.pack()
# how to draw a checkered canvas from
# https://www.python-course.eu/tkinter_canvas.php
# vertical lines at an interval of "line_distance" pixel
line_distance = 10 * self.scale_val
for x in range(line_distance, canvas_width, line_distance):
if (x % (line_distance * 10) == 0):
self.room_canvas.create_line(x, 0, x, canvas_height, fill="red", width=2)
else:
self.room_canvas.create_line(x, 0, x, canvas_height, fill="black")
# horizontal lines at an interval of "line_distance" pixel
for y in range(line_distance, canvas_height, line_distance):
if (y % (line_distance * 10) == 0):
self.room_canvas.create_line(0, y, canvas_width, y, fill="red", width=2)
else:
self.room_canvas.create_line(0, y, canvas_width, y, fill="black")
# bind the button clicks to draw out the map
self.room_canvas.bind("<Button-1>", self.toggle_obstacle_click)
self.room_canvas.bind("<Button-2>", self.change_obstacle_type_click)
# add in the obstacles (if any exist already)
(xs, ys) = np.nonzero(self.room_map)
factor = 10 * self.scale_val
for i, x in enumerate(xs):
y = ys[i]
lower_x = x * factor
lower_y = (self.room_map.shape[1] - y - 1) * factor
if (self.room_map[x, y] == 1):
self.draw_obstacle(lower_x, lower_y, factor, color="#7575a3", map_x=x, map_y=y)
elif (self.room_map[x, y] == 2):
self.draw_obstacle(lower_x, lower_y, factor, color="red", map_x=x, map_y=y)
elif (self.room_map[x, y] == 3):
self.draw_obstacle(lower_x, lower_y, factor, color="green", map_x=x, map_y=y)
def draw_map_from_file(self):
width = self.room_map.shape[1] / 10.0
length = self.room_map.shape[0] /10.0
#print("length and width of loaded room are ", length,width)
#print("Scale is ", self.scale_val)
self.draw_room(length, width)
def open_file_menu(self):
"""
Load a map from a file
:return:
"""
filename = filedialog.askopenfilename(initialdir=os.getcwd(),
title="Select map file",
filetypes=(("map files", "*.map"), ("all files", "*.*")))
fp = open(filename, "rb")
self.scale_val = pickle.load(fp)
self.room_map = pickle.load(fp)
#print("scale val is ", self.scale_val)
#print("room map is ", self.room_map)
fp.close()
self.draw_map_from_file()
def save_file_menu(self):
"""
Bring up a save file dialog and then save
:return:
"""
filename = filedialog.asksaveasfile(initialdir=os.getcwd(),
title="Save map file",
defaultextension=".map")
print("saving to ", filename.name)
fp = open(filename.name, "wb")
pickle.dump(self.scale_val, fp)
pickle.dump(self.room_map, fp)
fp.close()
def about_menu(self):
pass
def draw_initial_gui(self):
"""
Draws the intial GUI that lets you make a new room
or load one from a file
:return:
"""
# menu code mostly from
# https://www.python-course.eu/tkinter_menus.php
menu = Menu(self.root)
self.root.config(menu=menu)
filemenu = Menu(menu)
menu.add_cascade(label="File", menu=filemenu)
filemenu.add_command(label="Open Map", command=self.open_file_menu)
filemenu.add_separator()
filemenu.add_command(label="Exit", command=self.root.quit)
helpmenu = Menu(menu)
menu.add_cascade(label="Help", menu=helpmenu)
helpmenu.add_command(label="About...", command=self.about_menu)
# draw the request to create a new room
Label(self.root, text="Enter the size of the room you are flying in (decimals to tenths)").grid(row=0, columnspan=2)
Label(self.root, text="Length (x) (meters)").grid(row=1)
Label(self.root, text="Height (y) (meters)").grid(row=2)
Label(self.root, text="1 cm = _ pixels").grid(row=3)
# the entry boxes
self.length = Entry(self.root)
self.length.grid(row=1, column=1)
self.height = Entry(self.root)
self.height.grid(row=2, column=1)
self.scale = Entry(self.root)
self.scale.grid(row=3, column=1)
# action buttons
Button(self.root, text='Quit', command=self.root.quit).grid(row=4, column=0, pady=4)
Button(self.root, text='Create room', command=self.create_room).grid(row=4, column=1, pady=4)
def go(self):
"""
Start the main GUI loop
:return:
"""
mainloop()
if __name__ == "__main__":
gui = DroneGUI()
gui.draw_initial_gui()
gui.go()

View File

@ -0,0 +1,42 @@
"""
Demo of the groundcam
Mambo takes off, takes a picture and shows a RANDOM frame, not the last one
Author: Valentin Benke, https://github.com/Vabe7
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
#import cv2
addr = "d0:3a:69:b9:e6:5a"
mambo = Mambo(addr, use_wifi=False) #address is None since it only works with WiFi anyway
print("trying to connect to mambo now")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
mambo.smart_sleep(1)
mambo.ask_for_state_update()
mambo.smart_sleep(1)
mambo.safe_takeoff(5)
# take the photo
pic_success = mambo.take_picture()
# need to wait a bit for the photo to show up
mambo.smart_sleep(0.5)
picture_names = mambo.groundcam.get_groundcam_pictures_names() #get list of availible files
print(picture_names)
frame = mambo.groundcam.get_groundcam_picture(picture_names[0],True) #get frame which is the first in the array
#if frame is not None:
#if frame is not False:
#cv2.imshow("Groundcam", frame)
#cv2.waitKey(100)
mambo.safe_land(5)
mambo.disconnect()

View File

@ -0,0 +1,43 @@
"""
Demo the claw for the python interface
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
# you will need to change this to the address of YOUR mambo
mamboAddr = "d0:3a:69:b9:e6:5a"
# make my mambo object
# remember you can't use the claw with the camera installed so this must be BLE connected to work
mambo = Mambo(mamboAddr, use_wifi=False)
print("trying to connect")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
# get the state information
print("sleeping")
mambo.smart_sleep(2)
mambo.ask_for_state_update()
mambo.smart_sleep(2)
print("taking off!")
mambo.safe_takeoff(5)
print("open and close the claw")
mambo.open_claw()
# you have to sleep to let the claw open (it needs time to do it)
mambo.smart_sleep(5)
mambo.close_claw()
# you have to sleep to let the claw close (it needs time to do it)
mambo.smart_sleep(5)
print("landing")
mambo.safe_land(5)
mambo.smart_sleep(5)
print("disconnect")
mambo.disconnect()

View File

@ -0,0 +1,63 @@
"""
Demo the direct flying for the python interface
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
# you will need to change this to the address of YOUR mambo
mamboAddr = "d0:3a:69:b9:e6:5a"
# make my mambo object
# remember to set True/False for the wifi depending on if you are using the wifi or the BLE to connect
mambo = Mambo(mamboAddr, use_wifi=False)
print("trying to connect")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
mambo.smart_sleep(2)
mambo.ask_for_state_update()
mambo.smart_sleep(2)
print("taking off!")
mambo.safe_takeoff(5)
#print("Flying direct: going forward (positive pitch)")
#mambo.fly_direct(roll=0, pitch=50, yaw=0, vertical_movement=0, duration=1)
print("Showing turning (in place) using turn_degrees")
mambo.turn_degrees(90)
mambo.smart_sleep(2)
mambo.turn_degrees(-90)
mambo.smart_sleep(2)
mambo.turn_degrees(180)
mambo.smart_sleep(2)
mambo.turn_degrees(180)
mambo.smart_sleep(2)
#print("Flying direct: yaw")
#mambo.fly_direct(roll=0, pitch=0, yaw=50, vertical_movement=0, duration=1)
#print("Flying direct: going backwards (negative pitch)")
#mambo.fly_direct(roll=0, pitch=-50, yaw=0, vertical_movement=0, duration=0.5)
#print("Flying direct: roll")
#mambo.fly_direct(roll=50, pitch=0, yaw=0, vertical_movement=0, duration=1)
#print("Flying direct: going up")
#mambo.fly_direct(roll=0, pitch=0, yaw=0, vertical_movement=50, duration=1)
#print("Flying direct: going around in a circle (yes you can mix roll, pitch, yaw in one command!)")
#mambo.fly_direct(roll=25, pitch=0, yaw=50, vertical_movement=0, duration=3)
print("landing")
mambo.safe_land(5)
mambo.smart_sleep(5)
print("disconnect")
mambo.disconnect()

View File

@ -0,0 +1,20 @@
# Minimal makefile for Sphinx documentation
#
# You can set these variables from the command line.
SPHINXOPTS =
SPHINXBUILD = python -msphinx
SPHINXPROJ = pyparrot
SOURCEDIR = .
BUILDDIR = _build
# Put it first so that "make" without argument is like "make help".
help:
@$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O)
.PHONY: help Makefile
# Catch-all target: route all unknown targets to Sphinx using the new
# "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS).
%: Makefile
@$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O)

View File

@ -0,0 +1,28 @@
.. title:: About pyparrot
.. about:
About the pyparrot project
==========================
About pyparrot
-----------------
Pyparrot was developed by `Dr. Amy McGovern <http://www.mcgovern-fagg.org/amy/>`_ with the support of
the `University of Oklahoma <https://www.kipr.org>`_ and
the `Kiss Institute for Practical Robotics <https://www.kipr.org>`_. The original goal was to teach children to program
using educational programs like `botball <http://www.botball.org>`_. The pyparrot project has been adopted by groups
around the world and has been used in both K-12 settings and at the university level.
Educational Programs Using pyparrot
-----------------------------------
If you would like to be added to this list, please email dramymcgovern @ gmail.com (without the spaces).
* `Botball <http://www.botball.org>`_
* `University of Oklahoma School of Computer Science <http://www.ou.edu/coe/cs>`_
* `Talenteahaus <http://www.talentehaus.at>`_
* `Tech Garage <https://tech-garage.org>`_
* `St Eugene College <http://www.steugene.qld.edu.au>`_
* `KIPR/botball <http://www.kipr.org/>`_

View File

@ -0,0 +1,164 @@
.. title:: Bebop Commands and Sensors
.. bebopcommands:
Bebop Commands and Sensors
==============================
Bebop commands
--------------
Each of the public commands available to control the bebop is listed below with its documentation.
The code is also well documented and you can also look at the API through readthedocs.
All of the functions preceeded with an underscore are intended to be internal functions and are not listed below.
Creating a Bebop object
^^^^^^^^^^^^^^^^^^^^^^^
``Bebop(drone_type="Bebop2")`` create a Bebop object with an optional drone_type argument that can be used to create
a bebop one or bebop 2 object. Default is Bebop 2. Note, there is limited support for the original bebop since
I do not own one for testing.
Connecting and disconnecting
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
``connect(num_retries)`` connect to the Bebop's wifi services. This performs a handshake.
This can take several seconds to ensure the connection is working.
You can specify a maximum number of re-tries. Returns true if the connection suceeded or False otherwise.
``disconnect()`` disconnect from the wifi connection
Takeoff and landing
^^^^^^^^^^^^^^^^^^^
``takeoff()`` Sends a single takeoff command to the bebop. This is not the recommended method.
``safe_takeoff(timeout)`` This is the recommended method for takeoff. It sends a command and then checks the
sensors (via flying state) to ensure the bebop is actually taking off. Then it waits until the bebop is
flying or hovering to return. It will timeout and return if the time exceeds timeout seconds.
``land()`` Sends a single land command to the bebop. This is not the recommended method.
``safe_land(timeout)`` This is the recommended method to land the bebop. Sends commands
until the bebop has actually reached the landed state. It will timeout and return if the time exceeds timeout seconds.
Flying
^^^^^^
``flip(direction)`` Sends the flip command to the bebop. Valid directions to flip are: front, back, right, left.
``fly_direct(roll, pitch, yaw, vertical_movement, duration)`` Fly the bebop directly using the
specified roll, pitch, yaw, and vertical movements. The commands are repeated for duration seconds.
Note there are currently no sensors reported back to the user to ensure that these are working but hopefully
that is addressed in a future firmware upgrade. Each value ranges from -100 to 100 and is essentially a percentage
and direction of the max_tilt (for roll/pitch) or max_vertical_speed (for vertical movement).
``move_relative(dx, dy, dz, dradians)`` Moves the bebop a relative number of meters in x (forward/backward,
forward is positive), y (right/left, right is positive), dz (up/down, positive is down), and dradians.
If you use this command INDOORS, make sure you either have FULL GPS coverage or NO GPS coverage (e.g. cover the front of the bebop
with tin foil to keep it from getting a lock). If it has mixed coverage, it randomly flies at high speed in random
directions after the command executes. This is a known issue in Parrot's firmware and they state that a fix is coming.
``set_max_altitude(altitude)`` Set the maximum allowable altitude in meters.
The altitude must be between 0.5 and 150 meters.
``set_max_distance(distance)`` Set max distance between the takeoff and the drone in meters.
The distance must be between 10 and 2000 meters.
``enable_geofence(value)`` If geofence is enabled, the drone won't fly over the given max distance.
Valid value: 1 if the drone can't fly further than max distance, 0 if no limitation on the drone should be done.
``set_max_tilt(tilt)`` Set the maximum allowable tilt in degrees for the drone (this limits speed).
The tilt must be between 5 (very slow) and 30 (very fast) degrees.
``set_max_tilt_rotation_speed(speed)`` Set the maximum allowable tilt rotation speed in degree/s.
The tilt rotation speed must be between 80 and 300 degree/s.
``set_max_vertical_speed(speed)`` Set the maximum allowable vertical speed in m/s.
The vertical speed must be between 0.5 and 2.5 m/s.
``set_max_rotation_speed(speed)`` Set the maximum allowable rotation speed in degree/s.
The rotation speed must be between 10 and 200 degree/s.
``set_flat_trim(duration=0)`` Tell the Bebop to run with a flat trim. If duration > 0, waits for the comand to be acknowledged
``set_hull_protection(present)`` Set the presence of hull protection (only for bebop 1).
The value must be 1 if hull protection is present or 0 if not present. This is only useful for the bebop 1.
``set_indoor(is_outdoor)`` Set the bebop 1 (ignored on bebop 2) to indoor or outdoor mode.
The value must be 1 if bebop 1 is outdoors or 0 if it is indoors. This is only useful for the bebop 1.
Pausing or sleeping in a thread safe manner
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
``smart_sleep(seconds)`` This sleeps the number of seconds (which can be a floating point) but wakes for all
wifi notifications. You should use this instead of time.sleep to be consistent with the mambo but it is not
required (whereas time.sleep() will break a mambo using BLE).
Video camera
^^^^^^^^^^^^
``start_video_stream()``: tells the bebop to start streaming the video. These are really intended to be
called within the DroneVision or DroneVisionGUI functions and not directly by the user (but you can call
them directly if you are writing your own vision routines).
``stop_video_stream()``: tells the bebop to stop streaming the video. Same as above: intended to be called
by the DroneVision or DroneVisionGUI routines.
``set_video_stream_mode(mode)``: set the video mode to one of three choices: "low_latency",
"high_reliability", "high_reliability_low_framerate". low_latency is the default.
``pan_tilt_camera(tilt_degrees, pan_degrees)``: Send the command to pan/tilt the camera by the specified number of degrees in pan/tilt.
Note, this only seems to work in small increments. Use pan_tilt_velocity to get the camera to look straight downward.
``pan_tilt_camera_velocity(self, tilt_velocity, pan_velocity, duration=0)``: Send the command to tilt the camera by
the specified number of degrees per second in pan/tilt. This function has two modes. First, if duration is 0,
the initial velocity is sent and then the function returns (meaning the camera will keep moving).
If duration is greater than 0, the command executes for that amount of time and then sends a stop command to
the camera and then returns.
``set_picture_format(format)``: Change the picture format to raw, jpeg, snapshot or jpeg_fisheye.
``set_white_balance(type)``: Change the type of white balance between: auto, tungsten, daylight, cloudy or cool_white.
``set_exposition(value)``: Change the image exposition between -1.5 and 1.5.
``set_saturation(value)``: Change the image saturation between -100 and 100.
``set_timelapse(enable, interval)``: To start a timelapse set enable at 1 and an interval between 8 and 300 sec.
To stop the timelapse just set enable to 0.
``set_video_stabilization(mode)``: Change the video stabilization between 4 modes: roll_pitch, pitch, roll, none.
``set_video_recording(mode)``: Change the video recording mode between quality and time.
``set_video_framerate(framerate)``: Change the video framerate between: 24_FPS, 25_FPS or 30_FPS.
``set_video_resolutions(type)``: Change the video resolutions for stream and rec between rec1080_stream480, rec720_stream720.
Sensor commands
^^^^^^^^^^^^^^^
``ask_for_state_update()`` This sends a request to the bebop to send back ALL states. The data returns
fairly quickly although not instantly. The bebop already has a sensor refresh rate of 10Hz but not all sensors are sent
automatically. If you are looking for a specific sensor that is not automatically sent, you can call this but I don't
recommend sending it over and over. Most of the sensors you need should be sent at either the 10Hz rate or as an event
is called that triggers that sensor.
Bebop sensors
-------------
All of the sensor data that is passed back to the Bebop is saved in a python dictionary. As needed, other variables
are stored outside the dictionary but you can get everything you need from the dictionary itself. All of the data
is stored in the BebopSensors class.
The easiest way to interact with the sensors is to call:
``bebop.set_user_sensor_callback(function, args)``. This sets a user callback function with optional
arguments that is called each time a sensor is updated. The refresh rate on wifi is 10Hz.
The sensors are:
* battery (defaults to 100 and stays at that level until a real reading is received from the drone)
* flying_state: This is updated as frequently as the drone sends it out and can be one of "landed", "takingoff", "hovering", "flying", "landing", "emergency", "usertakeoff", "motor_ramping", "emergency_landing". These are the values as specified in `ardrone3.xml <https://github.com/amymcgovern/pyparrot/blob/master/pyparrot/commandsandsensors/ardrone3.xml>`_.
* sensors_dict: all other sensors are saved by name in a dictionary. The names come from the `ardrone3.xml <https://github.com/amymcgovern/pyparrot/blob/master/pyparrot/commandsandsensors/ardrone3.xml>`_ and `common.xml <https://github.com/amymcgovern/pyparrot/blob/master/pyparrot/commandsandsensors/common.xml>`_.

View File

@ -0,0 +1,179 @@
#!/usr/bin/env python3
# -*- coding: utf-8 -*-
#
# pyparrot documentation build configuration file, created by
# sphinx-quickstart on Tue May 29 13:55:14 2018.
#
# This file is execfile()d with the current directory set to its
# containing dir.
#
# Note that not all possible configuration values are present in this
# autogenerated file.
#
# All configuration values have a default; values that are commented out
# serve to show the default.
# If extensions (or modules to document with autodoc) are in another directory,
# add these directories to sys.path here. If the directory is relative to the
# documentation root, use os.path.abspath to make it absolute, like shown here.
#
import os
import sys
# the mock stuff was borrowed from hagelslag to help make things work on readthedocs
from mock import Mock as MagicMock
class Mock(MagicMock):
@classmethod
def __getattr__(cls, name):
return Mock()
MOCK_MODULES = ['numpy', 'scipy', 'zeroconf', 'cv2', 'untangle', 'bluepy', 'bluepy.btle',
'ipaddress', 'queue', 'http.server', 'PyQt5', 'PyQt5.QtCore', 'PyQt5.QtGui',
'PyQt5.QtWidgets']
sys.modules.update((mod_name, Mock()) for mod_name in MOCK_MODULES)
sys.path.insert(0, os.path.abspath('..'))
# -- General configuration ------------------------------------------------
# If your documentation needs a minimal Sphinx version, state it here.
#
# needs_sphinx = '1.0'
# Add any Sphinx extension module names here, as strings. They can be
# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom
# ones.
extensions = ['sphinx.ext.autodoc',
'sphinx.ext.mathjax',
'sphinx.ext.viewcode']
# Add any paths that contain templates here, relative to this directory.
templates_path = ['_templates']
# The suffix(es) of source filenames.
# You can specify multiple suffix as a list of string:
#
source_suffix = ['.rst', '.md']
#source_suffix = '.rst'
# The master toctree document.
master_doc = 'index'
# General information about the project.
project = 'pyparrot'
copyright = '2018, Amy McGovern'
author = 'Amy McGovern'
# The version info for the project you're documenting, acts as replacement for
# |version| and |release|, also used in various other places throughout the
# built documents.
#
# The short X.Y version.
version = '1.5'
# The full version, including alpha/beta/rc tags.
release = '1.5.3'
# The language for content autogenerated by Sphinx. Refer to documentation
# for a list of supported languages.
#
# This is also used if you do content translation via gettext catalogs.
# Usually you set "language" from the command line for these cases.
language = None
# List of patterns, relative to source directory, that match files and
# directories to ignore when looking for source files.
# This patterns also effect to html_static_path and html_extra_path
exclude_patterns = ['_build', 'Thumbs.db', '.DS_Store']
# The name of the Pygments (syntax highlighting) style to use.
pygments_style = 'sphinx'
# If true, `todo` and `todoList` produce output, else they produce nothing.
todo_include_todos = False
# -- Options for HTML output ----------------------------------------------
# The theme to use for HTML and HTML Help pages. See the documentation for
# a list of builtin themes.
#
html_theme = 'nature'
# Theme options are theme-specific and customize the look and feel of a theme
# further. For a list of options available for each theme, see the
# documentation.
#
# html_theme_options = {}
# Add any paths that contain custom static files (such as style sheets) here,
# relative to this directory. They are copied after the builtin static files,
# so a file named "default.css" will overwrite the builtin "default.css".
html_static_path = ['_static']
# Custom sidebar templates, must be a dictionary that maps document names
# to template names.
#
# This is required for the alabaster theme
# refs: http://alabaster.readthedocs.io/en/latest/installation.html#sidebars
html_sidebars = {}
# -- Options for HTMLHelp output ------------------------------------------
# Output file base name for HTML help builder.
htmlhelp_basename = 'pyparrotdoc'
# -- Options for LaTeX output ---------------------------------------------
latex_elements = {
# The paper size ('letterpaper' or 'a4paper').
#
# 'papersize': 'letterpaper',
# The font size ('10pt', '11pt' or '12pt').
#
# 'pointsize': '10pt',
# Additional stuff for the LaTeX preamble.
#
# 'preamble': '',
# Latex figure (float) alignment
#
# 'figure_align': 'htbp',
}
# Grouping the document tree into LaTeX files. List of tuples
# (source start file, target name, title,
# author, documentclass [howto, manual, or own class]).
latex_documents = [
(master_doc, 'pyparrot.tex', 'pyparrot Documentation',
'Amy McGovern', 'manual'),
]
# -- Options for manual page output ---------------------------------------
# One entry per manual page. List of tuples
# (source start file, name, description, authors, manual section).
man_pages = [
(master_doc, 'pyparrot', 'pyparrot Documentation',
[author], 1)
]
# -- Options for Texinfo output -------------------------------------------
# Grouping the document tree into Texinfo files. List of tuples
# (source start file, target name, title, author,
# dir menu entry, description, category)
texinfo_documents = [
(master_doc, 'pyparrot', 'pyparrot Documentation',
author, 'pyparrot', 'One line description of project.',
'Miscellaneous'),
]

View File

@ -0,0 +1,20 @@
.. title:: Contact the pyparrot developers
.. contact:
Contact the pyparrot developers
===============================
Contribute
----------
We welcome your contributions via bug report or pull request.
* Issue Tracker: `<https://github.com/amymcgovern/pyparrot/issues>`_
* Pull requests: `<https://github.com/amymcgovern/pyparrot/pulls>`_
* Source Code: `<https://github.com/amymcgovern/pyparrot>`_
Support
-------
If you are having issues, please let us know by reporting issues on GitHub using the issue
tracker `<https://github.com/amymcgovern/pyparrot/issues>`_.

View File

@ -0,0 +1,62 @@
.. title:: Frequently Asked Questions
.. faq:
Frequently Asked Questions
====================================
Below is a list of common errors and how to fix them.
Vision isn't showing anything on the minidrone
----------------------------------------------
The Minidrone camera puts itself into a "resting" state after not flying for several minutes. To solve this, you
either need to fly again (a simple takeoff and landing will suffice) or reboot the minidrone and reconnect.
I'm using windows and my drone gives me lots of timeout errors
---------------------------------------------------------------
This is a windows security setting and it can be fixed. Go into your windows firewall settings (control panel,
system and security, allow a program through Windows Firewall) and change the settings
for python.exe to be allowed through the firewall for both home/private networks and public networks. Your sensors will
suddenly be able to send data to your machine and safe_land will start working again as well as any sensors!
My drone does takeoff and landing but nothing else
--------------------------------------------------
Likely you have the remote controller on and attached! For some reason, if the remote is on,
it will allow the python code to takeoff & land but no other commands will work.
Turn off the remote and your code should work fine!
Errors connecting to the drone
------------------------------
There are two common errors that I see when flying. One requires the drone to reboot and one requires the
computer controlling the drone to reboot.
Connection failed
^^^^^^^^^^^^^^^^^
If you fail to connect to the drone, you will see an error message like this:
::
connection failed: did you remember to connect your machine to the Drone's wifi network?
The most likely cause is that you forgot to connect to the drone's wifi. If you tried to connect,
sometimes that connection fails. Try again or let the connection sit for a minute and try your program again.
If you are on the wifi but you get connection refused errors, reboot the drone.
Address in use
^^^^^^^^^^^^^^
The second common error is about the address being in use, as shown below.
::
OSError: [Errno 48] Address already in use
There are two ways to fix this, depending on the issue. It is possible you tried to run a second program while
you still had a first program running. If this is the case, make sure you stop all of your minidrone programs and then
restart only one. If you are not running a second minidrone program, then the solution is to reboot. This sometimes
happens due to the program crashing before it releases the socket.

View File

@ -0,0 +1,13 @@
.. title:: Slides from Workshops Teaching PyParrot
.. gettingstartedslides:
Workshop Materials and Slides
==============================
We have taught several workshops on using pyparrot. As we continue to teach and develop materials for
pyparrot, we will continue to share the curriculum materials. The materials are all stored in the coursework
directory on at `GitHub <https://github.com/amymcgovern/pyparrot/tree/master/coursework>`_ The files in
`ai_class <https://github.com/amymcgovern/pyparrot/tree/master/coursework/ai_class>`_
include the project descriptions for the Spring 2018 AI Class taught by Dr. McGovern using the drones.
The files in `workshop_slides <https://github.com/amymcgovern/pyparrot/tree/master/coursework/workshop_slides>`_
contain the slides from prior workshops including OKlahoma's 2018 and 2019 workshops.

View File

@ -0,0 +1,38 @@
.. pyparrot documentation master file, created by
sphinx-quickstart on Tue May 29 13:16:36 2018.
You can adapt this file completely to your liking, but it should at least
contain the root `toctree` directive.
Welcome to pyparrot's documentation!
====================================
pyparrot was designed by Dr. Amy McGovern to program Parrot Minidrone (primarily Mambo FPV but Swing is also
supported) and Parrot Bebop (1 or 2) drones using Python. This interface was developed to teach kids of all ages (K-20) STEM
concepts (programming, math, and more) by having them program a drone
to fly autonomously. Anyone can use it who is interested in
autonomous drone programming!
Main documentation
==========================
.. toctree::
:maxdepth: 3
installation.rst
quickstartminidrone.rst
quickstartbebop.rst
gettingstartedslides.rst
minidronecommands.rst
bebopcommands.rst
vision.rst
faq.rst
contact.rst
about.rst
license.rst
modules.rst
Indices and tables
==================
* :ref:`modindex` is a good place to start if you want to read API docs
* :ref:`genindex` of ALL functions (warning, this is huge and overwhelming)
* :ref:`search`

View File

@ -0,0 +1,189 @@
.. title:: Installation
.. installation:
Installation
===============
You have two choices for installing pyparrot: using the ``source`` code directly or downloading with ``pip``.
**Note** Pyparrot will only work with python 3. This choice was made because the support for multi-threaded
programs is improved in python 3.
Requirements
------------
The choice of related packages is dependent on your choice of drone (Mambo, Mambo FPV, Bebop 1 or 2, Swing, Anafi) and
to the operating system that you will be using to develop.
Hardware/Drone requirements
^^^^^^^^^^^^^^^^^^^^^^^^^^^
* **Parrot Mambo FPV**: If you have a Mambo FPV (e.g. you have the camera), you can use the wifi interface. The wifi interface will work on Mac, Linux, or Windows.
* **Parrot Mambo Fly or Code**: If you have a Mambo without the camera, you will use the BLE interface. pyparrot currently only supports Linux for BLE. The BLE interface was developed on a Raspberry Pi 3 Model B but it has been tested on other Linux machines.
* **Parrot Swing**: To use the Swing you will use the BLE interface.
* **Parrot Bebop 2**: The Bebop interface was tested on a Bebop 2 using a laptop with wifi (any wifi enabled device should work).
* **Parrot Bebop 1**: A Bebop 1 will also work with any wifi enabled device.
* **Parrot Anafi**: Per the development board, the Anafi should work with very minor changes. I will work to officially suppport it once the SDK from parrot is released for it.
Software requirements
^^^^^^^^^^^^^^^^^^^^^
Software requirements are listed below by type of connection to the drone.
* All drones: Python 3
I use the `<https://www.anaconda.com/download/>`_:: installer and package manager for python. Note, when you
install anaconda, install the Visual Studio option, especially if you have windows. Otherwise you will need to install
Visual Studio separately. The zeroconf package (listed below) requires developer tools because it needs to be compiled.
* All drones: untangle package (this is used to parse the xml files in the parrot SDK)
::
pip install untangle
* Vision: If you intend to process the camera files, you will need to install opencv and then either ffmpeg
or VLC. I installed ffmpeg using brew for the mac but apt-get on linux should also work. For VLC, you MUST install
the actual `VLC <https://www.videolan.org/vlc/index.html`_ program (and not just the library in python)
and it needs to be version 3.0.1 or greater.
* Wifi connection: `zeroconf <https://pypi.python.org/pypi/zeroconf>`_ To install zeroconf software do the following:
::
pip install zeroconf
* BLE connection: pybluez (note this is ONLY for support without the camera!) This is ONLY supported on linux.
To install the BLE software do the following:
::
sudo apt-get install bluetooth
sudo apt-get install bluez
sudo apt-get install python-bluez
Note it is also possible that you will need to install bluepy (if it isn't already there). These commands should do it:
::
sudo apt-get install python-pip libglib2.0-dev
sudo pip install bluepy
sudo apt-get update
Installing From Source
----------------------
First download pyparrot by cloning the repository from `<https://github.com/amymcgovern/pyparrot>`_ The instructions for this are below.
::
git clone https://github.com/amymcgovern/pyparrot
cd pyparrot
Make sure you install the necessary other packages (wifi or BLE, vision, etc) as specified above.
Installing From Pip
-------------------
To install from pip, type
::
pip install pyparrot
Make sure you install the necessary other packages (wifi or BLE, vision, etc) as specified above.
Installation guide for windows users who might need more help
-------------------------------------------------------------
Thank you to @JackdQuinn for contributing this.
Make sure you install **Visual Studio** either using Anaconda or by downloading it from Microsoft. Note that Visual
Studio is free but it is required for compilation of the wifi module zeroconf, and specifically of the netifaces
module that zeroconf requires. It is a very large download if you chose to do it outside of anaconda so you will
want to start that download first.
If you install python without anaconda, when you install choose Special install Python and
click add python to path (this will clear up some command line call issues).
Again, if you chose regular python and not anaconda, you can check installation by typing py in the windows command line.
::
py
Once you are sure that python started, you will want to quit python. type: ``quit()`` to exit python
::
quit()
If you chose to use anaconda, bring up the anaconda menu and open an anaconda prompt to verify that it installed.
The rest of the instructions depend on whether you chose python or anaconda for your installation. If you chose python,
use the windows command prompt for pip. If you chose anaconda, use your anaconda prompt.
If you type the pip command (with no options), it will produce a long list of options. This tells you that you
are at the right command prompt to do the rest of the installation.
**Note, the pip command will not work inside of python.** This is a command prompt command, not a python command.
::
pip
Sometimes pip tells you that it wants to upgrade. For windows, the command is:
::
python -m pip install -U pip
To actually install, use the commands described above (and repeated here).
::
pip install untangle
pip install pyparrot
pip install zeroconf
**Note that visual studio is a requirement for zeroconf**
Testing your install
^^^^^^^^^^^^^^^^^^^^
The first step is to connect your connect your controlling device (laptop, computer, etc) to the wifi for the drone.
Look for a wifi network named Mambo_number where number changes for each drone.
After connection to your drone its time to run code! You can download all the example code from
these docs. Below is a short set of commands of how to run that code.
Run code by cd'ing down to the directory (the folder your python code is in) and running the desired python file from the cmd line
Example:
* open command line either through windows or anaconda (depending on your installation method)
* type: ``cd desktop``
* this will Change your Directory to the desktop
* type: ``dir``
* this will display a list of all the folders (directories) on the desktop
* type: ``cd yourFolderNameHere``
* type: ``dir``
* this will display all the files and folders in the directory
* type: ``py TheNameOfTheFileYouWantToRun.py`` or ``python TheNameOfTheFileYouWantToRun.py``
* When you click enter the file will begin to run, if you are using the demo scripts you should see lots of nice feedback as it changes states. You can use the arrow keys to go through your history of commands which can save you lots of time if your file names are long.
* If you have several connects and disconnects try restarting your computer or resetting your ip (for the more technically inclined)
* If you have crashes where the drone is flipping to one side when it shouldn't check the blades and bumpers. The bumpers can shift after a crash and prevent the blades from spinning, or slow down their spin, which causes unintended flips

View File

@ -0,0 +1,32 @@
.. title:: License
.. license:
License
===============
MIT License
-----------
The project is licensed under the MIT License.
Copyright (c) 2017 amymcgovern
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.

View File

@ -0,0 +1,152 @@
.. title:: Minidrone Commands and Sensors
.. minidronecommands:
Minidrone Commands and Sensors
==============================
Minidrone commands
--------------
Each of the public commands available to control the minidrone is listed below with its documentation.
The code is also well documented and you can also look at the API through readthedocs.
All of the functions preceeded with an underscore are intended to be internal functions and are not listed below.
Creating a Mambo object
^^^^^^^^^^^^^^^^^^^^^^^
``Mambo(address="", use_wifi=True/False)``
create a mambo object with the specific harware address (found using findMinidrone). The use_wifi argument defaults to
False (which means BLE is the default). Set to True to use wifi. You can only use wifi if you have a FPV camera
installed on your Mambo! If you are using wifi, the hardware address argument can be ignored (it defaults to an empty
string).
Creating a Swing object
^^^^^^^^^^^^^^^^^^^^^^^
``Swing(address="")``
create a Swing object with the specific harware address (found using findMinidrone).
Connecting and disconnecting
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
``connect(num_retries)`` connect to the Minidrone either using BLE services and characteristics or wifi
(specified when you created the Mambo object). This can take several seconds to ensure the connection is working.
You can specify a maximum number of re-tries. Returns true if the connection suceeded or False otherwise.
``disconnect()`` disconnect from the BLE or wifi connection
Takeoff and landing
^^^^^^^^^^^^^^^^^^^
``safe_takeoff(timeout)`` This is the recommended method for takeoff. It sends a command and then checks the
sensors (via flying state) to ensure the minidrone is actually taking off. Then it waits until the minidrone is
flying or hovering to return. It will timeout and return if the time exceeds timeout seconds.
``safe_land(timeout)`` This is the recommended method to land the minidrone. Sends commands
until the minidrone has actually reached the landed state. It will timeout and return if the time exceeds timeout seconds.
``takeoff()`` Sends a single takeoff command to the minidrone. This is not the recommended method.
``land()`` Sends a single land command to the minidrone. This is not the recommended method.
``turn_on_auto_takeoff()`` This puts the minidrone in throw mode. When it is in throw mode, the eyes will blink.
Flying
^^^^^^
``hover()`` and ``set_flat_trim()`` both tell the drone to assume the current configuration is a flat trim and it will
use this as the default when not receiving commands. This enables good hovering when not sending commands.
``flip(direction)`` Sends the flip command to the minidrone. Valid directions to flip are: front, back, right, left.
``turn_degrees(degrees)`` Turns the minidrone in place the specified number of degrees.
The range is -180 to 180. This can be accomplished in direct_fly() as well but this one uses the
internal minidrone sensors (which are not sent out right now) so it is more accurate.
``fly_direct(roll, pitch, yaw, vertical_movement, duration)`` Fly the minidrone directly using the
specified roll, pitch, yaw, and vertical movements. The commands are repeated for duration seconds.
Note there are currently no sensors reported back to the user to ensure that these are working but hopefully
that is addressed in a future firmware upgrade. Each value ranges from -100 to 100 and is essentially a percentage
and direction of the max_tilt (for roll/pitch) or max_vertical_speed (for vertical movement).
``set_max_tilt(degrees)`` Set the maximum tilt in degrees. Be careful as this makes your drone go slower or faster!
It is important to note that the fly_direct command uses this value in conjunction with the -100 to 100 percentages.
``set_max_vertical_speed(speed)`` Set the maximum vertical speed in m/s. Be careful as this makes your drone go up/down faster!
Pausing or sleeping in a thread safe manner
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
``smart_sleep(seconds)`` This sleeps the number of seconds (which can be a floating point) but wakes for all
BLE or wifi notifications. **Note, if you are using BLE: This comamnd is VERY important**. **NEVER** use regular
time.sleep() as your BLE will disconnect regularly! Use smart_sleep instead! time.sleep() is ok if you are using
wifi but smart_sleep() handles that for you.
USB accessories: Claw and Gun
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
``open_claw()`` Open the claw. Note that the claw should be attached for this to work.
The id is obtained from a prior ``ask_for_state_update()`` call. Note that you cannot use the claw with the FPV camera attached.
``close_claw()`` Close the claw. Note that the claw should be attached for this to work.
The id is obtained from a prior ``ask_for_state_update()`` call. Note that you cannot use the claw with the FPV camera attached.
``fire_gun()`` Fires the gun. Note that the gun should be attached for this to work.
The id is obtained from a prior ``ask_for_state_update()`` call. Note that you cannot use the gun with the FPV camera attached.
Swing specific commands
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
``set_plane_gear_box(state)`` Choose the swing angle in plane mode. There are 3 tilt modes: gear_1, gear_2, gear_3.
Warning gear_3 is very fast.
``set_flying_mode(mode)`` Choose flight mode between: quadricopter, plane_forward, plane_backward.
Ground facing camera
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
``take_picture()``` The minidrone will take a picture with the downward facing camera. It only stores up to 40 pictures
internally so this function deletes them after 35 have been taken. Make sure you are downloading them either
using the mobile interface or through the python code.
**Note**: Parrot broke the ability to access the groundcam in their latest (3.0.25) firmware upgrade. We will reenable these
functions as soon as parrot fixes the firmware but for now, they will only work in versions 3.0.24 and below.
``get_groundcam_pictures_names()`` Returns the names of the pictures stored internally from the groundcam. Only for the mambo.
``get_groundcam_picture(name)`` Returns the picture with the specified name. Only for the mambo.
Sensor related commands
^^^^^^^^^^^^^^^^^^^^^^^
``ask_for_state_update()`` This sends a request to the minidrone to send back ALL states
(this includes the claw and gun states). This really only needs to be called once at the start of the program
to initialize some of the state variables. If you are on wifi, many of the other variables are sent at 2Hz. If you are
on BLE, you will want to use this command to get more state information but keep in mind it will be slow.
This command will return immediately but you should wait a few seconds before using the new state information
as it has to be updated.
Mambo sensors
-------------
All of the sensor data that is passed back to the program is saved. Note that Parrot sends back more
information via wifi than via BLE, due to the limited BLE bandwidth. The sensors are saved in Minidrone.sensors.
This is an instance of a MamboSensors class, which can be seen at the top of the Minidrone.py file.
The easiest way to interact with the sensors is to call:
``minidrone.set_user_sensor_callback(function, args)``. This sets a user callback function with optional
arguments that is called each time a sensor is updated. The refresh rate on wifi is 2Hz.
The sensors are:
* battery (defaults to 100 and stays at that level until a real reading is received from the drone)
* flying_state: This is updated as frequently as the drone sends it out and can be one of "landed", "takingoff", "hovering", "flying", "landing", "emergency", "rolling", "init". These are the values as specified in `minidrone.xml <https://github.com/amymcgovern/pyparrot/blob/master/commandsandsensors/minidrone.xml>`_.
* gun_id: defaults to 0 (as far as I can tell, it is only ever 0 when it comes from the drone anyway)
* gun_state: "READY" or "BUSY" as sent by the drone, if a gun is attached. Defaults to None.
* claw_id: defaults to 0
* claw_state: "OPENING", "OPENED", "CLOSING", "CLOSED" as sent by the drone, if a claw is attached. Defaults to None.
* speed_x, speed_y, speed_z, speed_ts: the speed in x (forward > 0), y (right > 0), and z (down > 0). The ts is the timestamp that the speed was valid.
* altitude, altitude_ts: wifi only, altitude in meters. Zero is where you took off. The ts is the timestamp where the altitude was valid.
* quaternion_w, quaternion_x, quaternion_y, quaternion_z, quaternion_ts: wifi only. Quaternion as estimated from takeoff (which is set to 0). Ranges from -1 to 1. ts is the timestamp where this was valid.
* ``get_estimated_z_orientation()``: returns the estimated orientation using the unit quaternions. Note that 0 is the direction the drone is facing when you boot it up
* sensors_dict: all other sensors are saved by name in a dictionary. The names come from the `minidrone.xml <https://github.com/amymcgovern/pyparrot/blob/master/commandsandsensors/minidrone.xml>`_ and `common.xml <https://github.com/amymcgovern/pyparrot/blob/master/commandsandsensors/common.xml>`_.

View File

@ -0,0 +1,7 @@
pyparrot
========
.. toctree::
:maxdepth: 4
pyparrot

View File

@ -0,0 +1,30 @@
pyparrot.commandsandsensors package
===================================
Submodules
----------
pyparrot.commandsandsensors.DroneCommandParser module
-----------------------------------------------------
.. automodule:: pyparrot.commandsandsensors.DroneCommandParser
:members:
:undoc-members:
:show-inheritance:
pyparrot.commandsandsensors.DroneSensorParser module
----------------------------------------------------
.. automodule:: pyparrot.commandsandsensors.DroneSensorParser
:members:
:undoc-members:
:show-inheritance:
Module contents
---------------
.. automodule:: pyparrot.commandsandsensors
:members:
:undoc-members:
:show-inheritance:

View File

@ -0,0 +1,30 @@
pyparrot.networking package
===========================
Submodules
----------
pyparrot.networking.bleConnection module
----------------------------------------
.. automodule:: pyparrot.networking.bleConnection
:members:
:undoc-members:
:show-inheritance:
pyparrot.networking.wifiConnection module
-----------------------------------------
.. automodule:: pyparrot.networking.wifiConnection
:members:
:undoc-members:
:show-inheritance:
Module contents
---------------
.. automodule:: pyparrot.networking
:members:
:undoc-members:
:show-inheritance:

View File

@ -0,0 +1,64 @@
pyparrot package
================
Subpackages
-----------
.. toctree::
pyparrot.commandsandsensors
pyparrot.networking
pyparrot.scripts
pyparrot.utils
Submodules
----------
pyparrot.Bebop module
---------------------
.. automodule:: pyparrot.Bebop
:members:
:undoc-members:
:show-inheritance:
pyparrot.DroneVision module
---------------------------
.. automodule:: pyparrot.DroneVision
:members:
:undoc-members:
:show-inheritance:
pyparrot.DroneVisionGUI module
------------------------------
.. automodule:: pyparrot.DroneVisionGUI
:members:
:undoc-members:
:show-inheritance:
pyparrot.Minidrone module
---------------------
.. automodule:: pyparrot.Minidrone
:members:
:undoc-members:
:show-inheritance:
pyparrot.VisionServer module
----------------------------
.. automodule:: pyparrot.VisionServer
:members:
:undoc-members:
:show-inheritance:
Module contents
---------------
.. automodule:: pyparrot
:members:
:undoc-members:
:show-inheritance:

View File

@ -0,0 +1,22 @@
pyparrot.scripts package
========================
Submodules
----------
pyparrot.scripts.findMinidrone module
---------------------------------
.. automodule:: pyparrot.scripts.findMinidrone
:members:
:undoc-members:
:show-inheritance:
Module contents
---------------
.. automodule:: pyparrot.scripts
:members:
:undoc-members:
:show-inheritance:

View File

@ -0,0 +1,38 @@
pyparrot.utils package
======================
Submodules
----------
pyparrot.utils.NonBlockingStreamReader module
---------------------------------------------
.. automodule:: pyparrot.utils.NonBlockingStreamReader
:members:
:undoc-members:
:show-inheritance:
pyparrot.utils.colorPrint module
--------------------------------
.. automodule:: pyparrot.utils.colorPrint
:members:
:undoc-members:
:show-inheritance:
pyparrot.utils.vlc module
-------------------------
.. automodule:: pyparrot.utils.vlc
:members:
:undoc-members:
:show-inheritance:
Module contents
---------------
.. automodule:: pyparrot.utils
:members:
:undoc-members:
:show-inheritance:

View File

@ -0,0 +1,199 @@
.. title:: Quick Start with a Bebop
.. quickstartmambo:
Quick Start Guide with a Bebop
==============================
Using the pyparrot library on the Bebop
---------------------------------------
Before running any of the sample code, you will need to connect to your drone. To control the Bebop, you need to
connect your controlling device (laptop, computer, etc) to the wifi for the drone. Look for the wifi network
named Bebop_number where number varies for each drone.
Quick start: Demo Code
-----------------------
I have provided a set of `example <https://github.com/amymcgovern/pyparrot/tree/master/examples>`_ scripts for both the
Mambo and the Bebop.
Demo of the trick commands on the bebop
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
The code shown below is the
`demoBebopTricks.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoBebopTricks.py>`_.
demoBebopTricks.py will take off, demonstrate all 4 types of flips, and then land. It is a good program to
verify that your connection to your bebop is working well. The bebop can flip just like the Mambo! This does
the exact same thing as the Mambo tricks demo: take off, flip in all 4 directions, land.
**Be sure to run it in a room large enough to perform the flips!**
.. code-block:: python
"""
Demos the tricks on the bebop. Make sure you have enough room to perform them!
Author: Amy McGovern
"""
from pyparrot.Bebop import Bebop
bebop = Bebop()
print("connecting")
success = bebop.connect(10)
print(success)
print("sleeping")
bebop.smart_sleep(5)
bebop.ask_for_state_update()
bebop.safe_takeoff(10)
print("flip left")
print("flying state is %s" % bebop.sensors.flying_state)
success = bebop.flip(direction="left")
print("mambo flip result %s" % success)
bebop.smart_sleep(5)
print("flip right")
print("flying state is %s" % bebop.sensors.flying_state)
success = bebop.flip(direction="right")
print("mambo flip result %s" % success)
bebop.smart_sleep(5)
print("flip front")
print("flying state is %s" % bebop.sensors.flying_state)
success = bebop.flip(direction="front")
print("mambo flip result %s" % success)
bebop.smart_sleep(5)
print("flip back")
print("flying state is %s" % bebop.sensors.flying_state)
success = bebop.flip(direction="back")
print("mambo flip result %s" % success)
bebop.smart_sleep(5)
bebop.smart_sleep(5)
bebop.safe_land(10)
print("DONE - disconnecting")
bebop.disconnect()
Outdoor or large area demo of the direct flight commands on the bebop
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
The second example program shows how to directly fly the bebop by controlling the yaw, pitch, roll, and
vertical movement parameters. **Make sure you try this one in a large enough room!**
This code is provided in
`demoBebopDirectFlight.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoBebopDirectFlight.py>`_
and is also shown below.
.. code-block:: python
"""
Flies the bebop in a fairly wide arc. You want to be sure you have room for this. (it is commented
out but even what is here is still going to require a large space)
Author: Amy McGovern
"""
from pyparrot.Bebop import Bebop
bebop = Bebop()
print("connecting")
success = bebop.connect(10)
print(success)
print("sleeping")
bebop.smart_sleep(5)
bebop.ask_for_state_update()
bebop.safe_takeoff(10)
print("Flying direct: going forward (positive pitch)")
bebop.fly_direct(roll=0, pitch=50, yaw=0, vertical_movement=0, duration=1)
print("Flying direct: yaw")
bebop.fly_direct(roll=0, pitch=0, yaw=50, vertical_movement=0, duration=1)
print("Flying direct: going backwards (negative pitch)")
bebop.fly_direct(roll=0, pitch=-50, yaw=0, vertical_movement=0, duration=0.5)
print("Flying direct: roll")
bebop.fly_direct(roll=50, pitch=0, yaw=0, vertical_movement=0, duration=1)
print("Flying direct: going up")
bebop.fly_direct(roll=0, pitch=0, yaw=0, vertical_movement=50, duration=1)
print("Turning relative")
bebop.move_relative(0, 0, 0, math.radians(90))
# this works but requires a larger test space than I currently have. Uncomment with care and test only in large spaces!
#print("Flying direct: going around in a circle (yes you can mix roll, pitch, yaw in one command!)")
#bebop.fly_direct(roll=25, pitch=0, yaw=50, vertical_movement=0, duration=5)
bebop.smart_sleep(5)
bebop.safe_land(10)
print("DONE - disconnecting")
bebop.disconnect()
Indoor demo of the direct flight commands on the bebop
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
If you couldn't run the outdoor or large space demo to test your bebop, this one is designed for a smaller space.
It simply takes off, turns, and lands. **Make sure you are still flying in a safe place!** This code is provided in
`demoBebopIndoors.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoBebopIndoors.py>`_
and is also shown below.
.. code-block:: python
"""
Demo the Bebop indoors (sets small speeds and then flies just a small amount)
Note, the bebop will hurt your furniture if it hits it. Even though this is a very small
amount of flying, be sure you are doing this in an open area and are prepared to catch!
Author: Amy McGovern
"""
from pyparrot.Bebop import Bebop
bebop = Bebop()
print("connecting")
success = bebop.connect(10)
print(success)
if (success):
print("turning on the video")
bebop.start_video_stream()
print("sleeping")
bebop.smart_sleep(2)
bebop.ask_for_state_update()
bebop.safe_takeoff(10)
# set safe indoor parameters
bebop.set_max_tilt(5)
bebop.set_max_vertical_speed(1)
# trying out the new hull protector parameters - set to 1 for a hull protection and 0 without protection
bebop.set_hull_protection(1)
print("Flying direct: Slow move for indoors")
bebop.fly_direct(roll=0, pitch=20, yaw=0, vertical_movement=0, duration=2)
bebop.smart_sleep(5)
bebop.safe_land(10)
print("DONE - disconnecting")
bebop.stop_video_stream()
bebop.smart_sleep(5)
bebop.disconnect()

View File

@ -0,0 +1,604 @@
.. title:: Quick Start with a Minidrone
.. quickstartmambo:
Quick Start Guide with a Minidrone
==============================
Using the pyparrot library on the Minidrone
---------------------------------------
Before running any of the sample code, you will need to connect to your drone. If you have a Mambo FPV, I highly
recommend using the wifi connection since it sends much more information using wifi than BLE. If you have a Mambo Code
or a Mambo Fly or Swing(neither of which has a camera), then you need to use the BLE connection.
wifi connection
^^^^^^^^^^^^^^^
If you are using the wifi (e.g. Mambo FPV), you need to connect your controlling device (laptop, computer, etc)
to the wifi for the drone. Look for a wifi network named Mambo_number where number changes for each drone.
BLE connection
^^^^^^^^^^^^^^
If you do not have a camera or want to use BLE for other reasons(e.g. swarm), you will first need to find the
BLE address of your Minidrone(s). BLE permissions on linux require that this command run in sudo mode.
To run this, from the bin directory for your python installation, type:
::
sudo findMinidrone
This will identify all BLE devices within hearing of the Pi. The Minidrone's specific address will be printed at the end.
Save the address and use it in your connection code (discussed below). If findMinidrone does not
report "FOUND A MAMBO!" or "FOUND A SWING!", then be sure your minidrone is turned on when you run the findMambo code and that your Pi
(or other linux box) has its BLE interface turned on.
The output should look something like this. I removed my own BLE addresses from my network for security but I am
showing the address of the mambo that I use for all the demo scripts.
.. code-block:: console
~/miniconda3/bin $ sudo ./find_mambo
Discovered device <address removed>
Discovered device <address removed>
Discovered device <address removed>
Discovered device e0:14:d0:63:3d:d0
Received new data from <address removed>
Discovered device <address removed>
Discovered device <address removed>
Received new data from <address removed>
Discovered device <address removed>
FOUND A MAMBO!
Device e0:14:d0:63:3d:d0 (random), RSSI=-60 dB
Complete Local Name = Mambo_<numbers>
Quick start: Demo Code
-----------------------
I have provided a set of `example <https://github.com/amymcgovern/pyparrot/tree/master/examples>`_ scripts for both the
Mambo and the Bebop. Note that you will need to edit the minidrone scripts to either use your own BLE address or to
ensure that use_wifi=True is set, so that it connects using wifi.
**Note that you do not need to run any of the other code in sudo mode!** That was only for discovery.
Demo of the trick commands on the mambo
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
The code shown below is the
`demoMamboTricks.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoMamboTricks.py>`_.
demoMamboTricks.py will take off, demonstrate all 4 types of flips, and then land. It is a good program to
verify that your connection to your mambo is working well. Be sure to run it in a room large enough
to perform the flips! The highlighted lines need to change for YOUR mambo and connection choices.
.. code-block:: python
"""
Demo the trick flying for the python interface
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
# you will need to change this to the address of YOUR mambo
mamboAddr = "e0:14:d0:63:3d:d0"
# make my mambo object
# remember to set True/False for the wifi depending on if you are using the wifi or the BLE to connect
mambo = Mambo(mamboAddr, use_wifi=True)
print("trying to connect")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
mambo.smart_sleep(2)
mambo.ask_for_state_update()
mambo.smart_sleep(2)
print("taking off!")
mambo.safe_takeoff(5)
if (mambo.sensors.flying_state != "emergency"):
print("flying state is %s" % mambo.sensors.flying_state)
print("Flying direct: going up")
mambo.fly_direct(roll=0, pitch=0, yaw=0, vertical_movement=20, duration=1)
print("flip left")
print("flying state is %s" % mambo.sensors.flying_state)
success = mambo.flip(direction="left")
print("mambo flip result %s" % success)
mambo.smart_sleep(5)
print("flip right")
print("flying state is %s" % mambo.sensors.flying_state)
success = mambo.flip(direction="right")
print("mambo flip result %s" % success)
mambo.smart_sleep(5)
print("flip front")
print("flying state is %s" % mambo.sensors.flying_state)
success = mambo.flip(direction="front")
print("mambo flip result %s" % success)
mambo.smart_sleep(5)
print("flip back")
print("flying state is %s" % mambo.sensors.flying_state)
success = mambo.flip(direction="back")
print("mambo flip result %s" % success)
mambo.smart_sleep(5)
print("landing")
print("flying state is %s" % mambo.sensors.flying_state)
mambo.safe_land(5)
mambo.smart_sleep(5)
print("disconnect")
mambo.disconnect()
Demo of the direct flight commands on the mambo
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
The second example program shows how to directly fly the mambo by controlling the yaw, pitch, roll, and
vertical movement parameters. **Make sure you try this one in a large enough room!**
This code is provided in
`demoMamboDirectFlight.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoMamboDirectFlight.py>`_
and is also shown below. Again, the highlighted lines must be changed to the parameters for your mambo and connection.
.. code-block:: python
"""
Demo the direct flying for the python interface
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
# you will need to change this to the address of YOUR mambo
mamboAddr = "e0:14:d0:63:3d:d0"
# make my mambo object
# remember to set True/False for the wifi depending on if you are using the wifi or the BLE to connect
mambo = Mambo(mamboAddr, use_wifi=True)
print("trying to connect")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
mambo.smart_sleep(2)
mambo.ask_for_state_update()
mambo.smart_sleep(2)
print("taking off!")
mambo.safe_takeoff(5)
print("Flying direct: going forward (positive pitch)")
mambo.fly_direct(roll=0, pitch=50, yaw=0, vertical_movement=0, duration=1)
print("Showing turning (in place) using turn_degrees")
mambo.turn_degrees(90)
mambo.smart_sleep(2)
mambo.turn_degrees(-90)
mambo.smart_sleep(2)
print("Flying direct: yaw")
mambo.fly_direct(roll=0, pitch=0, yaw=50, vertical_movement=0, duration=1)
print("Flying direct: going backwards (negative pitch)")
mambo.fly_direct(roll=0, pitch=-50, yaw=0, vertical_movement=0, duration=0.5)
print("Flying direct: roll")
mambo.fly_direct(roll=50, pitch=0, yaw=0, vertical_movement=0, duration=1)
print("Flying direct: going up")
mambo.fly_direct(roll=0, pitch=0, yaw=0, vertical_movement=50, duration=1)
print("Flying direct: going around in a circle (yes you can mix roll, pitch, yaw in one command!)")
mambo.fly_direct(roll=25, pitch=0, yaw=50, vertical_movement=0, duration=3)
print("landing")
mambo.safe_land(5)
mambo.smart_sleep(5)
print("disconnect")
mambo.disconnect()
Demo of the USB claw accessory
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
If your mambo has the USB accessories (claw and gun), you can control them but you *MUST* be in BLE mode.
The mambo can only handle one USB accessory at a time and the camera counts as a USB accessory so you must use
the BLE connection only. `demoMamboClaw.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoMamboClaw.py>`_
show how to use the claw accessory. The highlighted line must be changed to the BLE address for your mambo and the use_wifi
parameter must stay at False. In this demo program, the mambo takes off, opens and closes the claw, and lands again.
.. code-block:: python
"""
Demo the claw for the python interface
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
# you will need to change this to the address of YOUR mambo
mamboAddr = "e0:14:d0:63:3d:d0"
# make my mambo object
# remember you can't use the claw with the camera installed so this must be BLE connected to work
mambo = Mambo(mamboAddr, use_wifi=False)
print("trying to connect")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
# get the state information
print("sleeping")
mambo.smart_sleep(2)
mambo.ask_for_state_update()
mambo.smart_sleep(2)
print("taking off!")
mambo.safe_takeoff(5)
print("open and close the claw")
mambo.open_claw()
# you have to sleep to let the claw open (it needs time to do it)
mambo.smart_sleep(5)
mambo.close_claw()
# you have to sleep to let the claw close (it needs time to do it)
mambo.smart_sleep(5)
print("landing")
mambo.safe_land(5)
mambo.smart_sleep(5)
print("disconnect")
mambo.disconnect()
Demo of the USB gun accessory
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
`demoMamboGun.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoMamboGun.py>`_
show how to use the gun accessory. The highlighted line must be changed to the BLE address for your mambo and the use_wifi
parameter must stay at False. In this demo program, the mambo takes off, fires the gun, and lands again.
.. code-block:: python
"""
Demo the gun for the python interface
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
# you will need to change this to the address of YOUR mambo
mamboAddr = "e0:14:d0:63:3d:d0"
# make my mambo object
# remember you can't use the gun with the camera installed so this must be BLE connected to work
mambo = Mambo(mamboAddr, use_wifi=False)
print("trying to connect")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
# get the state information
print ("sleeping")
mambo.smart_sleep(2)
mambo.ask_for_state_update()
mambo.smart_sleep(2)
print("shoot the gun")
mambo.fire_gun()
# sleep to ensure it does the firing
mambo.smart_sleep(15)
print("disconnect")
mambo.disconnect()
Demo of the ground-facing camera
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
`demoMamboGroundcam.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoMamboGroundcam.py>`_
show how to use the mambo's ground-facing camera. This feature **ONLY** works in wifi mode. It can be slow
to download the frames so do not count on this running at several frames per second. The example code shown
below takes off, takes a picture, and then grabs a random picture from the ground facing camera set.
.. code-block:: python
"""
Demo of the groundcam
Mambo takes off, takes a picture and shows a RANDOM frame, not the last one
Author: Valentin Benke, https://github.com/Vabe7
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
import cv2
mambo = Mambo(None, use_wifi=True) #address is None since it only works with WiFi anyway
print("trying to connect to mambo now")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
mambo.smart_sleep(1)
mambo.ask_for_state_update()
mambo.smart_sleep(1)
mambo.safe_takeoff(5)
# take the photo
pic_success = mambo.take_picture()
# need to wait a bit for the photo to show up
mambo.smart_sleep(0.5)
picture_names = mambo.groundcam.get_groundcam_pictures_names() #get list of availible files
print(picture_names)
frame = mambo.groundcam.get_groundcam_picture(picture_names[0],True) #get frame which is the first in the array
if frame is not None:
if frame is not False:
cv2.imshow("Groundcam", frame)
cv2.waitKey(100)
mambo.safe_land(5)
mambo.disconnect()
Demo of the flying mode on the swing
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
`demoSwingDirectFlight.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoSwingDirectFlight.py>`_
You can see how to use the set_flying_mode command. I advise you to have enough space to use this script.
.. code-block:: python
"""
Demo the direct flying for the python interface
Author: Victor804
"""
from pyparrot.Minidrone import Swing
# you will need to change this to the address of YOUR swing
swingAddr = "e0:14:04:a7:3d:cb"
# make my swing object
swing = Swing(swingAddr)
print("trying to connect")
success = swing.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
swing.smart_sleep(2)
swing.ask_for_state_update()
swing.smart_sleep(2)
print("taking off!")
swing.safe_takeoff(5)
print("plane forward")
swing.set_flying_mode("plane_forward")
swing.smart_sleep(1)
print("quadricopter")
swing.set_flying_mode("quadricopter")
print("landing")
swing.safe_land(5)
swing.smart_sleep(5)
print("disconnect")
swing.disconnect()
Demo joystick for Swing
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
`demoSwingJoystick.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoSwingJoystick.py>`_
Example code to control the swig with a joystick. Easy to modify for your needs.
.. code-block:: python
import pygame
import sys
from pyparrot.Minidrone import Swing
def joystick_init():
"""
Initializes the controller, allows the choice of the controller.
If no controller is detected returns an error.
:param:
:return joystick:
"""
pygame.init()
pygame.joystick.init()
joystick_count = pygame.joystick.get_count()
if joystick_count > 0:
for i in range(joystick_count):
joystick = pygame.joystick.Joystick(i)
joystick.init()
name = joystick.get_name()
print([i], name)
joystick.quit()
else:
sys.exit("Error: No joystick detected")
selected_joystick = eval(input("Enter your joystick number:"))
if selected_joystick not in range(joystick_count):
sys.exit("Error: Your choice is not valid")
joystick = pygame.joystick.Joystick(selected_joystick)
joystick.init()
return joystick
def mapping_button(joystick, dict_commands):
"""
Associating a controller key with a command in dict_commands.
:param joystick, dict_commands:
:return mapping:
"""
mapping = {}
for command in dict_commands:
print("Press the key", command)
done = False
while not done:
for event in pygame.event.get():
if event.type == pygame.JOYBUTTONDOWN:
if event.button not in (value for value in mapping.values()):
mapping[command] = event.button
done = True
return mapping
def mapping_axis(joystick, axes=["pitch", "roll", "yaw", "vertical"]):
"""
Associating the analog thumbsticks of the controller with a command in dict commands
:param joystick, dict_commands:
:return mapping:
"""
mapping = {}
for i in axes:
print("Push the", i, "axis")
done = False
while not done:
for event in pygame.event.get():
if event.type == pygame.JOYAXISMOTION:
if event.axis not in (value for value in mapping.values()):
mapping[i] = event.axis
done = True
return mapping
def _parse_button(dict_commands, button):
"""
Send the commands to the drone.
If multiple commands are assigned to a key each command will be sent one by one to each press.
:param dict_commands, button:
:return:
"""
commands = dict_commands[button][0]
args = dict_commands[button][-1]
command = commands[0]
arg = args[0]
if len(commands) == 1:
if len(args) == 1:
command(arg)
else:
command(arg)
dict_commands[button][-1] = args[1:]+[arg]
else:
if len(commands) == 1:
command(arg)
dict_commands[button][0] = commands[1:]+[command]
else:
command(arg)
dict_commands[button][0] = commands[1:]+[command]
dict_commands[button][-1] = args[1:]+[arg]
def main_loop(joystick, dict_commands, mapping_button, mapping_axis):
"""
First connects to the drone and makes a flat trim.
Then in a loop read the events of the controller to send commands to the drone.
:param joystick, dict_commands, mapping_button, mapping_axis:
:return:
"""
swing.connect(10)
swing.flat_trim()
while True:
pygame.event.get()
pitch = joystick.get_axis(mapping_axis["pitch"])*-100
roll = joystick.get_axis(mapping_axis["roll"])*100
yaw = joystick.get_axis(mapping_axis["yaw"])*100
vertical = joystick.get_axis(mapping_axis["vertical"])*-100
swing.fly_direct(roll, pitch, yaw, vertical, 0.1)
for button, value in mapping_button.items():
if joystick.get_button(value):
_parse_button(dict_commands, button)
if __name__ == "__main__":
swing = Swing("e0:14:04:a7:3d:cb")
#Example of dict_commands
dict_commands = {
"takeoff_landing":[ #Name of the button
[swing.safe_takeoff, swing.safe_land],#Commands execute one by one
[5]#Argument for executing the function
],
"fly_mode":[
[swing.set_flying_mode],
["quadricopter", "plane_forward"]
],
"plane_gear_box_up":[
[swing.set_plane_gear_box],
[((swing.sensors.plane_gear_box[:-1]+str(int(swing.sensors.plane_gear_box[-1])+1)) if swing.sensors.plane_gear_box[-1] != "3" else "gear_3")]#"gear_1" => "gear_2" => "gear_3"
],
"plane_gear_box_down":[
[swing.set_plane_gear_box],
[((swing.sensors.plane_gear_box[:-1]+str(int(swing.sensors.plane_gear_box[-1])-1)) if swing.sensors.plane_gear_box[-1] != "1" else "gear_1")]#"gear_3" => "gear_2" => "gear_1"
]
}
joystick = joystick_init()
mapping_button = mapping_button(joystick, dict_commands)
mapping_axis = mapping_axis(joystick)
main_loop(joystick, dict_commands, mapping_button, mapping_axis)

View File

@ -0,0 +1,495 @@
.. title:: Using Vision on the Mambos and Bebop
.. vision:
Using Vision on the Mambos and Bebop
====================================
The vision system uses a common interface for the Mambo and the Bebop. There are two approaches to the vision.
The first relies on ffmpeg and the second on libVLC. Both approaches assume opencv is also installed.
Note, the reason we do not simply rely on opencv directly is that there is a known existing bug in
opencv with RTSP streams that makes them unreliable. The behavior we reliably saw by using opencv directly was
that the stream would open, obtain between 10 and 15 frames and then stop collecting any new frames. Since
this is not tenable for flying, we bypass opencv's direct open of the stream with two other approaches described below.
Using ffmpeg for vision
-----------------------
`ffmpeg <https://www.ffmpeg.org>`_ is an open-source cross-platform library that can be used to process a
wide variety of video and audio streams. We use ffmpeg to bypass the issue with opencv by opening the video stream
in ffmpeg. The advantage of this approach is that the ffmpeg encoder can read the raw video streams (RTSP for
Mambo and RTP for Bebop) and convert it directly to a format that opencv can easily read. We chose to convert to png
format. The disadvantage is that ffmpeg has to save the converted images to disk, which introduces a slight delay
to the image processing. If you use a high-end laptop with a solid state drive, this delay can be as low as
0.5 seconds. Lower-processing speed laptops can introduce longer delays. However, if you want access to the images
after your flight or you do not need real-time access, this is the better choice.
The vision code itself can be found in
`DroneVision.py <https://github.com/amymcgovern/pyparrot/blob/master/pyparrot/DroneVision.py>`_.
Running this code requires both the ffmpeg software and the opencv package. This approach does NOT show a
live stream of the vision to the user but you can visualize the images using
the `VisionServer.py <https://github.com/amymcgovern/pyparrot/blob/master/pyparrot/VisionServer.py>`_.
One thing to note: since ffmpeg requires the images to be written to a folder, it will save images to a
directory named images inside the pyparrot package. **You will want to clean this folder out after each flight!**
Mambo ffmpeg vision demo
^^^^^^^^^^^^^^^^^^^^^^^^
The demo code for the mambo, `demoMamboVision.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoMamboVision.py>`_
shown below, has the mambo take off, move upwards for a short time, flip, and then land.
While all of this flight code is running, the vision processing is running in a separate thread.
The first highlighted line:
.. code-block:: python
testFlying = False
can be changed to True to have the mambo fly or set to False to do the vision without the mambo moving.
**One big note: if the mambo is NOT flying, it will turn the camera into a sleep mode after several minutes
and you either need to reboot the mambo or connect and takeoff to restart the camera.**
The highlighted line with the code:
.. code-block:: python
mamboVision.set_user_callback_function(userVision.save_pictures, user_callback_args=None)
is where the user sets the function to be called with every new vision frame. In this demo, the images are simply
read in and saved back to a new file name.
.. code-block:: python
:emphasize-lines: 14, 54
"""
Demo of the ffmpeg based mambo vision code (basically flies around and saves out photos as it flies)
Author: Amy McGovern
"""
from pyparrot.Mambo import Mambo
from pyparrot.DroneVision import DroneVision
import threading
import cv2
import time
# set this to true if you want to fly for the demo
testFlying = False
class UserVision:
def __init__(self, vision):
self.index = 0
self.vision = vision
def save_pictures(self, args):
print("in save pictures on image %d " % self.index)
img = self.vision.get_latest_valid_picture()
if (img is not None):
filename = "test_image_%06d.png" % self.index
cv2.imwrite(filename, img)
self.index +=1
#print(self.index)
# you will need to change this to the address of YOUR mambo
mamboAddr = "e0:14:d0:63:3d:d0"
# make my mambo object
# remember to set True/False for the wifi depending on if you are using the wifi or the BLE to connect
mambo = Mambo(mamboAddr, use_wifi=True)
print("trying to connect to mambo now")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
mambo.smart_sleep(1)
mambo.ask_for_state_update()
mambo.smart_sleep(1)
print("Preparing to open vision")
mamboVision = DroneVision(mambo, is_bebop=False, buffer_size=30)
userVision = UserVision(mamboVision)
mamboVision.set_user_callback_function(userVision.save_pictures, user_callback_args=None)
success = mamboVision.open_video()
print("Success in opening vision is %s" % success)
if (success):
print("Vision successfully started!")
#removed the user call to this function (it now happens in open_video())
#mamboVision.start_video_buffering()
if (testFlying):
print("taking off!")
mambo.safe_takeoff(5)
if (mambo.sensors.flying_state != "emergency"):
print("flying state is %s" % mambo.sensors.flying_state)
print("Flying direct: going up")
mambo.fly_direct(roll=0, pitch=0, yaw=0, vertical_movement=20, duration=1)
print("flip left")
print("flying state is %s" % mambo.sensors.flying_state)
success = mambo.flip(direction="left")
print("mambo flip result %s" % success)
mambo.smart_sleep(5)
print("landing")
print("flying state is %s" % mambo.sensors.flying_state)
mambo.safe_land(5)
else:
print("Sleeeping for 15 seconds - move the mambo around")
mambo.smart_sleep(15)
# done doing vision demo
print("Ending the sleep and vision")
mamboVision.close_video()
mambo.smart_sleep(5)
print("disconnecting")
mambo.disconnect()
Bebop ffmpeg vision demo
^^^^^^^^^^^^^^^^^^^^^^^^
The demo code for the bebop for the ffmpeg vision works nearly identically to the mambo demo except it does
not fly the bebop around. Instead, it starts the camera and then sleeps for 30 seconds for the user to
move around or move the drone around. This is intended as a safe demo for indoors. It also moves
the camera around so that it is obvious the vision is recording different photos. The code is
available at `demoBebopVision.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoBebopVision.py>`_
and is shown below. The highlighted line is again where the user sets the callback function of how to
process the vision frames.
Updated in Version 1.5.13: you can tell DroneVision to either remove all the old vision files (now the default)
or not by sending the parameter cleanup_old_images=True or False.
.. code-block:: python
:emphasize-lines: 40
"""
Demo of the Bebop ffmpeg based vision code (basically flies around and saves out photos as it flies)
Author: Amy McGovern
"""
from pyparrot.Bebop import Bebop
from pyparrot.DroneVision import DroneVision
import threading
import cv2
import time
isAlive = False
class UserVision:
def __init__(self, vision):
self.index = 0
self.vision = vision
def save_pictures(self, args):
#print("saving picture")
img = self.vision.get_latest_valid_picture()
if (img is not None):
filename = "test_image_%06d.png" % self.index
#cv2.imwrite(filename, img)
self.index +=1
# make my bebop object
bebop = Bebop()
# connect to the bebop
success = bebop.connect(5)
if (success):
# start up the video
bebopVision = DroneVision(bebop, is_bebop=True)
userVision = UserVision(bebopVision)
bebopVision.set_user_callback_function(userVision.save_pictures, user_callback_args=None)
success = bebopVision.open_video()
if (success):
print("Vision successfully started!")
#removed the user call to this function (it now happens in open_video())
#bebopVision.start_video_buffering()
# skipping actually flying for safety purposes indoors - if you want
# different pictures, move the bebop around by hand
print("Fly me around by hand!")
bebop.smart_sleep(5)
print("Moving the camera using velocity")
bebop.pan_tilt_camera_velocity(pan_velocity=0, tilt_velocity=-2, duration=4)
bebop.smart_sleep(25)
print("Finishing demo and stopping vision")
bebopVision.close_video()
# disconnect nicely so we don't need a reboot
bebop.disconnect()
else:
print("Error connecting to bebop. Retry")
Using libVLC for vision
-----------------------
Our second approach to vision relies on the libVLC library, which in turn relies on the VLC program.
`VLC <https://www.videolan.org/vlc/index.html>`_ is a cross-platform media player and libVLC is a python
interface to the VLC libraries. This can be done entirely in memory (not writing out to disk as ffmpeg required),
which means that the delay is minimized. If you have a need for the full image stream after your flight, you likely
should choose the ffmpeg approach. If you simply want to use the vision, this approach may work better for you
since you don't have the disk delay and you don't introduce the issues with the images subdirectory.
The other advantage of this approach is that you get a real-time video stream of what the drone is seeing. However,
controlling the drone after vision has started requires setting a new parameter called user_code_to_run, as shown
below and in the highlighted line in the demo code.
.. code-block:: python
mamboVision = DroneVisionGUI(mambo, is_bebop=False, buffer_size=200,
user_code_to_run=demo_mambo_user_vision_function, user_args=(mambo, ))
**To make this approach work, you MUST install the VLC client version 3.0.1 or greater.**
Installing only libvlc is not needed (the source is included with pyparrot) and it will not work.
Installing the client installs extra software that the libvlc python library requires.
There are two example programs, one for the bebop and one for the mambo. Both show the window opened by this
approach and the way that a user can run their own code by assigning code to the Run button.
libVLC demo code for the Mambo
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
This code can be downloaded from
`demoMamboVisionGUI.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoMamboVisionGUI.py>`_
and is repeated below.
.. code-block:: python
:emphasize-lines: 93, 94
"""
Demo of the Bebop vision using DroneVisionGUI that relies on libVLC. It is a different
multi-threaded approach than DroneVision
Author: Amy McGovern
"""
from pyparrot.Mambo import Mambo
from pyparrot.DroneVisionGUI import DroneVisionGUI
import cv2
# set this to true if you want to fly for the demo
testFlying = True
class UserVision:
def __init__(self, vision):
self.index = 0
self.vision = vision
def save_pictures(self, args):
# print("in save pictures on image %d " % self.index)
img = self.vision.get_latest_valid_picture()
if (img is not None):
filename = "test_image_%06d.png" % self.index
# uncomment this if you want to write out images every time you get a new one
#cv2.imwrite(filename, img)
self.index +=1
#print(self.index)
def demo_mambo_user_vision_function(mamboVision, args):
"""
Demo the user code to run with the run button for a mambo
:param args:
:return:
"""
mambo = args[0]
if (testFlying):
print("taking off!")
mambo.safe_takeoff(5)
if (mambo.sensors.flying_state != "emergency"):
print("flying state is %s" % mambo.sensors.flying_state)
print("Flying direct: going up")
mambo.fly_direct(roll=0, pitch=0, yaw=0, vertical_movement=15, duration=2)
print("flip left")
print("flying state is %s" % mambo.sensors.flying_state)
success = mambo.flip(direction="left")
print("mambo flip result %s" % success)
mambo.smart_sleep(5)
print("landing")
print("flying state is %s" % mambo.sensors.flying_state)
mambo.safe_land(5)
else:
print("Sleeeping for 15 seconds - move the mambo around")
mambo.smart_sleep(15)
# done doing vision demo
print("Ending the sleep and vision")
mamboVision.close_video()
mambo.smart_sleep(5)
print("disconnecting")
mambo.disconnect()
if __name__ == "__main__":
# you will need to change this to the address of YOUR mambo
mamboAddr = "e0:14:d0:63:3d:d0"
# make my mambo object
# remember to set True/False for the wifi depending on if you are using the wifi or the BLE to connect
mambo = Mambo(mamboAddr, use_wifi=True)
print("trying to connect to mambo now")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
mambo.smart_sleep(1)
mambo.ask_for_state_update()
mambo.smart_sleep(1)
print("Preparing to open vision")
mamboVision = DroneVisionGUI(mambo, is_bebop=False, buffer_size=200,
user_code_to_run=demo_mambo_user_vision_function, user_args=(mambo, ))
userVision = UserVision(mamboVision)
mamboVision.set_user_callback_function(userVision.save_pictures, user_callback_args=None)
mamboVision.open_video()
libVLC demo code for the Bebop
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
This code can be downloaded from
`demoBebopVision.py <https://github.com/amymcgovern/pyparrot/blob/master/examples/demoBebopVisionGUI.py>`_
and is repeated below. Note that in version 1.5.18 we added the ability for the user to draw a second window.
This is optional and is shown in the code below.
.. code-block:: python
:emphasize-lines: 69,70
"""
"""
Demo of the Bebop vision using DroneVisionGUI (relies on libVLC). It is a different
multi-threaded approach than DroneVision
Author: Amy McGovern
"""
from pyparrot.Bebop import Bebop
from pyparrot.DroneVisionGUI import DroneVisionGUI
import threading
import cv2
import time
from PyQt5.QtGui import QImage
isAlive = False
class UserVision:
def __init__(self, vision):
self.index = 0
self.vision = vision
def save_pictures(self, args):
#print("saving picture")
img = self.vision.get_latest_valid_picture()
# limiting the pictures to the first 10 just to limit the demo from writing out a ton of files
if (img is not None and self.index <= 10):
filename = "test_image_%06d.png" % self.index
cv2.imwrite(filename, img)
self.index +=1
def draw_current_photo():
"""
Quick demo of returning an image to show in the user window. Clearly one would want to make this a dynamic image
"""
image = cv2.imread('test_image_000001.png')
if (image is not None):
if len(image.shape) < 3 or image.shape[2] == 1:
image = cv2.cvtColor(image, cv2.COLOR_GRAY2RGB)
else:
image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB)
height, width, byteValue = image.shape
byteValue = byteValue * width
qimage = QImage(image, width, height, byteValue, QImage.Format_RGB888)
return qimage
else:
return None
def demo_user_code_after_vision_opened(bebopVision, args):
bebop = args[0]
print("Vision successfully started!")
#removed the user call to this function (it now happens in open_video())
#bebopVision.start_video_buffering()
# takeoff
# bebop.safe_takeoff(5)
# skipping actually flying for safety purposes indoors - if you want
# different pictures, move the bebop around by hand
print("Fly me around by hand!")
bebop.smart_sleep(15)
if (bebopVision.vision_running):
print("Moving the camera using velocity")
bebop.pan_tilt_camera_velocity(pan_velocity=0, tilt_velocity=-2, duration=4)
bebop.smart_sleep(5)
# land
bebop.safe_land(5)
print("Finishing demo and stopping vision")
bebopVision.close_video()
# disconnect nicely so we don't need a reboot
print("disconnecting")
bebop.disconnect()
if __name__ == "__main__":
# make my bebop object
bebop = Bebop()
# connect to the bebop
success = bebop.connect(5)
if (success):
# start up the video
bebopVision = DroneVisionGUI(bebop, is_bebop=True, user_code_to_run=demo_user_code_after_vision_opened,
user_args=(bebop, ), user_draw_window_fn=draw_current_photo)
userVision = UserVision(bebopVision)
bebopVision.set_user_callback_function(userVision.save_pictures, user_callback_args=None)
bebopVision.open_video()
else:
print("Error connecting to bebop. Retry")

View File

@ -0,0 +1,49 @@
"""
Flies the bebop in a fairly wide arc. You want to be sure you have room for this. (it is commented
out but even what is here is still going to require a large space)
Author: Amy McGovern
"""
from pyparrot.Bebop import Bebop
import math
bebop = Bebop()
print("connecting")
success = bebop.connect(10)
print(success)
print("sleeping")
bebop.smart_sleep(5)
bebop.ask_for_state_update()
bebop.safe_takeoff(5)
print("Flying direct: going forward (positive pitch)")
bebop.fly_direct(roll=0, pitch=50, yaw=0, vertical_movement=0, duration=1)
print("Flying direct: yaw")
bebop.fly_direct(roll=0, pitch=0, yaw=50, vertical_movement=0, duration=1)
print("Flying direct: going backwards (negative pitch)")
bebop.fly_direct(roll=0, pitch=-50, yaw=0, vertical_movement=0, duration=0.5)
print("Flying direct: roll")
bebop.fly_direct(roll=50, pitch=0, yaw=0, vertical_movement=0, duration=1)
print("Flying direct: going up")
bebop.fly_direct(roll=0, pitch=0, yaw=0, vertical_movement=50, duration=1)
#print("Turning relative")
#bebop.move_relative(0, 0, 0, math.radians(90))
# this works but requires a larger test space than I currently have. Uncomment with care and test only in large spaces!
#print("Flying direct: going around in a circle (yes you can mix roll, pitch, yaw in one command!)")
#bebop.fly_direct(roll=25, pitch=0, yaw=50, vertical_movement=0, duration=5)
bebop.smart_sleep(1)
bebop.safe_land(5)
print("DONE - disconnecting")
bebop.disconnect()

View File

@ -0,0 +1,46 @@
"""
Demo the Bebop indoors (sets small speeds and then flies just a small amount)
Note, the bebop will hurt your furniture if it hits it. Even though this is a very small
amount of flying, be sure you are doing this in an open area and are prepared to catch!
Author: Amy McGovern
"""
from pyparrot.Bebop import Bebop
bebop = Bebop(drone_type="Bebop2")
print("connecting")
success = bebop.connect(10)
print(success)
if (success):
print("turning on the video")
bebop.start_video_stream()
print("sleeping")
bebop.smart_sleep(2)
bebop.ask_for_state_update()
bebop.safe_takeoff(10)
# set safe indoor parameters
bebop.set_max_tilt(5)
bebop.set_max_vertical_speed(1)
# trying out the new hull protector parameters - set to 1 for a hull protection and 0 without protection
#bebop.set_hull_protection(1)
print("Flying direct: Slow move for indoors")
bebop.fly_direct(roll=0, pitch=20, yaw=0, vertical_movement=0, duration=2)
bebop.smart_sleep(5)
bebop.safe_land(10)
print("DONE - disconnecting")
bebop.stop_video_stream()
bebop.smart_sleep(5)
print(bebop.sensors.battery)
bebop.disconnect()

View File

@ -0,0 +1,50 @@
"""
Demos the tricks on the bebop. Make sure you have enough room to perform them!
Author: Amy McGovern
"""
from pyparrot.Bebop import Bebop
bebop = Bebop()
print("connecting")
success = bebop.connect(10)
print(success)
print("sleeping")
bebop.smart_sleep(5)
bebop.ask_for_state_update()
bebop.safe_takeoff(10)
print("flip left")
print("flying state is %s" % bebop.sensors.flying_state)
success = bebop.flip(direction="left")
print("mambo flip result %s" % success)
bebop.smart_sleep(5)
print("flip right")
print("flying state is %s" % bebop.sensors.flying_state)
success = bebop.flip(direction="right")
print("mambo flip result %s" % success)
bebop.smart_sleep(5)
print("flip front")
print("flying state is %s" % bebop.sensors.flying_state)
success = bebop.flip(direction="front")
print("mambo flip result %s" % success)
bebop.smart_sleep(5)
print("flip back")
print("flying state is %s" % bebop.sensors.flying_state)
success = bebop.flip(direction="back")
print("mambo flip result %s" % success)
bebop.smart_sleep(5)
bebop.smart_sleep(5)
bebop.safe_land(10)
print("DONE - disconnecting")
bebop.disconnect()

View File

@ -0,0 +1,63 @@
"""
Demo of the Bebop ffmpeg based vision code (basically flies around and saves out photos as it flies)
Author: Amy McGovern
"""
from pyparrot.Bebop import Bebop
from pyparrot.DroneVision import DroneVision
import threading
import cv2
import time
isAlive = False
class UserVision:
def __init__(self, vision):
self.index = 0
self.vision = vision
def save_pictures(self, args):
#print("saving picture")
img = self.vision.get_latest_valid_picture()
if (img is not None):
filename = "test_image_%06d.png" % self.index
#cv2.imwrite(filename, img)
self.index +=1
# make my bebop object
bebop = Bebop()
# connect to the bebop
success = bebop.connect(5)
if (success):
# start up the video
bebopVision = DroneVision(bebop, is_bebop=True)
userVision = UserVision(bebopVision)
bebopVision.set_user_callback_function(userVision.save_pictures, user_callback_args=None)
success = bebopVision.open_video()
if (success):
print("Vision successfully started!")
#removed the user call to this function (it now happens in open_video())
#bebopVision.start_video_buffering()
# skipping actually flying for safety purposes indoors - if you want
# different pictures, move the bebop around by hand
print("Fly me around by hand!")
bebop.smart_sleep(5)
print("Moving the camera using velocity")
bebop.pan_tilt_camera_velocity(pan_velocity=0, tilt_velocity=-2, duration=4)
bebop.smart_sleep(25)
print("Finishing demo and stopping vision")
bebopVision.close_video()
# disconnect nicely so we don't need a reboot
bebop.disconnect()
else:
print("Error connecting to bebop. Retry")

View File

@ -0,0 +1,101 @@
"""
Demo of the Bebop vision using DroneVisionGUI (relies on libVLC). It is a different
multi-threaded approach than DroneVision
Author: Amy McGovern
"""
from pyparrot.Bebop import Bebop
from pyparrot.DroneVisionGUI import DroneVisionGUI
import threading
import cv2
import time
from PyQt5.QtGui import QImage
isAlive = False
class UserVision:
def __init__(self, vision):
self.index = 0
self.vision = vision
def save_pictures(self, args):
#print("saving picture")
img = self.vision.get_latest_valid_picture()
# limiting the pictures to the first 10 just to limit the demo from writing out a ton of files
if (img is not None and self.index <= 10):
filename = "test_image_%06d.png" % self.index
cv2.imwrite(filename, img)
self.index +=1
def draw_current_photo():
"""
Quick demo of returning an image to show in the user window. Clearly one would want to make this a dynamic image
"""
image = cv2.imread('test_image_000001.png')
if (image is not None):
if len(image.shape) < 3 or image.shape[2] == 1:
image = cv2.cvtColor(image, cv2.COLOR_GRAY2RGB)
else:
image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB)
height, width, byteValue = image.shape
byteValue = byteValue * width
qimage = QImage(image, width, height, byteValue, QImage.Format_RGB888)
return qimage
else:
return None
def demo_user_code_after_vision_opened(bebopVision, args):
bebop = args[0]
print("Vision successfully started!")
#removed the user call to this function (it now happens in open_video())
#bebopVision.start_video_buffering()
# takeoff
# bebop.safe_takeoff(5)
# skipping actually flying for safety purposes indoors - if you want
# different pictures, move the bebop around by hand
print("Fly me around by hand!")
bebop.smart_sleep(15)
if (bebopVision.vision_running):
print("Moving the camera using velocity")
bebop.pan_tilt_camera_velocity(pan_velocity=0, tilt_velocity=-2, duration=4)
bebop.smart_sleep(5)
# land
bebop.safe_land(5)
print("Finishing demo and stopping vision")
bebopVision.close_video()
# disconnect nicely so we don't need a reboot
print("disconnecting")
bebop.disconnect()
if __name__ == "__main__":
# make my bebop object
bebop = Bebop()
# connect to the bebop
success = bebop.connect(5)
if (success):
# start up the video
bebopVision = DroneVisionGUI(bebop, is_bebop=True, user_code_to_run=demo_user_code_after_vision_opened,
user_args=(bebop, ), user_draw_window_fn=draw_current_photo)
userVision = UserVision(bebopVision)
bebopVision.set_user_callback_function(userVision.save_pictures, user_callback_args=None)
bebopVision.open_video()
else:
print("Error connecting to bebop. Retry")

View File

@ -0,0 +1,43 @@
"""
Demo the claw for the python interface
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
# you will need to change this to the address of YOUR mambo
mamboAddr = "d0:3a:69:b9:e6:5a"
# make my mambo object
# remember you can't use the claw with the camera installed so this must be BLE connected to work
mambo = Mambo(mamboAddr, use_wifi=False)
print("trying to connect")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
# get the state information
print("sleeping")
mambo.smart_sleep(2)
mambo.ask_for_state_update()
mambo.smart_sleep(2)
print("taking off!")
mambo.safe_takeoff(5)
print("open and close the claw")
mambo.open_claw()
# you have to sleep to let the claw open (it needs time to do it)
mambo.smart_sleep(5)
mambo.close_claw()
# you have to sleep to let the claw close (it needs time to do it)
mambo.smart_sleep(5)
print("landing")
mambo.safe_land(5)
mambo.smart_sleep(5)
print("disconnect")
mambo.disconnect()

View File

@ -0,0 +1,59 @@
"""
Demo the direct flying for the python interface
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
# you will need to change this to the address of YOUR mambo
mamboAddr = "e0:14:d0:63:3d:d0"
# make my mambo object
# remember to set True/False for the wifi depending on if you are using the wifi or the BLE to connect
mambo = Mambo(mamboAddr, use_wifi=True)
print("trying to connect")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
mambo.smart_sleep(2)
mambo.ask_for_state_update()
mambo.smart_sleep(2)
print("taking off!")
mambo.safe_takeoff(5)
print("Flying direct: going forward (positive pitch)")
mambo.fly_direct(roll=0, pitch=50, yaw=0, vertical_movement=0, duration=1)
print("Showing turning (in place) using turn_degrees")
mambo.turn_degrees(90)
mambo.smart_sleep(2)
mambo.turn_degrees(-90)
mambo.smart_sleep(2)
print("Flying direct: yaw")
mambo.fly_direct(roll=0, pitch=0, yaw=50, vertical_movement=0, duration=1)
print("Flying direct: going backwards (negative pitch)")
mambo.fly_direct(roll=0, pitch=-50, yaw=0, vertical_movement=0, duration=0.5)
print("Flying direct: roll")
mambo.fly_direct(roll=50, pitch=0, yaw=0, vertical_movement=0, duration=1)
print("Flying direct: going up")
mambo.fly_direct(roll=0, pitch=0, yaw=0, vertical_movement=50, duration=1)
print("Flying direct: going around in a circle (yes you can mix roll, pitch, yaw in one command!)")
mambo.fly_direct(roll=25, pitch=0, yaw=50, vertical_movement=0, duration=3)
print("landing")
mambo.safe_land(5)
mambo.smart_sleep(5)
print("disconnect")
mambo.disconnect()

View File

@ -0,0 +1,41 @@
"""
Demo of the groundcam
Mambo takes off, takes a picture and shows a RANDOM frame, not the last one
Author: Valentin Benke, https://github.com/Vabe7
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
import cv2
mambo = Mambo(None, use_wifi=True) #address is None since it only works with WiFi anyway
print("trying to connect to mambo now")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
mambo.smart_sleep(1)
mambo.ask_for_state_update()
mambo.smart_sleep(1)
mambo.safe_takeoff(5)
# take the photo
pic_success = mambo.take_picture()
# need to wait a bit for the photo to show up
mambo.smart_sleep(0.5)
picture_names = mambo.groundcam.get_groundcam_pictures_names() #get list of availible files
print(picture_names)
frame = mambo.groundcam.get_groundcam_picture(picture_names[0],True) #get frame which is the first in the array
if frame is not None:
if frame is not False:
cv2.imshow("Groundcam", frame)
cv2.waitKey(100)
mambo.safe_land(5)
mambo.disconnect()

View File

@ -0,0 +1,33 @@
"""
Demo the gun for the python interface
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
# you will need to change this to the address of YOUR mambo
mamboAddr = "e0:14:d0:63:3d:d0"
# make my mambo object
# remember you can't use the gun with the camera installed so this must be BLE connected to work
mambo = Mambo(mamboAddr, use_wifi=False)
print("trying to connect")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
# get the state information
print ("sleeping")
mambo.smart_sleep(2)
mambo.ask_for_state_update()
mambo.smart_sleep(2)
print("shoot the gun")
mambo.fire_gun()
# sleep to ensure it does the firing
mambo.smart_sleep(15)
print("disconnect")
mambo.disconnect()

View File

@ -0,0 +1,66 @@
"""
Demo the trick flying for the python interface
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
# If you are using BLE: you will need to change this to the address of YOUR mambo
# if you are using Wifi, this can be ignored
mamboAddr = "e0:14:d0:63:3d:d0"
# make my mambo object
# remember to set True/False for the wifi depending on if you are using the wifi or the BLE to connect
mambo = Mambo(mamboAddr, use_wifi=True)
print("trying to connect")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
mambo.smart_sleep(2)
mambo.ask_for_state_update()
mambo.smart_sleep(2)
print("taking off!")
mambo.safe_takeoff(5)
if (mambo.sensors.flying_state != "emergency"):
print("flying state is %s" % mambo.sensors.flying_state)
print("Flying direct: going up")
mambo.fly_direct(roll=0, pitch=0, yaw=0, vertical_movement=20, duration=1)
print("flip left")
print("flying state is %s" % mambo.sensors.flying_state)
success = mambo.flip(direction="left")
print("mambo flip result %s" % success)
mambo.smart_sleep(5)
print("flip right")
print("flying state is %s" % mambo.sensors.flying_state)
success = mambo.flip(direction="right")
print("mambo flip result %s" % success)
mambo.smart_sleep(5)
print("flip front")
print("flying state is %s" % mambo.sensors.flying_state)
success = mambo.flip(direction="front")
print("mambo flip result %s" % success)
mambo.smart_sleep(5)
print("flip back")
print("flying state is %s" % mambo.sensors.flying_state)
success = mambo.flip(direction="back")
print("mambo flip result %s" % success)
mambo.smart_sleep(5)
print("landing")
print("flying state is %s" % mambo.sensors.flying_state)
mambo.safe_land(5)
mambo.smart_sleep(5)
print("disconnect")
mambo.disconnect()

View File

@ -0,0 +1,92 @@
"""
Demo of the ffmpeg based mambo vision code (basically flies around and saves out photos as it flies)
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
from pyparrot.DroneVision import DroneVision
import threading
import cv2
import time
# set this to true if you want to fly for the demo
testFlying = False
class UserVision:
def __init__(self, vision):
self.index = 0
self.vision = vision
def save_pictures(self, args):
print("in save pictures on image %d " % self.index)
img = self.vision.get_latest_valid_picture()
if (img is not None):
filename = "test_image_%06d.png" % self.index
cv2.imwrite(filename, img)
self.index +=1
#print(self.index)
# you will need to change this to the address of YOUR mambo
mamboAddr = "e0:14:d0:63:3d:d0"
# make my mambo object
# remember to set True/False for the wifi depending on if you are using the wifi or the BLE to connect
mambo = Mambo(mamboAddr, use_wifi=True)
print("trying to connect to mambo now")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
mambo.smart_sleep(1)
mambo.ask_for_state_update()
mambo.smart_sleep(1)
print("Preparing to open vision")
mamboVision = DroneVision(mambo, is_bebop=False, buffer_size=30)
userVision = UserVision(mamboVision)
mamboVision.set_user_callback_function(userVision.save_pictures, user_callback_args=None)
success = mamboVision.open_video()
print("Success in opening vision is %s" % success)
if (success):
print("Vision successfully started!")
#removed the user call to this function (it now happens in open_video())
#mamboVision.start_video_buffering()
if (testFlying):
print("taking off!")
mambo.safe_takeoff(5)
if (mambo.sensors.flying_state != "emergency"):
print("flying state is %s" % mambo.sensors.flying_state)
print("Flying direct: going up")
mambo.fly_direct(roll=0, pitch=0, yaw=0, vertical_movement=20, duration=1)
print("flip left")
print("flying state is %s" % mambo.sensors.flying_state)
success = mambo.flip(direction="left")
print("mambo flip result %s" % success)
mambo.smart_sleep(5)
print("landing")
print("flying state is %s" % mambo.sensors.flying_state)
mambo.safe_land(5)
else:
print("Sleeeping for 15 seconds - move the mambo around")
mambo.smart_sleep(15)
# done doing vision demo
print("Ending the sleep and vision")
mamboVision.close_video()
mambo.smart_sleep(5)
print("disconnecting")
mambo.disconnect()

View File

@ -0,0 +1,97 @@
"""
Demo of the Bebop vision using DroneVisionGUI that relies on libVLC. It is a different
multi-threaded approach than DroneVision
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
from pyparrot.DroneVisionGUI import DroneVisionGUI
import cv2
# set this to true if you want to fly for the demo
testFlying = True
class UserVision:
def __init__(self, vision):
self.index = 0
self.vision = vision
def save_pictures(self, args):
# print("in save pictures on image %d " % self.index)
img = self.vision.get_latest_valid_picture()
if (img is not None):
filename = "test_image_%06d.png" % self.index
# uncomment this if you want to write out images every time you get a new one
#cv2.imwrite(filename, img)
self.index +=1
#print(self.index)
def demo_mambo_user_vision_function(mamboVision, args):
"""
Demo the user code to run with the run button for a mambo
:param args:
:return:
"""
mambo = args[0]
if (testFlying):
print("taking off!")
mambo.safe_takeoff(5)
if (mambo.sensors.flying_state != "emergency"):
print("flying state is %s" % mambo.sensors.flying_state)
print("Flying direct: going up")
mambo.fly_direct(roll=0, pitch=0, yaw=0, vertical_movement=15, duration=2)
print("flip left")
print("flying state is %s" % mambo.sensors.flying_state)
success = mambo.flip(direction="left")
print("mambo flip result %s" % success)
mambo.smart_sleep(5)
print("landing")
print("flying state is %s" % mambo.sensors.flying_state)
mambo.safe_land(5)
else:
print("Sleeeping for 15 seconds - move the mambo around")
mambo.smart_sleep(15)
# done doing vision demo
print("Ending the sleep and vision")
mamboVision.close_video()
mambo.smart_sleep(5)
print("disconnecting")
mambo.disconnect()
if __name__ == "__main__":
# you will need to change this to the address of YOUR mambo
mamboAddr = "e0:14:d0:63:3d:d0"
# make my mambo object
# remember to set True/False for the wifi depending on if you are using the wifi or the BLE to connect
mambo = Mambo(mamboAddr, use_wifi=True)
print("trying to connect to mambo now")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
mambo.smart_sleep(1)
mambo.ask_for_state_update()
mambo.smart_sleep(1)
print("Preparing to open vision")
mamboVision = DroneVisionGUI(mambo, is_bebop=False, buffer_size=200,
user_code_to_run=demo_mambo_user_vision_function, user_args=(mambo, ))
userVision = UserVision(mamboVision)
mamboVision.set_user_callback_function(userVision.save_pictures, user_callback_args=None)
mamboVision.open_video()

View File

@ -0,0 +1,107 @@
"""
Demo of the Mambo vision using DroneVisionGUI that relies on libVLC and shows how to make a
second window using opencv to draw on the processed window. It is a different
multi-threaded approach than DroneVision
Author: Amy McGovern
"""
from pyparrot.Minidrone import Mambo
from pyparrot.DroneVisionGUI import DroneVisionGUI
import cv2
import time
# set this to true if you want to fly for the demo
testFlying = True
font = cv2.FONT_HERSHEY_SIMPLEX
def draw_second_pictures(args):
"""
Grab the latest stream from the drone and draw it in a second opencv window with some text to show that it
is being processed
:param args:
:return:
"""
# get the vision
mamboVision = args[0]
# get the latest images
img = mamboVision.get_latest_valid_picture()
# if the images is invalid, return
if(img is None):
return
# put the roll and pitch at the top of the screen
cv2.putText(img, 'demo text', (50, 50), font, 1, (255, 0, 255), 2, cv2.LINE_AA)
cv2.imshow("MarkerStream", img)
def demo_mambo_user_vision_function(mamboVision, args):
"""
Demo the user code to run with the run button for a mambo
:param args:
:return:
"""
mambo = args[0]
if (testFlying):
print("taking off!")
mambo.safe_takeoff(5)
if (mambo.sensors.flying_state != "emergency"):
print("flying state is %s" % mambo.sensors.flying_state)
print("Flying direct: going up")
mambo.fly_direct(roll=0, pitch=0, yaw=0, vertical_movement=15, duration=2)
print("flip left")
print("flying state is %s" % mambo.sensors.flying_state)
success = mambo.flip(direction="left")
print("mambo flip result %s" % success)
mambo.smart_sleep(5)
print("landing")
print("flying state is %s" % mambo.sensors.flying_state)
mambo.safe_land(5)
else:
print("Sleeeping for 15 seconds - move the mambo around")
mambo.smart_sleep(15)
# done doing vision demo
print("Ending the sleep and vision")
mamboVision.close_video()
mambo.smart_sleep(5)
print("disconnecting")
mambo.disconnect()
if __name__ == "__main__":
# make my mambo object
# remember to set True/False for the wifi depending on if you are using the wifi or the BLE to connect
# the address can be empty if you are using wifi
mambo = Mambo(address="", use_wifi=True)
print("trying to connect to mambo now")
success = mambo.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
mambo.smart_sleep(1)
mambo.ask_for_state_update()
mambo.smart_sleep(1)
# setup the extra window to draw the markers in
cv2.namedWindow("ExampleWindow")
print("Preparing to open vision")
mamboVision = DroneVisionGUI(mambo, is_bebop=False, buffer_size=200,
user_code_to_run=demo_mambo_user_vision_function, user_args=(mambo, ))
mamboVision.set_user_callback_function(draw_second_pictures, user_callback_args=(mamboVision, ))
mamboVision.open_video()

View File

@ -0,0 +1,42 @@
"""
Demo the direct flying for the python interface
Author: Victor804
"""
from pyparrot.Minidrone import Swing
# you will need to change this to the address of YOUR swing
swingAddr = "e0:14:04:a7:3d:cb"
# make my swing object
swing = Swing(swingAddr)
print("trying to connect")
success = swing.connect(num_retries=3)
print("connected: %s" % success)
if (success):
# get the state information
print("sleeping")
swing.smart_sleep(2)
swing.ask_for_state_update()
swing.smart_sleep(2)
print("taking off!")
swing.safe_takeoff(5)
print("plane forward")
swing.set_flying_mode("plane_forward")
swing.smart_sleep(1)
print("quadricopter")
swing.set_flying_mode("quadricopter")
print("landing")
swing.safe_land(5)
swing.smart_sleep(5)
print("disconnect")
swing.disconnect()

View File

@ -0,0 +1,173 @@
import pygame
import sys
from pyparrot.Minidrone import Swing
def joystick_init():
"""
Initializes the controller, allows the choice of the controller.
If no controller is detected returns an error.
:param:
:return joystick:
"""
pygame.init()
pygame.joystick.init()
joystick_count = pygame.joystick.get_count()
if joystick_count > 0:
for i in range(joystick_count):
joystick = pygame.joystick.Joystick(i)
joystick.init()
name = joystick.get_name()
print([i], name)
joystick.quit()
else:
sys.exit("Error: No joystick detected")
selected_joystick = eval(input("Enter your joystick number:"))
if selected_joystick not in range(joystick_count):
sys.exit("Error: Your choice is not valid")
joystick = pygame.joystick.Joystick(selected_joystick)
joystick.init()
return joystick
def mapping_button(joystick, dict_commands):
"""
Associating a controller key with a command in dict_commands.
:param joystick, dict_commands:
:return mapping:
"""
mapping = {}
for command in dict_commands:
print("Press the key", command)
done = False
while not done:
for event in pygame.event.get():
if event.type == pygame.JOYBUTTONDOWN:
if event.button not in (value for value in mapping.values()):
mapping[command] = event.button
done = True
return mapping
def mapping_axis(joystick, axes=["pitch", "roll", "yaw", "vertical"]):
"""
Associating the analog thumbsticks of the controller with a command in dict commands
:param joystick, dict_commands:
:return mapping:
"""
mapping = {}
for i in axes:
print("Push the", i, "axis")
done = False
while not done:
for event in pygame.event.get():
if event.type == pygame.JOYAXISMOTION:
if event.axis not in (value for value in mapping.values()):
mapping[i] = event.axis
done = True
return mapping
def _parse_button(dict_commands, button):
"""
Send the commands to the drone.
If multiple commands are assigned to a key each command will be sent one by one to each press.
:param dict_commands, button:
:return:
"""
commands = dict_commands[button][0]
args = dict_commands[button][-1]
command = commands[0]
arg = args[0]
if len(commands) == 1:
if len(args) == 1:
command(arg)
else:
command(arg)
dict_commands[button][-1] = args[1:]+[arg]
else:
if len(commands) == 1:
command(arg)
dict_commands[button][0] = commands[1:]+[command]
else:
command(arg)
dict_commands[button][0] = commands[1:]+[command]
dict_commands[button][-1] = args[1:]+[arg]
def main_loop(joystick, dict_commands, mapping_button, mapping_axis):
"""
First connects to the drone and makes a flat trim.
Then in a loop read the events of the controller to send commands to the drone.
:param joystick, dict_commands, mapping_button, mapping_axis:
:return:
"""
swing.connect(10)
swing.flat_trim()
while True:
pygame.event.get()
pitch = joystick.get_axis(mapping_axis["pitch"])*-100
roll = joystick.get_axis(mapping_axis["roll"])*100
yaw = joystick.get_axis(mapping_axis["yaw"])*100
vertical = joystick.get_axis(mapping_axis["vertical"])*-100
swing.fly_direct(roll, pitch, yaw, vertical, 0.1)
for button, value in mapping_button.items():
if joystick.get_button(value):
_parse_button(dict_commands, button)
if __name__ == "__main__":
swing = Swing("e0:14:04:a7:3d:cb")
#Example of dict_commands
dict_commands = {
"takeoff_landing":[ #Name of the button
[swing.safe_takeoff, swing.safe_land],#Commands execute one by one
[5]#Argument for executing the function
],
"fly_mode":[
[swing.set_flying_mode],
["quadricopter", "plane_forward"]
],
"plane_gear_box_up":[
[swing.set_plane_gear_box],
[((swing.sensors.plane_gear_box[:-1]+str(int(swing.sensors.plane_gear_box[-1])+1)) if swing.sensors.plane_gear_box[-1] != "3" else "gear_3")]#"gear_1" => "gear_2" => "gear_3"
],
"plane_gear_box_down":[
[swing.set_plane_gear_box],
[((swing.sensors.plane_gear_box[:-1]+str(int(swing.sensors.plane_gear_box[-1])-1)) if swing.sensors.plane_gear_box[-1] != "1" else "gear_1")]#"gear_3" => "gear_2" => "gear_1"
]
}
joystick = joystick_init()
mapping_button = mapping_button(joystick, dict_commands)
mapping_axis = mapping_axis(joystick)
main_loop(joystick, dict_commands, mapping_button, mapping_axis)

View File

@ -0,0 +1,883 @@
"""
Bebop class holds all of the methods needed to pilot the drone from python and to ask for sensor
data back from the drone
Author: Amy McGovern, dramymcgovern@gmail.com
"""
import time
from pyparrot.networking.wifiConnection import WifiConnection
from pyparrot.utils.colorPrint import color_print
from pyparrot.commandsandsensors.DroneCommandParser import DroneCommandParser
from pyparrot.commandsandsensors.DroneSensorParser import DroneSensorParser
from datetime import datetime
class BebopSensors:
def __init__(self):
self.sensors_dict = dict()
self.RelativeMoveEnded = False
self.CameraMoveEnded_tilt = False
self.CameraMoveEnded_pan = False
self.flying_state = "unknown"
self.flat_trim_changed = False
self.max_altitude_changed = False
self.max_distance_changed = False
self.no_fly_over_max_distance = False
self.max_tilt_changed = False
self.max_pitch_roll_rotation_speed_changed = False
self.max_vertical_speed_changed = False
self.max_rotation_speed = False
self.hull_protection_changed = False
self.outdoor_mode_changed = False
self.picture_format_changed = False
self.auto_white_balance_changed = False
self.exposition_changed = False
self.saturation_changed = False
self.timelapse_changed = False
self.video_stabilization_changed = False
self.video_recording_changed = False
self.video_framerate_changed = False
self.video_resolutions_changed = False
# default to full battery
self.battery = 100
# this is optionally set elsewhere
self.user_callback_function = None
def set_user_callback_function(self, function, args):
"""
Sets the user callback function (called everytime the sensors are updated)
:param function: name of the user callback function
:param args: arguments (tuple) to the function
:return:
"""
self.user_callback_function = function
self.user_callback_function_args = args
def update(self, sensor_name, sensor_value, sensor_enum):
if (sensor_name is None):
print("Error empty sensor")
return
if (sensor_name, "enum") in sensor_enum:
# grab the string value
if (sensor_value is None or sensor_value > len(sensor_enum[(sensor_name, "enum")])):
value = "UNKNOWN_ENUM_VALUE"
else:
enum_value = sensor_enum[(sensor_name, "enum")][sensor_value]
value = enum_value
self.sensors_dict[sensor_name] = value
else:
# regular sensor
self.sensors_dict[sensor_name] = sensor_value
# some sensors are saved outside the dictionary for internal use (they are also in the dictionary)
if (sensor_name == "FlyingStateChanged_state"):
self.flying_state = self.sensors_dict["FlyingStateChanged_state"]
if (sensor_name == "PilotingState_FlatTrimChanged"):
self.flat_trim_changed = True
if (sensor_name == "moveByEnd_dX"):
self.RelativeMoveEnded = True
if (sensor_name == "OrientationV2_tilt"):
self.CameraMoveEnded_tilt = True
if (sensor_name == "OrientationV2_pan"):
self.CameraMoveEnded_pan = True
if (sensor_name == "MaxAltitudeChanged_current"):
self.max_altitude_changed = True
if (sensor_name == "MaxDistanceChanged_current"):
self.max_distance_changed = True
if (sensor_name == "NoFlyOverMaxDistanceChanged_shouldNotFlyOver"):
self.no_fly_over_max_distance_changed = True
if (sensor_name == "MaxTiltChanged_current"):
self.max_tilt_changed = True
if (sensor_name == "MaxPitchRollRotationSpeedChanged_current"):
self.max_pitch_roll_rotation_speed_changed = True
if (sensor_name == "MaxVerticalSpeedChanged_current"):
self.max_vertical_speed_changed = True
if (sensor_name == "MaxRotationSpeedChanged_current"):
self.max_rotation_speed_changed = True
if (sensor_name == "HullProtectionChanged_present"):
self.hull_protection_changed = True
if (sensor_name == "OutdoorChanged_present"):
self.outdoor_mode_changed = True
if (sensor_name == "BatteryStateChanged_battery_percent"):
self.battery = sensor_value
if (sensor_name == "PictureFormatChanged_type"):
self.picture_format_changed = True
if (sensor_name == "AutoWhiteBalanceChanged_type"):
self.auto_white_balance_changed = True
if (sensor_name == "ExpositionChanged_value"):
self.exposition_changed = True
if (sensor_name == "SaturationChanged_value"):
self.saturation_changed = True
if (sensor_name == "TimelapseChanged_enabled"):
self.timelapse_changed = True
if (sensor_name == "VideoStabilizationModeChanged_mode"):
self.video_stabilization_changed = True
if (sensor_name == "VideoRecordingModeChanged_mode"):
self.video_recording_changed = True
if (sensor_name == "VideoFramerateChanged_framerate"):
self.video_framerate_changed = True
if (sensor_name == "VideoResolutionsChanged_type"):
self.video_resolutions_changed = True
# call the user callback if it isn't None
if (self.user_callback_function is not None):
self.user_callback_function(self.user_callback_function_args)
def __str__(self):
str = "Bebop sensors: %s" % self.sensors_dict
return str
class Bebop():
def __init__(self, drone_type="Bebop2", ip_address=None):
"""
Create a new Bebop object. Assumes you have connected to the Bebop's wifi
"""
self.drone_type = drone_type
self.drone_connection = WifiConnection(self, drone_type=drone_type, ip_address=ip_address)
# intialize the command parser
self.command_parser = DroneCommandParser()
# initialize the sensors and the parser
self.sensors = BebopSensors()
self.sensor_parser = DroneSensorParser(drone_type=drone_type)
def set_user_sensor_callback(self, function, args):
"""
Set the (optional) user callback function for sensors. Every time a sensor
is updated, it calls this function.
:param function: name of the function
:param args: tuple of arguments to the function
:return: nothing
"""
self.sensors.set_user_callback_function(function, args)
def update_sensors(self, data_type, buffer_id, sequence_number, raw_data, ack):
"""
Update the sensors (called via the wifi or ble connection)
:param data: raw data packet that needs to be parsed
:param ack: True if this packet needs to be ack'd and False otherwise
"""
#print("data type is %d buffer id is %d sequence number is %d " % (data_type, buffer_id, sequence_number))
sensor_list = self.sensor_parser.extract_sensor_values(raw_data)
#print(sensor_list)
if (sensor_list is not None):
for sensor in sensor_list:
(sensor_name, sensor_value, sensor_enum, header_tuple) = sensor
if (sensor_name is not None):
self.sensors.update(sensor_name, sensor_value, sensor_enum)
else:
color_print("data type %d buffer id %d sequence number %d" % (data_type, buffer_id, sequence_number), "WARN")
color_print("This sensor is missing (likely because we don't need it)", "WARN")
if (ack):
self.drone_connection.ack_packet(buffer_id, sequence_number)
def connect(self, num_retries):
"""
Connects to the drone and re-tries in case of failure the specified number of times. Seamlessly
connects to either wifi or BLE depending on how you initialized it
:param: num_retries is the number of times to retry
:return: True if it succeeds and False otherwise
"""
# special case for when the user tries to do BLE when it isn't available
if (self.drone_connection is None):
return False
connected = self.drone_connection.connect(num_retries)
return connected
def disconnect(self):
"""
Disconnect the BLE connection. Always call this at the end of your programs to
cleanly disconnect.
:return: void
"""
self.drone_connection.disconnect()
def ask_for_state_update(self):
"""
Ask for a full state update (likely this should never be used but it can be called if you want to see
everything the bebop is storing)
:return: nothing but it will eventually fill the sensors with all of the state variables as they arrive
"""
command_tuple = self.command_parser.get_command_tuple("common", "Common", "AllStates")
return self.drone_connection.send_noparam_command_packet_ack(command_tuple)
def flat_trim(self, duration=0):
"""
Sends the flat_trim command to the bebop. Gets the codes for it from the xml files.
:param duration: if duration is greater than 0, waits for the trim command to be finished or duration to be reached
"""
command_tuple = self.command_parser.get_command_tuple("ardrone3", "Piloting", "FlatTrim")
self.drone_connection.send_noparam_command_packet_ack(command_tuple)
if (duration > 0):
# wait for the specified duration
start_time = datetime.now()
new_time = datetime.now()
diff = (new_time - start_time).seconds + ((new_time - start_time).microseconds / 1000000.0)
while (not self.sensors.flat_trim_changed and diff < duration):
self.smart_sleep(0.1)
new_time = datetime.now()
diff = (new_time - start_time).seconds + ((new_time - start_time).microseconds / 1000000.0)
def takeoff(self):
"""
Sends the takeoff command to the bebop. Gets the codes for it from the xml files. Ensures the
packet was received or sends it again up to a maximum number of times.
:return: True if the command was sent and False otherwise
"""
command_tuple = self.command_parser.get_command_tuple("ardrone3", "Piloting", "TakeOff")
self.drone_connection.send_noparam_command_packet_ack(command_tuple)
def safe_takeoff(self, timeout):
"""
Sends commands to takeoff until the Bebop reports it is taking off
:param timeout: quit trying to takeoff if it takes more than timeout seconds
"""
start_time = time.time()
# take off until it really listens
while (self.sensors.flying_state != "takingoff" and (time.time() - start_time < timeout)):
if (self.sensors.flying_state == "emergency"):
return
success = self.takeoff()
self.smart_sleep(1)
# now wait until it finishes takeoff before returning
while ((self.sensors.flying_state not in ("flying", "hovering") and
(time.time() - start_time < timeout))):
if (self.sensors.flying_state == "emergency"):
return
self.smart_sleep(1)
def land(self):
"""
Sends the land command to the bebop. Gets the codes for it from the xml files. Ensures the
packet was received or sends it again up to a maximum number of times.
:return: True if the command was sent and False otherwise
"""
command_tuple = self.command_parser.get_command_tuple("ardrone3", "Piloting", "Landing")
return self.drone_connection.send_noparam_command_packet_ack(command_tuple)
def emergency_land(self):
"""
Sends the land command to the bebop on the high priority/emergency channel.
Gets the codes for it from the xml files. Ensures the
packet was received or sends it again up to a maximum number of times.
:return: True if the command was sent and False otherwise
"""
command_tuple = self.command_parser.get_command_tuple("ardrone3", "Piloting", "Landing")
return self.drone_connection.send_noparam_high_priority_command_packet(command_tuple)
def is_landed(self):
"""
Returns true if it is landed or emergency and False otherwise
:return:
"""
if (self.sensors.flying_state in ("landed", "emergency")):
return True
else:
return False
def safe_land(self, timeout):
"""
Ensure the Bebop lands by sending the command until it shows landed on sensors
"""
start_time = time.time()
while (self.sensors.flying_state not in ("landing", "landed") and (time.time() - start_time < timeout)):
if (self.sensors.flying_state == "emergency"):
return
color_print("trying to land", "INFO")
success = self.land()
self.smart_sleep(1)
while (self.sensors.flying_state != "landed" and (time.time() - start_time < timeout)):
if (self.sensors.flying_state == "emergency"):
return
self.smart_sleep(1)
def smart_sleep(self, timeout):
"""
Don't call time.sleep directly as it will mess up BLE and miss WIFI packets! Use this
which handles packets received while sleeping
:param timeout: number of seconds to sleep
"""
self.drone_connection.smart_sleep(timeout)
def _ensure_fly_command_in_range(self, value):
"""
Ensure the fly direct commands are in range
:param value: the value sent by the user
:return: a value in the range -100 to 100
"""
if (value < -100):
return -100
elif (value > 100):
return 100
else:
return value
def fly_direct(self, roll, pitch, yaw, vertical_movement, duration):
"""
Direct fly commands using PCMD. Each argument ranges from -100 to 100. Numbers outside that are clipped
to that range.
Note that the xml refers to gaz, which is apparently french for vertical movements:
http://forum.developer.parrot.com/t/terminology-of-gaz/3146
:param roll:
:param pitch:
:param yaw:
:param vertical_movement:
:return:
"""
my_roll = self._ensure_fly_command_in_range(roll)
my_pitch = self._ensure_fly_command_in_range(pitch)
my_yaw = self._ensure_fly_command_in_range(yaw)
my_vertical = self._ensure_fly_command_in_range(vertical_movement)
# print("roll is %d pitch is %d yaw is %d vertical is %d" % (my_roll, my_pitch, my_yaw, my_vertical))
command_tuple = self.command_parser.get_command_tuple("ardrone3", "Piloting", "PCMD")
self.drone_connection.send_pcmd_command(command_tuple, my_roll, my_pitch, my_yaw, my_vertical, duration)
def flip(self, direction):
"""
Sends the flip command to the bebop. Gets the codes for it from the xml files. Ensures the
packet was received or sends it again up to a maximum number of times.
Valid directions to flip are: front, back, right, left
:return: True if the command was sent and False otherwise
"""
fixed_direction = direction.lower()
if (fixed_direction not in ("front", "back", "right", "left")):
print("Error: %s is not a valid direction. Must be one of %s" % direction, "front, back, right, or left")
print("Ignoring command and returning")
return
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("ardrone3",
"Animations", "Flip", fixed_direction)
# print command_tuple
# print enum_tuple
return self.drone_connection.send_enum_command_packet_ack(command_tuple, enum_tuple)
def move_relative(self, dx, dy, dz, dradians):
"""
Move relative to our current position and pause until the command is done. Note that
EVERY time we tested flying relative up (e.g. negative z) it did additional lateral moves
that were unnecessary. I'll be posting this to the development board but, until then,
I recommend only using dx, dy, and dradians which all seem to work well.
:param dx: change in front axis (meters)
:param dy: change in right/left (positive is right) (meters)
:param dz: change in height (positive is DOWN) (meters)
:param dradians: change in heading in radians
:return: nothing
"""
command_tuple = self.command_parser.get_command_tuple("ardrone3", "Piloting", "moveBy")
param_tuple = [dx, dy, dz, dradians] # Enable
param_type_tuple = ['float', 'float', 'float', 'float']
#reset the bit that tells when the move ends
self.sensors.RelativeMoveEnded = False
# send the command
self.drone_connection.send_param_command_packet(command_tuple, param_tuple, param_type_tuple)
# sleep until it ends
while (not self.sensors.RelativeMoveEnded):
self.smart_sleep(0.01)
def start_video_stream(self):
"""
Sends the start stream command to the bebop. The bebop will start streaming
RTP packets on the port defined in wifiConnection.py (55004 by default).
The packets can be picked up by opening an approriate SDP file in a media
player such as VLC, MPlayer, FFMPEG or OpenCV.
:return: nothing
"""
command_tuple = self.command_parser.get_command_tuple("ardrone3", "MediaStreaming", "VideoEnable")
param_tuple = [1] # Enable
param_type_tuple = ['u8']
self.drone_connection.send_param_command_packet(command_tuple,param_tuple,param_type_tuple)
def stop_video_stream(self):
"""
Sends the stop stream command to the bebop. The bebop will stop streaming
RTP packets.
:return: nothing
"""
command_tuple = self.command_parser.get_command_tuple("ardrone3", "MediaStreaming", "VideoEnable")
param_tuple = [0] # Disable
param_type_tuple = ['u8']
self.drone_connection.send_param_command_packet(command_tuple,param_tuple,param_type_tuple)
def set_video_stream_mode(self,mode='low_latency'):
"""
Set the video mode for the RTP stream.
:param: mode: one of 'low_latency', 'high_reliability' or 'high_reliability_low_framerate'
:return: True if the command was sent and False otherwise
"""
# handle case issues
fixed_mode = mode.lower()
if (fixed_mode not in ("low_latency", "high_reliability", "high_reliability_low_framerate")):
print("Error: %s is not a valid stream mode. Must be one of %s" % (mode, "low_latency, high_reliability or high_reliability_low_framerate"))
print("Ignoring command and returning")
return False
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("ardrone3",
"MediaStreaming", "VideoStreamMode", mode)
return self.drone_connection.send_enum_command_packet_ack(command_tuple,enum_tuple)
def pan_tilt_camera(self, tilt_degrees, pan_degrees):
"""
Send the command to pan/tilt the camera by the specified number of degrees in pan/tilt
Note, this only seems to work in small increments. Use pan_tilt_velocity to get the camera to look
straight downward
:param tilt_degrees: tilt degrees
:param pan_degrees: pan degrees
:return:
"""
if(self.drone_type == "Bebop2"):
command_tuple = self.command_parser.get_command_tuple("ardrone3", "Camera", "OrientationV2")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[tilt_degrees, pan_degrees],
param_type_tuple=['float', 'float'], ack=False)
else:
command_tuple = self.command_parser.get_command_tuple("ardrone3", "Camera", "Orientation")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[tilt_degrees, pan_degrees],
param_type_tuple=['i8', 'i8'], ack=False)
def pan_tilt_camera_velocity(self, tilt_velocity, pan_velocity, duration=0):
"""
Send the command to tilt the camera by the specified number of degrees per second in pan/tilt.
This function has two modes. First, if duration is 0, the initial velocity is sent and
then the function returns (meaning the camera will keep moving). If duration is greater than 0,
the command executes for that amount of time and then sends a stop command to the camera
and then returns.
:param tilt_degrees: tile change in degrees per second
:param pan_degrees: pan change in degrees per second
:param duration: seconds to run the command for
:return:
"""
command_tuple = self.command_parser.get_command_tuple("ardrone3", "Camera", "Velocity")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[tilt_velocity, pan_velocity],
param_type_tuple=['float', 'float'], ack=False)
if (duration > 0):
# wait for the specified duration
start_time = time.time()
while (time.time() - start_time < duration):
self.drone_connection.smart_sleep(0.1)
# send the stop command
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[0, 0],
param_type_tuple=['float', 'float'], ack=False)
def set_max_altitude(self, altitude):
"""
Set max altitude in meters.
:param altitude: altitude in meters
:return:
"""
if (altitude < 0.5 or altitude > 150):
print("Error: %s is not valid altitude. The altitude must be between 0.5 and 150 meters" % altitude)
print("Ignoring command and returning")
return
command_tuple = self.command_parser.get_command_tuple("ardrone3", "PilotingSettings", "MaxAltitude")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[altitude], param_type_tuple=['float'])
while (not self.sensors.max_altitude_changed):
self.smart_sleep(0.1)
def set_max_distance(self, distance):
"""
Set max distance between the takeoff and the drone in meters.
:param distance: distance in meters
:return:
"""
if (distance < 10 or distance > 2000):
print("Error: %s is not valid altitude. The distance must be between 10 and 2000 meters" % distance)
print("Ignoring command and returning")
return
command_tuple = self.command_parser.get_command_tuple("ardrone3", "PilotingSettings", "MaxDistance")
self.sensors.max_distance_changed = False
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[distance], param_type_tuple=['float'])
while (not self.sensors.max_distance_changed):
self.smart_sleep(0.1)
def enable_geofence(self, value):
"""
If geofence is enabled, the drone won't fly over the given max distance.
1 if the drone can't fly further than max distance, 0 if no limitation on the drone should be done.
:param value:
:return:
"""
if (value not in (0, 1)):
print("Error: %s is not valid value. Valid value: 1 to enable geofence/ 0 to disable geofence" % value)
print("Ignoring command and returning")
return
command_tuple = self.command_parser.get_command_tuple("ardrone3", "PilotingSettings", "NoFlyOverMaxDistance")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[value], param_type_tuple=['u8'])
while (not self.sensors.no_fly_over_max_distance_changed):
self.smart_sleep(0.1)
def set_max_tilt(self, tilt):
"""
Set max pitch/roll in degrees
:param tilt: max tilt for both pitch and roll in degrees
:return:
"""
if (tilt < 5 or tilt > 30):
print("Error: %s is not valid tilt. The tilt must be between 5 and 30 degrees" % tilt)
print("Ignoring command and returning")
return
command_tuple = self.command_parser.get_command_tuple("ardrone3", "PilotingSettings", "MaxTilt")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[tilt], param_type_tuple=['float'])
while (not self.sensors.max_tilt_changed):
self.smart_sleep(0.1)
def set_max_tilt_rotation_speed(self, speed):
"""
Set max pitch/roll rotation speed in degree/s
:param speed: max rotation speed for both pitch and roll in degree/s
:return:
"""
if (speed < 80 or speed > 300):
print("Error: %s is not valid speed. The speed must be between 80 and 300 degree/s" % speed)
print("Ignoring command and returning")
return
command_tuple = self.command_parser.get_command_tuple("ardrone3", "SpeedSettings", "MaxPitchRollRotationSpeed")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[speed], param_type_tuple=['float'])
while (not self.sensors.max_pitch_roll_rotation_speed_changed):
self.smart_sleep(0.1)
def set_max_vertical_speed(self, speed):
"""
Set max vertical speed in m/s
:param speed: max vertical speed in m/s
:return:
"""
if (speed < 0.5 or speed > 2.5):
print("Error: %s is not valid speed. The speed must be between 0.5 and 2.5 m/s" % speed)
print("Ignoring command and returning")
return
command_tuple = self.command_parser.get_command_tuple("ardrone3", "SpeedSettings", "MaxVerticalSpeed")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[speed], param_type_tuple=['float'])
while (not self.sensors.max_vertical_speed_changed):
self.smart_sleep(0.1)
def set_max_rotation_speed(self, speed):
"""
Set max yaw rotation speed in degree/s
:param speed: max rotation speed for yaw in degree/s
:return:
"""
if (speed < 10 or speed > 200):
print("Error: %s is not valid speed. The speed must be between 10 and 200 degree/s" % speed)
print("Ignoring command and returning")
return
command_tuple = self.command_parser.get_command_tuple("ardrone3", "SpeedSettings", "MaxRotationSpeed")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[speed], param_type_tuple=['float'])
while (not self.sensors.max_rotation_speed_changed):
self.smart_sleep(0.1)
def set_hull_protection(self, present):
"""
Set the presence of hull protection - this is only needed for bebop 1
1 if present, 0 if not present
:param present:
:return:
"""
if (present not in (0, 1)):
print("Error: %s is not valid value. The value must be 0 or 1" % present)
print("Ignoring command and returning")
return
command_tuple = self.command_parser.get_command_tuple("ardrone3", "SpeedSettings", "HullProtection")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[present], param_type_tuple=['u8'])
while (not self.sensors.hull_protection_changed):
self.smart_sleep(0.1)
def set_indoor(self, is_outdoor):
"""
Set bebop 1 to indoor mode (not used in bebop 2!!)
1 if outdoor, 0 if indoor
:param present:
:return:
"""
if (is_outdoor not in (0, 1)):
print("Error: %s is not valid value. The value must be 0 or 1" % is_outdoor)
print("Ignoring command and returning")
return
command_tuple = self.command_parser.get_command_tuple("ardrone3", "SpeedSettings", "Outdoor")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[is_outdoor], param_type_tuple=['u8'])
#while (not self.sensors.outdoor_mode_changed):
# self.smart_sleep(0.1)
def set_picture_format(self, format):
"""
Set picture format
:param format:
:return:
"""
if (format not in ('raw', 'jpeg', 'snapshot', 'jpeg_fisheye')):
print("Error: %s is not valid value. The value must be : raw, jpeg, snapshot, jpeg_fisheye" % format)
print("Ignoring command and returning")
return
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("ardrone3", "PictureSettings", "PictureFormatSelection", format)
self.drone_connection.send_enum_command_packet_ack(command_tuple, enum_tuple)
while (not self.sensors.picture_format_changed):
self.smart_sleep(0.1)
def set_white_balance(self, type):
"""
Set white balance
:param type:
:return:
"""
if (type not in ('auto', 'tungsten', 'daylight', 'cloudy', 'cool_white')):
print("Error: %s is not valid value. The value must be : auto, tungsten, daylight, cloudy, cool_white" % type)
print("Ignoring command and returning")
return
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("ardrone3", "PictureSettings", "AutoWhiteBalanceSelection", type)
self.drone_connection.send_enum_command_packet_ack(command_tuple, enum_tuple)
while (not self.sensors.auto_white_balance_changed):
self.smart_sleep(0.1)
def set_exposition(self, value):
"""
Set image exposure
:param value:
:return:
"""
if (value < -1.5 or value > 1.5):
print("Error: %s is not valid image exposure. The value must be between -1.5 and 1.5." % value)
print("Ignoring command and returning")
return
command_tuple = self.command_parser.get_command_tuple("ardrone3", "PictureSettings", "ExpositionSelection")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[value], param_type_tuple=['float'])
while (not self.sensors.exposition_changed):
self.smart_sleep(0.1)
def set_saturation(self, value):
"""
Set image saturation
:param value:
:return:
"""
if (value < -100 or value > 100):
print("Error: %s is not valid image saturation. The value must be between -100 and 100." % value)
print("Ignoring command and returning")
return
command_tuple = self.command_parser.get_command_tuple("ardrone3", "PictureSettings", "SaturationSelection")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[value], param_type_tuple=['float'])
while (not self.sensors.saturation_changed):
self.smart_sleep(0.1)
def set_timelapse(self, enable, interval=8):
"""
Set timelapse mode
:param enable:
:param interval:
:return:
"""
if (enable not in (0, 1) or interval < 8 or interval > 300):
print("Error: %s or %s is not valid value." % (enable, interval))
print("Ignoring command and returning")
return
command_tuple = self.command_parser.get_command_tuple("ardrone3", "PictureSettings", "TimelapseSelection")
self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[enable, interval], param_type_tuple=['u8', 'float'])
while (not self.sensors.timelapse_changed):
self.smart_sleep(0.1)
def set_video_stabilization(self, mode):
"""
Set video stabilization mode
:param mode:
:return:
"""
if (mode not in ('roll_pitch', 'pitch', 'roll', 'none')):
print("Error: %s is not valid value. The value must be : roll_pitch, pitch, roll, none" % mode)
print("Ignoring command and returning")
return
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("ardrone3", "PictureSettings", "VideoStabilizationMode", mode)
self.drone_connection.send_enum_command_packet_ack(command_tuple, enum_tuple)
while (not self.sensors.video_stabilization_changed):
self.smart_sleep(0.1)
def set_video_recording(self, mode):
"""
Set video recording mode
:param mode:
:return:
"""
if (mode not in ('quality', 'time')):
print("Error: %s is not valid value. The value must be : quality, time" % mode)
print("Ignoring command and returning")
return
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("ardrone3", "PictureSettings", "VideoRecordingMode", mode)
self.drone_connection.send_enum_command_packet_ack(command_tuple, enum_tuple)
while (not self.sensors.video_recording_changed):
self.smart_sleep(0.1)
def set_video_framerate(self, framerate):
"""
Set video framerate
:param framerate:
:return:
"""
if (framerate not in ('24_FPS', '25_FPS', '30_FPS')):
print("Error: %s is not valid value. The value must be : 24_FPS, 25_FPS, 30_FPS" % framerate)
print("Ignoring command and returning")
return
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("ardrone3", "PictureSettings", "VideoFramerate", framerate)
self.drone_connection.send_enum_command_packet_ack(command_tuple, enum_tuple)
while (not self.sensors.video_framerate_changed):
self.smart_sleep(0.1)
def set_video_resolutions(self, type):
"""
Set video resolutions
:param type:
:return:
"""
if (type not in ('rec1080_stream480', 'rec720_stream720')):
print("Error: %s is not valid value. The value must be : rec1080_stream480, rec720_stream720" % type)
print("Ignoring command and returning")
return
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("ardrone3", "PictureSettings", "VideoResolutions", type)
self.drone_connection.send_enum_command_packet_ack(command_tuple, enum_tuple)
while (not self.sensors.video_resolutions_changed):
self.smart_sleep(0.1)

View File

@ -0,0 +1,295 @@
"""
DroneVision is separated from the main Mambo/Bebop class to enable the use of the drone without the FPV camera.
If you want to do vision processing, you will need to create a DroneVision object to capture the
video stream.
Note that this module relies on the opencv module and the ffmpeg program
Ffmpeg write the images out to the images directory and then they are read in from the user thread. The DroneVisionGUI
does not save copies of the images and instead shows you the images on the screen (they are saved to memory only).
While you can see the images in real-time from this program using VisionServer, if you need copies of the images,
you will want to use the ffmpeg approach. If you want a smaller delay on your image data for real-time control, you likely want
to use libvlc and DroneVisionGUI.
Author: Amy McGovern, dramymcgovern@gmail.com
"""
import cv2
import threading
import time
import subprocess
import os
from os.path import join
import inspect
from pyparrot.utils.NonBlockingStreamReader import NonBlockingStreamReader
import shutil
import signal
class DroneVision:
def __init__(self, drone_object, is_bebop, buffer_size=200, cleanup_old_images=True):
"""
Setup your vision object and initialize your buffers. You won't start seeing pictures
until you call open_video.
:param drone_object reference to the drone (mambo or bebop) object
:param is_bebop: True if it is a bebop and false if it is a mambo
:param buffer_size: number of frames to buffer in memory. Defaults to 10.
:param cleanup_old_images: clean up the old images in the directory (defaults to True, set to false to keep old data around)
"""
self.fps = 30
self.buffer_size = buffer_size
self.drone_object = drone_object
self.is_bebop = is_bebop
self.cleanup_old_images = cleanup_old_images
# initialize a buffer (will contain the last buffer_size vision objects)
self.buffer = [None] * buffer_size
self.buffer_index = 0
# setup the thread for monitoring the vision (but don't start it until we connect in open_video)
self.vision_thread = threading.Thread(target=self._buffer_vision,
args=(buffer_size, ))
self.user_vision_thread = None
self.vision_running = True
# the vision thread starts opencv on these files. That will happen inside the other thread
# so here we just sent the image index to 1 ( to start)
self.image_index = 1
def set_user_callback_function(self, user_callback_function=None, user_callback_args=None):
"""
Set the (optional) user callback function for handling the new vision frames. This is
run in a separate thread that starts when you start the vision buffering
:param user_callback_function: function
:param user_callback_args: arguments to the function
:return:
"""
self.user_vision_thread = threading.Thread(target=self._user_callback,
args=(user_callback_function, user_callback_args))
def open_video(self):
"""
Open the video stream using ffmpeg for capturing and processing. The address for the stream
is the same for all Mambos and is documented here:
http://forum.developer.parrot.com/t/streaming-address-of-mambo-fpv-for-videoprojection/6442/6
Remember that this will only work if you have connected to the wifi for your mambo!
Note that the old method tried to open the stream directly into opencv but there are known issues
with rtsp streams in opencv. We bypassed opencv to use ffmpeg directly and then opencv is used to
process the output of ffmpeg
:return True if the vision opened correctly and False otherwise
"""
# start the stream on the bebop
if (self.is_bebop):
self.drone_object.start_video_stream()
# we have bypassed the old opencv VideoCapture method because it was unreliable for rtsp
# get the path for the config files
fullPath = inspect.getfile(DroneVision)
shortPathIndex = fullPath.rfind("/")
if (shortPathIndex == -1):
# handle Windows paths
shortPathIndex = fullPath.rfind("\\")
print(shortPathIndex)
shortPath = fullPath[0:shortPathIndex]
self.imagePath = join(shortPath, "images")
self.utilPath = join(shortPath, "utils")
print(self.imagePath)
print(self.utilPath)
if (self.cleanup_old_images):
print("removing all the old images")
shutil.rmtree(self.imagePath)
os.mkdir(self.imagePath)
# the first step is to open the rtsp stream through ffmpeg first
# this step creates a directory full of images, one per frame
print("Opening ffmpeg")
if (self.is_bebop):
cmdStr = "ffmpeg -protocol_whitelist \"file,rtp,udp\" -i %s/bebop.sdp -r 30 image_" % self.utilPath + "%03d.png"
print(cmdStr)
self.ffmpeg_process = \
subprocess.Popen(cmdStr, shell=True, cwd=self.imagePath, stderr=subprocess.PIPE, stdout=subprocess.PIPE)
else:
self.ffmpeg_process = \
subprocess.Popen("ffmpeg -i rtsp://192.168.99.1/media/stream2 -r 30 image_%03d.png",
shell=True, cwd=self.imagePath, stderr=subprocess.PIPE, stdout=subprocess.PIPE)
# immediately start the vision buffering (before we even know if it succeeded since waiting puts us behind)
self._start_video_buffering()
# open non-blocking readers to look for errors or success
print("Opening non-blocking readers")
stderr_reader = NonBlockingStreamReader(self.ffmpeg_process.stderr)
stdout_reader = NonBlockingStreamReader(self.ffmpeg_process.stdout)
# look for success in the stdout
# If it starts correctly, it will have the following output in the stdout
# Stream mapping:
# Stream #0:0 -> #0:0 (h264 (native) -> png (native))
# if it fails, it has the following in stderr
# Output file #0 does not contain any stream
success = False
while (not success):
line = stderr_reader.readline()
if (line is not None):
line_str = line.decode("utf-8")
print(line_str)
if line_str.find("Stream #0:0 -> #0:0 (h264 (native) -> png (native))") > -1:
success = True
break
if line_str.find("Output file #0 does not contain any stream") > -1:
print("Having trouble connecting to the camera 1. A reboot of the mambo may help.")
break
line = stdout_reader.readline()
if (line is not None):
line_str = line.decode("utf-8")
print(line_str)
if line_str.find("Output file #0 does not contain any stream") > -1:
print("Having trouble connecting to the camera 2. A reboot of the mambo may help.")
break
if line_str.find("Stream #0:0 -> #0:0 (h264 (native) -> png (native))") > -1:
success = True
# cleanup our non-blocking readers no matter what happened
stdout_reader.finish_reader()
stderr_reader.finish_reader()
# return whether or not it worked
return success
def _start_video_buffering(self):
"""
If the video capture was successfully opened, then start the thread to buffer the stream
:return: Nothing
"""
print("starting vision thread")
self.vision_thread.start()
if (self.user_vision_thread is not None):
self.user_vision_thread.start()
def _user_callback(self, user_vision_function, user_args):
"""
Internal method to call the user vision functions
:param user_vision_function: user callback function to handle vision
:param user_args: optional arguments to the user callback function
:return:
"""
while (self.vision_running):
if (self.new_frame):
user_vision_function(user_args)
#reset the bit for a new frame
self.new_frame = False
# put the thread back to sleep for fps
# sleeping shorter to ensure we stay caught up on frames
time.sleep(1.0 / (3.0 * self.fps))
def _buffer_vision(self, buffer_size):
"""
Internal method to save valid video captures from the camera fps times a second
:param buffer_size: number of images to buffer (set in init)
:return:
"""
# start with no new data
self.new_frame = False
# when the method is first called, sometimes there is already data to catch up on
# so find the latest image in the directory and set the index to that
found_latest = False
while (not found_latest):
path = "%s/image_%03d.png" % (self.imagePath, self.image_index)
if (os.path.exists(path)) and (not os.path.isfile(path)):
# just increment through it (don't save any of these first images)
self.image_index = self.image_index + 1
else:
found_latest = True
# run forever, trying to grab the latest image
while (self.vision_running):
# grab the latest image from the ffmpeg stream
try:
# make the name for the next image
path = "%s/image_%03d.png" % (self.imagePath, self.image_index)
if (not os.path.exists(path)) and (not os.path.isfile(path)):
#print("File %s doesn't exist" % (path))
#print(os.listdir(self.imagePath))
continue
img = cv2.imread(path,1)
# sometimes cv2 returns a None object so skip putting those in the array
if (img is not None):
self.image_index = self.image_index + 1
# got a new image, save it to the buffer directly
self.buffer_index += 1
self.buffer_index %= buffer_size
#print video_frame
self.buffer[self.buffer_index] = img
self.new_frame = True
except cv2.error:
#Assuming its an empty image, so decrement the index and try again.
# print("Trying to read an empty png. Let's wait and try again.")
self.image_index = self.image_index - 1
continue
# put the thread back to sleep for faster than fps to ensure we stay on top of the frames
# coming in from ffmpeg
time.sleep(1.0 / (2.0 * self.fps))
def get_latest_valid_picture(self):
"""
Return the latest valid image (from the buffer)
:return: last valid image received from the Mambo
"""
return self.buffer[self.buffer_index]
def close_video(self):
"""
Stop the vision processing and all its helper threads
"""
# the helper threads look for this variable to be true
self.vision_running = False
# kill the ffmpeg subprocess
print("Killing the ffmpeg subprocess")
self.ffmpeg_process.kill()
self.ffmpeg_process.terminate()
time.sleep(3)
if (self.ffmpeg_process.poll() is not None):
print("Sending a second kill call to the ffmpeg process")
self.ffmpeg_process.kill()
self.ffmpeg_process.terminate()
time.sleep(3)
# send the command to kill the vision stream (bebop only)
if (self.is_bebop):
self.drone_object.stop_video_stream()

View File

@ -0,0 +1,473 @@
"""
DroneVisionGUI is a new class that parallels DroneVision but with several important changes.
1) This module uses VLC instead of FFMPEG
2) This module opens a GUI window to show you the video in real-time (you could
watch it in real-time previously through the VisionServer)
3) Because GUI windows are different on different OS's (and in particular OS X behaves differently
than linux and windows) and because they want to run in the main program thread, the way your program runs
is different. You first open the GUI and then you have the GUI spawn a thread to run your program.
4) This module can use a virtual disk in memory to save the images, thus shortening the time delay for the
camera for your programs.
Author: Amy McGovern, dramymcgovern@gmail.com
Some of the LIBVLC code comes from
Author: Valentin Benke, valentin.benke@aon.at
"""
import cv2
import time
from functools import partial
from os.path import join
import inspect
import tempfile
import sys
import pyparrot.utils.vlc as vlc
from PyQt5.QtCore import Qt, QTimer, QThread
from PyQt5.QtGui import QPalette, QColor, QPixmap
from PyQt5.QtWidgets import QMainWindow, QWidget, QFrame, QSlider, QHBoxLayout, QPushButton, \
QVBoxLayout, QAction, QFileDialog, QApplication, QLabel
class Player(QMainWindow):
"""
Modification of the simple Media Player using VLC and Qt
to show the mambo stream
The window part of this example was modified from the QT example cited below.
VLC requires windows to create and show the video and this was a cross-platform solution.
VLC will automatically create the windows in linux but not on the mac.
Amy McGovern, dramymcgovern@gmail.com
Qt example for VLC Python bindings
https://github.com/devos50/vlc-pyqt5-example
Copyright (C) 2009-2010 the VideoLAN team
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 2 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program; if not, write to the Free Software
Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston MA 02110-1301, USA.
"""
def __init__(self, vlc_player, drone_gui):
"""
Create a UI window for the VLC player
:param vlc_player: the VLC player (created outside the function)
"""
QMainWindow.__init__(self)
self.setWindowTitle("VLC Drone Video Player")
# save the media player
self.mediaplayer = vlc_player
# need a reference to the main drone vision class
self.drone_vision = drone_gui
# create the GUI
self.createUI()
def createUI(self):
"""
Set up the window for the VLC viewer
"""
self.widget = QWidget(self)
self.setCentralWidget(self.widget)
# In this widget, the video will be drawn
if sys.platform == "darwin": # for MacOS
from PyQt5.QtWidgets import QMacCocoaViewContainer
self.videoframe = QMacCocoaViewContainer(0)
else:
self.videoframe = QFrame()
self.palette = self.videoframe.palette()
self.palette.setColor (QPalette.Window,
QColor(0,0,0))
self.videoframe.setPalette(self.palette)
self.videoframe.setAutoFillBackground(True)
self.hbuttonbox = QHBoxLayout()
self.playbutton = QPushButton("Run my program")
self.hbuttonbox.addWidget(self.playbutton)
self.playbutton.clicked.connect(partial(self.drone_vision.run_user_code, self.playbutton))
self.landbutton = QPushButton("Land NOW")
self.hbuttonbox.addWidget(self.landbutton)
self.landbutton.clicked.connect(self.drone_vision.land)
self.stopbutton = QPushButton("Quit")
self.hbuttonbox.addWidget(self.stopbutton)
self.stopbutton.clicked.connect(self.drone_vision.close_exit)
self.vboxlayout = QVBoxLayout()
self.vboxlayout.addWidget(self.videoframe)
if (self.drone_vision.user_draw_window_fn is not None):
self.userWindow = QLabel()
fullPath = inspect.getfile(DroneVisionGUI)
shortPathIndex = fullPath.rfind("/")
if (shortPathIndex == -1):
# handle Windows paths
shortPathIndex = fullPath.rfind("\\")
print(shortPathIndex)
shortPath = fullPath[0:shortPathIndex]
pixmap = QPixmap('%s/demo_user_image.png' % shortPath)
print(pixmap)
print(pixmap.isNull())
self.userWindow.setPixmap(pixmap)
self.vboxlayout.addWidget(self.userWindow)
self.vboxlayout.addLayout(self.hbuttonbox)
self.widget.setLayout(self.vboxlayout)
# the media player has to be 'connected' to the QFrame
# (otherwise a video would be displayed in it's own window)
# this is platform specific!
# you have to give the id of the QFrame (or similar object) to
# vlc, different platforms have different functions for this
if sys.platform.startswith('linux'): # for Linux using the X Server
self.mediaplayer.set_xwindow(self.videoframe.winId())
elif sys.platform == "win32": # for Windows
self.mediaplayer.set_hwnd(self.videoframe.winId())
elif sys.platform == "darwin": # for MacOS
self.mediaplayer.set_nsobject(int(self.videoframe.winId()))
class UserVisionProcessingThread(QThread):
def __init__(self, user_vision_function, user_args, drone_vision):
"""
:param user_vision_function: user callback function to handle vision
:param user_args: optional arguments to the user callback function
"""
QThread.__init__(self)
self.user_vision_function = user_vision_function
self.user_args = user_args
self.drone_vision = drone_vision
def __del__(self):
self.wait()
def run(self):
print("user callback being called")
while (self.drone_vision.vision_running):
self.user_vision_function(self.user_args)
# put the thread back to sleep for fps
# sleeping shorter to ensure we stay caught up on frames
time.sleep(1.0 / (3.0 * self.drone_vision.fps))
# exit when the vision thread ends
print("exiting user vision thread")
self.terminate()
class UserWindowDrawThread(QThread):
def __init__(self, user_draw_function, drone_vision):
"""
:param user_draw_function: user drawing function that should return an image
"""
QThread.__init__(self)
self.user_draw_function = user_draw_function
self.drone_vision = drone_vision
def __del__(self):
self.wait()
def run(self):
#print("user window draw thread being called")
while (self.drone_vision.vision_running):
img = self.user_draw_function()
if(img is not None):
if (not img.isNull()):
self.drone_vision.vlc_gui.userWindow.setPixmap(QPixmap.fromImage(img))
# put the thread back to sleep for fps
# sleeping shorter to ensure we stay caught up on frames
time.sleep(1.0 / (3.0 * self.drone_vision.fps))
# exit when the vision thread ends
print("exiting user window draw thread")
self.terminate()
class UserCodeToRun(QThread):
def __init__(self, user_function, user_args, drone_vision):
"""
:param user_function: user code to run (presumably flies the drone)
:param user_args: optional arguments to the user function
"""
QThread.__init__(self)
self.user_vision_function = user_function
self.user_args = user_args
self.drone_vision = drone_vision
def __del__(self):
self.wait()
def run(self):
self.user_vision_function(self.drone_vision, self.user_args)
class DroneVisionGUI:
def __init__(self, drone_object, is_bebop, user_code_to_run, user_args, buffer_size=200, network_caching=200, fps=20, user_draw_window_fn=None):
"""
Setup your vision object and initialize your buffers. You won't start seeing pictures
until you call open_video.
:param drone_object reference to the drone (mambo or bebop) object
:param is_bebop: True if it is a bebop and false if it is a mambo
:param user_code_to_run: user code to run with the run button (remember
this is needed due to the GUI taking the thread)
:param user_args: arguments to the user code
:param buffer_size: number of frames to buffer in memory. Defaults to 10.
:param network_caching: buffering time in milli-seconds, 200 should be enough, 150 works on some devices (Mac OS X ignores this argument)
:param fps: frame rate for the vision
:param user_window: set to a function to be called to draw a QImage and None otherwise (default None)
"""
self.fps = fps
self.vision_interval = int(1000 * 1.0 / self.fps)
self.buffer_size = buffer_size
self.drone_object = drone_object
self.is_bebop = is_bebop
# initialize a buffer (will contain the last buffer_size vision objects)
self.buffer = [None] * buffer_size
self.buffer_size = buffer_size
self.buffer_index = 0
# vision threading is done from a QTimer instead of a separate thread
self.new_frame = False
self.vision_running = True
# the vision thread starts opencv on these files. That will happen inside the other thread
# so here we just sent the image index to 1 ( to start)
self.image_index = 1
# save the caching parameters and choice of libvlc
self.network_caching = network_caching
# save the user function and args for calling from the run button
self.user_code_to_run = user_code_to_run
self.user_args = user_args
self.user_thread = UserCodeToRun(user_code_to_run, user_args, self)
# if we are drawing a special user window
self.user_draw_window_fn = user_draw_window_fn
if (self.user_draw_window_fn is not None):
self.user_window_draw_thread = UserWindowDrawThread(self.user_draw_window_fn, self)
else:
self.user_window_draw_thread = None
# in case we never setup a user callback function
self.user_vision_thread = None
# has the land button been clicked - saved in case the user needs it in their code
self.land_button_clicked = False
def run_user_code(self, button):
"""
Start the thread to run the user code
:return:
"""
button.setEnabled(False)
self.user_thread.start()
def set_user_callback_function(self, user_callback_function=None, user_callback_args=None):
"""
Set the (optional) user callback function for handling the new vision frames. This is
run in a separate thread that starts when you start the vision buffering
:param user_callback_function: function
:param user_callback_args: arguments to the function
:return:
"""
self.user_vision_thread = UserVisionProcessingThread(user_callback_function, user_callback_args, self)
def open_video(self):
"""
Open the video stream using vlc. Note that this version is blocking meaning
this function will NEVER return. If you want to run your own code and not just
watch the video, be sure you set your user code in the constructor!
Remember that this will only work if you have connected to the wifi for your mambo!
:return never returns due to QT running in the main loop by requirement
"""
# start the stream on the bebop
if (self.is_bebop):
self.drone_object.start_video_stream()
# we have bypassed the old opencv VideoCapture method because it was unreliable for rtsp
# get the path for the config files
fullPath = inspect.getfile(DroneVisionGUI)
shortPathIndex = fullPath.rfind("/")
if (shortPathIndex == -1):
# handle Windows paths
shortPathIndex = fullPath.rfind("\\")
print(shortPathIndex)
shortPath = fullPath[0:shortPathIndex]
self.imagePath = join(shortPath, "images")
self.utilPath = join(shortPath, "utils")
print(self.imagePath)
print(self.utilPath)
if self.is_bebop:
# generate the streaming-address for the Bebop
self.utilPath = join(shortPath, "utils")
self.stream_adress = "%s/bebop.sdp" % self.utilPath
else:
# generate the streaming-address for the Mambo
self.stream_adress = "rtsp://192.168.99.1/media/stream2"
# initialise the vlc-player with the network-caching
self.player = vlc.MediaPlayer(self.stream_adress, ":network-caching=" + str(self.network_caching))
# start the buffering
success = self._start_video_buffering()
def _start_video_buffering(self):
"""
If the video capture was successfully opened, then start the thread to buffer the stream
:return: if using libvlc this will return whether or not the player started
"""
# open/draw the GUI
app = QApplication(sys.argv)
self.vlc_gui = Player(vlc_player=self.player, drone_gui=self)
self.vlc_gui.show()
self.vlc_gui.resize(640, 480)
# ensure that closing the window closes vision
app.aboutToQuit.connect(self.land_close_exit)
if (self.user_vision_thread is not None):
print("Starting user vision thread")
self.user_vision_thread.start()
if (self.user_draw_window_fn is not None):
print("Starting user drawing thread")
self.user_window_draw_thread.start()
# setup the timer for snapshots
self.timer = QTimer(self.vlc_gui)
self.timer.setInterval(self.vision_interval)
self.timer.timeout.connect(self._buffer_vision)
self.timer.start()
# show the stream
success = self.player.play()
print("success from play call is %s " % success)
# start the GUI loop
app.exec()
def _buffer_vision(self):
"""
Internal method to save valid video captures from the camera fps times a second
:return:
"""
# start with no new data
self.new_frame = False
# run forever, trying to grab the latest image
if (self.vision_running):
# generate a temporary file, gets deleted after usage automatically
#self.file = tempfile.NamedTemporaryFile(dir=self.imagePath)
self.file = join(self.imagePath, "visionStream.jpg")
#self.file = tempfile.SpooledTemporaryFile(max_size=32768)
# save the current picture from the stream
self.player.video_take_snapshot(0, self.file, 0, 0)
# read the picture into opencv
img = cv2.imread(self.file)
# sometimes cv2 returns a None object so skip putting those in the array
if (img is not None):
# got a new image, save it to the buffer directly
self.buffer_index += 1
self.buffer_index %= self.buffer_size
#print video_frame
self.buffer[self.buffer_index] = img
self.new_frame = True
def get_latest_valid_picture(self):
"""
Return the latest valid image (from the buffer)
:return: last valid image received from the Mambo
"""
return self.buffer[self.buffer_index]
def close_exit(self):
"""
Land, close the video, and exit the GUI
:return:
"""
self.close_video()
self.vlc_gui.close()
self.vlc_gui.destroy()
# kill the threads
if (self.user_window_draw_thread is not None):
self.user_window_draw_thread.quit()
self.user_vision_thread.quit()
self.user_thread.quit()
# this is hanging on Mac OS X when it tries to exit and I'm not sure why. The threads are properly
# exiting
sys.exit()
def land_close_exit(self):
"""
Called if you Quit the GUI: lands the drone, stops vision, and exits the GUI
:return:
"""
self.land()
self.close_exit()
def land(self):
"""
Send the land command over the emergency channel when the user pushes the button
:return:
"""
# tell the user that the land button was clicked
self.land_button_clicked = True
# land the drone
if (self.is_bebop):
if (not self.drone_object.is_landed()):
self.drone_object.emergency_land()
else:
if (not self.drone_object.is_landed()):
self.drone_object.safe_land(5)
def close_video(self):
"""
Stop the vision processing and all its helper threads
"""
# the helper threads look for this variable to be true
self.vision_running = False
self.player.stop()
# send the command to kill the vision stream (bebop only)
if (self.is_bebop):
self.drone_object.stop_video_stream()

View File

@ -0,0 +1,804 @@
"""
Mambo class holds all of the methods needed to pilot the drone from python and to ask for sensor
data back from the drone
Author: Amy McGovern, dramymcgovern@gmail.com
Author: Alexander Zach, https://github.com/alex-zach, groundcam support
Author: Valentin Benke, https://github.com/Vabe7, groundcam support
"""
import time
from pyparrot.networking.wifiConnection import WifiConnection
try:
from pyparrot.networking.bleConnection import BLEConnection
BLEAvailable = True
except:
BLEAvailable = False
from pyparrot.utils.colorPrint import color_print
from pyparrot.commandsandsensors.DroneCommandParser import DroneCommandParser
from pyparrot.commandsandsensors.DroneSensorParser import DroneSensorParser
import math
from os.path import join
import inspect
#Groundcam Imports
from ftplib import FTP
import tempfile
try:
import cv2
OpenCVAvailable = True
print("OpenCVAvailable is %s" % OpenCVAvailable)
except:
OpenCVAvailable = False
print("OpenCVAvailable is %s" % OpenCVAvailable)
class MinidroneSensors:
"""
Store the minidrone's last known sensor values
"""
def __init__(self):
# default to full battery
self.battery = 100
# drone on the ground
self.flying_state = "landed"
# dictionary for extra sensors
self.sensors_dict = dict()
self.gun_id = 0
self.gun_state = None
self.claw_id = 0
self.claw_state = None
self.flying_mode = "quadricopter"
self.plane_gear_box = "gear_1"
# new SDK sends speed, altitude, and quaternions
self.speed_x = 0
self.speed_y = 0
self.speed_z = 0
self.speed_ts = 0
# these are only available on wifi
self.altitude = -1
self.altitude_ts = 0
self.quaternion_w = 0
self.quaternion_x = 0
self.quaternion_y = 0
self.quaternion_z = 0
self.quaternion_ts = -1
# this is optionally set elsewhere
self.user_callback_function = None
def set_user_callback_function(self, function, args):
"""
Sets the user callback function (called everytime the sensors are updated)
:param function: name of the user callback function
:param args: arguments (tuple) to the function
:return:
"""
self.user_callback_function = function
self.user_callback_function_args = args
def update(self, name, value, sensor_enum):
"""
Update the sensor
:param name: name of the sensor to update
:param value: new value for the sensor
:param sensor_enum: enum list for the sensors that use enums so that we can translate from numbers to strings
:return:
"""
#print("updating sensor %s" % name)
#print(value)
if (name is None):
print("Error empty sensor")
return
if (name, "enum") in sensor_enum:
# grab the string value
if (value > len(sensor_enum[(name, "enum")])):
value = "UNKNOWN_ENUM_VALUE"
else:
enum_value = sensor_enum[(name, "enum")][value]
value = enum_value
# add it to the sensors
if (name == "BatteryStateChanged_battery_percent"):
self.battery = value
elif (name == "FlyingStateChanged_state"):
self.flying_state = value
elif (name == "ClawState_id"):
self.claw_id = value
elif (name == "ClawState_state"):
self.claw_state = value
elif (name == "GunState_id"):
self.gun_id = value
elif (name == "GunState_state"):
self.gun_state = value
elif (name == "DroneSpeed_speed_x"):
self.speed_x = value
elif (name == "DroneSpeed_speed_y"):
self.speed_y = value
elif (name == "DroneSpeed_speed_z"):
self.speed_z = value
elif (name == "DroneSpeed_ts"):
self.speed_ts = value
elif (name == "DroneAltitude_altitude"):
self.altitude = value
elif (name == "DroneAltitude_ts"):
self.altitude_ts = value
elif (name == "DroneQuaternion_q_w"):
self.quaternion_w = value
elif (name == "DroneQuaternion_q_x"):
self.quaternion_x = value
elif (name == "DroneQuaternion_q_y"):
self.quaternion_y = value
elif (name == "DroneQuaternion_q_z"):
self.quaternion_z = value
elif (name == "DroneQuaternion_ts"):
self.quaternion_ts = value
elif (name == "FlyingModeChanged_mode"):
self.flying_mode = value
elif (name == "PlaneGearBoxChanged_state"):
self.plane_gear_box = value
else:
#print "new sensor - add me to the struct but saving in the dict for now"
self.sensors_dict[name] = value
# call the user callback if it isn't None
if (self.user_callback_function is not None):
self.user_callback_function(self.user_callback_function_args)
def get_estimated_z_orientation(self):
"""
Uses the quaternions to return an estimated orientation
Learn more about unit quaternions here:
https://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation
NOTE: This is not a real compass heading. 0 degrees is where you are facing when
the mambo turns on!
:return:
"""
(X, Y, Z) = self.quaternion_to_euler_angle(self.quaternion_w, self.quaternion_x,
self.quaternion_y, self.quaternion_z)
return Z
def quaternion_to_euler_angle(self, w, x, y, z):
"""
This code is directly from:
https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles
:param x:
:param y:
:param z:
:return:
"""
ysqr = y * y
t0 = +2.0 * (w * x + y * z)
t1 = +1.0 - 2.0 * (x * x + ysqr)
X = math.degrees(math.atan2(t0, t1))
t2 = +2.0 * (w * y - z * x)
t2 = +1.0 if t2 > +1.0 else t2
t2 = -1.0 if t2 < -1.0 else t2
Y = math.degrees(math.asin(t2))
t3 = +2.0 * (w * z + x * y)
t4 = +1.0 - 2.0 * (ysqr + z * z)
Z = math.degrees(math.atan2(t3, t4))
return X, Y, Z
def __str__(self):
"""
Make a nicely printed struct for debugging
:return: string for print calls
"""
my_str = "mambo state: battery %d, " % self.battery
my_str += "flying state is %s, " % self.flying_state
my_str += "speed (x, y, z) and ts is (%f, %f, %f) at %f " % (self.speed_x, self.speed_y, self.speed_z, self.speed_ts)
if (self.altitude_ts > -1):
my_str += "altitude (m) %f and ts is %f " % (self.altitude, self.altitude_ts)
if (self.quaternion_ts > -1):
my_str += "quaternion (w, x, y, z) and ts is (%f, %f, %f, %f) at %f " % (
self.quaternion_w, self.quaternion_x, self.quaternion_y, self.quaternion_z, self.quaternion_ts)
my_str += "gun id: %d, state %s, " % (self.gun_id, self.gun_state)
my_str += "claw id: %d, state %s, " % (self.claw_id, self.claw_state)
my_str += "extra sensors: %s," % self.sensors_dict
return my_str
class MamboGroundcam:
def __init__(self):
"""
Initialises the FTP-Session for the picture-download.
Only works with WiFi.
"""
self.MEDIA_PATH = '/internal_000/mambo/media' # Filepath on the Mambo
# groundcam remains broken on 3.0.26 and now it times out
#try:
# self.ftp = FTP('192.168.99.3') # IP-Address of the drone itself
# login = self.ftp.login()
# print("FTP login success is %s" % login)
#except:
print("ERROR: ftp login is disabled by parrot firmware 3.0.25 and 26. Groundcam will not work.")
self.ftp = None
# get the path for the config files
fullPath = inspect.getfile(Mambo)
shortPathIndex = fullPath.rfind("/")
if (shortPathIndex == -1):
# handle Windows paths
shortPathIndex = fullPath.rfind("\\")
print(shortPathIndex)
shortPath = fullPath[0:shortPathIndex]
self.imagePath = join(shortPath, "images")
self.storageFile = join(self.imagePath, "groundcam.jpg")
print(self.storageFile)
#self.storageFile = tempfile.NamedTemporaryFile()
def _close(self):
if (self.ftp is not None):
self.ftp.close()
def get_groundcam_pictures_names(self):
"""
Retruns a list with the names of the pictures stored on the Mambo.
:return The list as an array, if there isn't any file, the array is empty.
"""
if (self.ftp is None):
return list()
else:
self.ftp.cwd(self.MEDIA_PATH)
list = self.ftp.nlst()
list = sorted(list)
return list
def get_groundcam_picture(self, filename, cv2_flag):
"""
Downloads the specified picture from the Mambo and stores it into a tempfile.
:param filename: the name of the file which should be downloaded ON THE MAMBO.
:param cv2_flag: if true this function will return a cv2 image object, if false the name of the temporary file will be returned
:return False if there was an error during download, if cv2 is True a cv2 frame or it just returns the file name of the temporary file
"""
# handle the broken firmware upgrade
if (self.ftp is None):
return False
# otherwise return the photos
self.ftp.cwd(self.MEDIA_PATH)
try:
self.ftp.retrbinary('RETR ' + filename, open(self.storageFile, "wb").write) #download
if cv2_flag and OpenCVAvailable:
img = cv2.imread(self.storageFile)
return img
else:
return filename
except Exception as e:
print(e)
return False
def _delete_file(self, filename):
'''
Deletes a file on the drone
:param filename: Filename of the file you wnat to delete
'''
if (self.ftp is not None):
self.ftp.delete(filename)
class Minidrone:
def __init__(self, address="", use_wifi=False):
"""
If you need BLE: Initialize with its BLE address - if you don't know the address, call findMambo
and that will discover it for you.
You can also connect to the wifi on the FPV camera. Do not use this if the camera is not connected. Also,
ensure you have connected your machine to the wifi on the camera before attempting this or it will not work.
:param address: unique address for this mambo (can be ignored if you are using wifi)
:param use_wifi: set to True to connect with wifi instead of BLE
"""
self.address = address
self.use_wifi = use_wifi
self.groundcam = None
if (use_wifi):
self.drone_connection = WifiConnection(self, drone_type="Mambo")
# initialize groundcam
self.groundcam = MamboGroundcam()
else:
if (BLEAvailable):
self.drone_connection = BLEConnection(address, self)
else:
self.drone_connection = None
color_print("ERROR: you are trying to use a BLE connection on a system that doesn't have BLE installed.", "ERROR")
return
# intialize the command parser
self.command_parser = DroneCommandParser()
# initialize the sensors and the parser
self.sensors = MinidroneSensors()
self.sensor_parser = DroneSensorParser(drone_type="Minidrone")
def set_user_sensor_callback(self, function, args):
"""
Set the (optional) user callback function for sensors. Every time a sensor
is updated, it calls this function.
:param function: name of the function
:param args: tuple of arguments to the function
:return: nothing
"""
self.sensors.set_user_callback_function(function, args)
def update_sensors(self, data_type, buffer_id, sequence_number, raw_data, ack):
"""
Update the sensors (called via the wifi or ble connection)
:param data: raw data packet that needs to be parsed
:param ack: True if this packet needs to be ack'd and False otherwise
"""
sensor_list = self.sensor_parser.extract_sensor_values(raw_data)
if (sensor_list is not None):
for sensor in sensor_list:
(sensor_name, sensor_value, sensor_enum, header_tuple) = sensor
if (sensor_name is not None):
self.sensors.update(sensor_name, sensor_value, sensor_enum)
# print(self.sensors)
else:
color_print(
"data type %d buffer id %d sequence number %d" % (data_type, buffer_id, sequence_number),
"WARN")
color_print("This sensor is missing (likely because we don't need it)", "WARN")
if (ack):
self.drone_connection.ack_packet(buffer_id, sequence_number)
def connect(self, num_retries):
"""
Connects to the drone and re-tries in case of failure the specified number of times. Seamlessly
connects to either wifi or BLE depending on how you initialized it
:param: num_retries is the number of times to retry
:return: True if it succeeds and False otherwise
"""
# special case for when the user tries to do BLE when it isn't available
if (self.drone_connection is None):
return False
connected = self.drone_connection.connect(num_retries)
return connected
def takeoff(self):
"""
Sends the takeoff command to the mambo. Gets the codes for it from the xml files. Ensures the
packet was received or sends it again up to a maximum number of times.
:return: True if the command was sent and False otherwise
"""
command_tuple = self.command_parser.get_command_tuple("minidrone", "Piloting", "TakeOff")
return self.drone_connection.send_noparam_command_packet_ack(command_tuple)
def safe_takeoff(self, timeout):
"""
Sends commands to takeoff until the mambo reports it is taking off
:param timeout: quit trying to takeoff if it takes more than timeout seconds
"""
start_time = time.time()
# take off until it really listens
while (self.sensors.flying_state != "takingoff" and (time.time() - start_time < timeout)):
if (self.sensors.flying_state == "emergency"):
return
success = self.takeoff()
self.smart_sleep(1)
# now wait until it finishes takeoff before returning
while ((self.sensors.flying_state not in ("flying", "hovering") and
(time.time() - start_time < timeout))):
if (self.sensors.flying_state == "emergency"):
return
self.smart_sleep(1)
def land(self):
"""
Sends the land command to the mambo. Gets the codes for it from the xml files. Ensures the
packet was received or sends it again up to a maximum number of times.
:return: True if the command was sent and False otherwise
"""
command_tuple = self.command_parser.get_command_tuple("minidrone", "Piloting", "Landing")
return self.drone_connection.send_noparam_command_packet_ack(command_tuple)
def is_landed(self):
"""
Returns true if it is landed or emergency and False otherwise
:return:
"""
if (self.sensors.flying_state in ("landed", "emergency")):
return True
else:
return False
def safe_land(self, timeout):
"""
Ensure the mambo lands by sending the command until it shows landed on sensors
"""
start_time = time.time()
while (self.sensors.flying_state not in ("landing", "landed") and (time.time() - start_time < timeout)):
if (self.sensors.flying_state == "emergency"):
return
color_print("trying to land", "INFO")
success = self.land()
self.smart_sleep(1)
while (self.sensors.flying_state != "landed" and (time.time() - start_time < timeout)):
if (self.sensors.flying_state == "emergency"):
return
self.smart_sleep(1)
def smart_sleep(self, timeout):
"""
Don't call time.sleep directly as it will mess up BLE and miss WIFI packets! Use this
which handles packets received while sleeping
:param timeout: number of seconds to sleep
"""
self.drone_connection.smart_sleep(timeout)
def hover(self):
"""
Sends the command execute a flat trim to the mambo. This is basically a hover command.
Gets the codes for it from the xml files. Ensures the
packet was received or sends it again up to a maximum number of times.
:return: True if the command was sent and False otherwise
"""
command_tuple = self.command_parser.get_command_tuple("minidrone", "Piloting", "FlatTrim")
# print command_tuple
return self.drone_connection.send_noparam_command_packet_ack(command_tuple)
def flip(self, direction):
"""
Sends the flip command to the mambo. Gets the codes for it from the xml files. Ensures the
packet was received or sends it again up to a maximum number of times.
Valid directions to flip are: front, back, right, left
:return: True if the command was sent and False otherwise
"""
fixed_direction = direction.lower()
if (fixed_direction not in ("front", "back", "right", "left")):
print("Error: %s is not a valid direction. Must be one of %s" % direction, "front, back, right, or left")
print("Ignoring command and returning")
return
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("minidrone",
"Animations", "Flip", fixed_direction)
# print command_tuple
# print enum_tuple
return self.drone_connection.send_enum_command_packet_ack(command_tuple, enum_tuple)
def turn_degrees(self, degrees):
"""
Turn the mambo the specified number of degrees (-180, 180). Degrees must be an integere
so it is cast to an integer here. If you send it a float, it will be rounded according to
the rules of int()
This is called cap in the xml but it means degrees per
http://forum.developer.parrot.com/t/what-does-cap-stand-for/6213/2
:param degrees: degrees to turn (-180 to 180)
:return: True if the command was sent and False otherwise
"""
degrees = int(degrees)
if (degrees > 180):
degrees = 180
print("Degrees too large: setting to 180")
elif (degrees < -180):
degrees = -180
print("Degrees too large and negative: setting to -180")
command_tuple = self.command_parser.get_command_tuple("minidrone", "Animations", "Cap")
return self.drone_connection.send_turn_command(command_tuple, degrees)
def turn_on_auto_takeoff(self):
"""
Turn on the auto take off (throw mode)
:return: True if the command was sent and False otherwise
"""
command_tuple = self.command_parser.get_command_tuple("minidrone", "Piloting", "AutoTakeOffMode")
return self.drone_connection.send_param_command_packet(command_tuple, param_tuple=[1], param_type_tuple=["u8"])
def take_picture(self):
"""
Ask the drone to take a picture also checks how many frames are on there, if there are ore than 35 it deletes one
If connected via Wifi it
If it is connected via WiFi it also deletes all frames on the Mambo once there are more than 35,
since after there are 40 the next ones are ignored
:return: True if the command was sent and False otherwise
"""
if self.use_wifi:
list = self.groundcam.get_groundcam_pictures_names()
if len(list) > 35: #if more than 35 pictures on the Mambo delete all
print("deleting")
for file in list:
self.groundcam._delete_file(file)
command_tuple = self.command_parser.get_command_tuple("minidrone", "MediaRecord", "PictureV2")
return self.drone_connection.send_noparam_command_packet_ack(command_tuple)
def ask_for_state_update(self):
"""
Ask for a full state update (likely this should never be used but it can be called if you want to see
everything the mambo is storing)
:return: nothing but it will eventually fill the MamboSensors with all of the state variables as they arrive
"""
command_tuple = self.command_parser.get_command_tuple("common", "Common", "AllStates")
return self.drone_connection.send_noparam_command_packet_ack(command_tuple)
def _ensure_fly_command_in_range(self, value):
"""
Ensure the fly direct commands are in range and also ensures the values are integers (just rounds them)
:param value: the value sent by the user
:return: a value in the range -100 to 100
"""
if (value < -100):
return -100
elif (value > 100):
return 100
else:
return int(value)
def fly_direct(self, roll, pitch, yaw, vertical_movement, duration=None):
"""
Direct fly commands using PCMD. Each argument ranges from -100 to 100. Numbers outside that are clipped
to that range.
Note that the xml refers to gaz, which is apparently french for vertical movements:
http://forum.developer.parrot.com/t/terminology-of-gaz/3146
duration is optional: if you want it to fly for a specified period of time, set this to the number of
seconds (fractions are fine) or use None to send the command once. Note, if you do this, you will need
an outside loop that sends lots of commands or your drone will not fly very far. The command is not repeated
inside the drone. it executes once and goes back to hovering without new commands coming in. But the option
of zero duration allows for smoother flying if you want to do the control loop yourself.
:param roll: roll speed in -100 to 100
:param pitch: pitch speed in -100 to 100
:param yaw: yaw speed in -100 to 100
:param vertical_movement: vertical speed in -100 to 100
:param duration: optional: seconds for a specified duration or None to send it once (see note above)
:return:
"""
my_roll = self._ensure_fly_command_in_range(roll)
my_pitch = self._ensure_fly_command_in_range(pitch)
my_yaw = self._ensure_fly_command_in_range(yaw)
my_vertical = self._ensure_fly_command_in_range(vertical_movement)
#print("roll is %d pitch is %d yaw is %d vertical is %d" % (my_roll, my_pitch, my_yaw, my_vertical))
command_tuple = self.command_parser.get_command_tuple("minidrone", "Piloting", "PCMD")
if (duration is None):
self.drone_connection.send_single_pcmd_command(command_tuple, my_roll, my_pitch, my_yaw, my_vertical)
else:
self.drone_connection.send_pcmd_command(command_tuple, my_roll, my_pitch, my_yaw, my_vertical, duration)
def open_claw(self):
"""
Open the claw - note not supposed under wifi since the camera takes the place of the claw
:return: True if the command was sent and False otherwise (can include errors or asking to do this using wifi)
"""
# not supposed under wifi since the camera takes the place of the claw
if (self.use_wifi):
return False
# print "open claw"
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("minidrone", "UsbAccessory", "ClawControl", "OPEN")
# print command_tuple
# print enum_tuple
return self.drone_connection.send_enum_command_packet_ack(command_tuple, enum_tuple, self.sensors.claw_id)
def close_claw(self):
"""
Close the claw - note not supposed under wifi since the camera takes the place of the claw
:return: True if the command was sent and False otherwise (can include errors or asking to do this using wifi)
"""
# not supposed under wifi since the camera takes the place of the claw
if (self.use_wifi):
return False
# print "close claw"
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("minidrone", "UsbAccessory", "ClawControl", "CLOSE")
# print command_tuple
# print enum_tuple
return self.drone_connection.send_enum_command_packet_ack(command_tuple, enum_tuple, self.sensors.claw_id)
def set_max_vertical_speed(self, value):
"""
Sets the maximum vertical speed in m/s. Unknown what the true maximum is but
we do ensure you only set positive values.
:param value: maximum speed
:return: True if the command was sent and False otherwise
"""
if (value < 0):
print("Can't set a negative max vertical speed. Setting to 1 m/s instead.")
value = 1
command_tuple = self.command_parser.get_command_tuple("minidrone", "SpeedSettings", "MaxVerticalSpeed")
param_tuple = [value]
param_type_tuple = ['float']
return self.drone_connection.send_param_command_packet(command_tuple,param_tuple,param_type_tuple)
def set_max_tilt(self, value):
"""
Sets the maximum tilt in degrees. Ensures you only set positive values.
:param value: maximum tilt in degrees
:return: True if the command was sent and False otherwise
"""
if (value < 0):
print("Can't set a negative max horizontal speed. Setting to 1 m/s instead.")
value = 1
command_tuple = self.command_parser.get_command_tuple("minidrone", "PilotingSettings", "MaxTilt")
param_tuple = [value]
param_type_tuple = ['float']
return self.drone_connection.send_param_command_packet(command_tuple,param_tuple,param_type_tuple)
def emergency(self):
"""
Sends the emergency command to the mambo. Gets the codes for it from the xml files. Ensures the
packet was received or sends it again up to a maximum number of times.
:return: True if the command was sent and False otherwise
"""
command_tuple = self.command_parser.get_command_tuple("minidrone", "Piloting", "Emergency")
self.drone_connection.send_noparam_command_packet_ack(command_tuple)
def safe_emergency(self, timeout):
"""
Sends emergency stop command until the Mambo reports it is not flying anymore
:param timeout: quit trying to emergency stop if it takes more than timeout seconds
"""
start_time = time.time()
# send emergency until it really listens
while ((self.sensors.flying_state in ("flying", "hovering")) and (time.time() - start_time < timeout)):
success = self.emergency()
self.smart_sleep(1)
# now wait until it touches ground before returning
while ((self.sensors.flying_state != "landed") and (time.time() - start_time < timeout)):
self.smart_sleep(1)
def flat_trim(self):
"""
Sends the flat_trim command to the mambo. Gets the codes for it from the xml files.
"""
command_tuple = self.command_parser.get_command_tuple("minidrone", "Piloting", "FlatTrim")
self.drone_connection.send_noparam_command_packet_ack(command_tuple)
class Mambo(Minidrone):
def disconnect(self):
"""
Disconnect the BLE connection. Always call this at the end of your programs to
cleanly disconnect.
:return: void
"""
self.drone_connection.disconnect()
if self.groundcam is not None:
self.groundcam._close()
def fire_gun(self):
"""
Fire the gun (assumes it is attached) - note not supposed under wifi since the camera takes the place of the gun
:return: True if the command was sent and False otherwise (can include errors or asking to do this using wifi)
"""
# not supposed under wifi since the camera takes the place of the gun
if (self.use_wifi):
return False
# print "firing gun"
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("minidrone", "UsbAccessory", "GunControl", "FIRE")
# print command_tuple
# print enum_tuple
return self.drone_connection.send_enum_command_packet_ack(command_tuple, enum_tuple, self.sensors.gun_id)
class Swing(Minidrone):
def disconnect(self):
"""
Disconnect the BLE connection. Always call this at the end of your programs to
cleanly disconnect.
:return: void
"""
self.drone_connection.disconnect()
def set_flying_mode(self, mode):
"""
Set drone flying mode
:param state:
:return:
"""
if (mode not in ('quadricopter', 'plane_forward', 'plane_backward')):
print("Error: %s is not a valid value. The value must be: quadricopter, plane_forward, plane_backward" % mode)
print("Ignoring command and returning")
return
self.set_plane_gear_box(self.sensors.plane_gear_box)
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("minidrone", "Piloting", "FlyingMode", mode)
self.drone_connection.send_enum_command_packet_ack(command_tuple, enum_tuple)
def set_plane_gear_box(self, state):
"""
Set plane gear box
:param state:
:return:
"""
if (state not in ('gear_1', 'gear_2', 'gear_3')):
print("Error: %s is not a valid value. The value must be: gear_1, gear_2, gear_3" % state)
print("Ignoring command and returning")
return
(command_tuple, enum_tuple) = self.command_parser.get_command_tuple_with_enum("minidrone", "Piloting", "PlaneGearBox", state)
self.drone_connection.send_enum_command_packet_ack(command_tuple, enum_tuple)

View File

@ -0,0 +1,143 @@
"""
This is a simple web server to let the user see the vision that is being processed by ffmpeg. It
essentially replaces the role of VLC. Note that there are several user parameters that should be
set to run this program.
This does not replace the vision process! This is a separate process just to run a web server that
lets you see what the mambo is seeing.
orig author: Igor Maculan - n3wtron@gmail.com
A Simple mjpg stream http server
Updated for python3 including png streaming and
graceful error handling - Taner Davis
"""
import cv2
import os.path
import time
from http.server import BaseHTTPRequestHandler, HTTPServer
"""
Location on your computer where you want to start reading files from to start
streaming. You'll need keep the %03d in the file name to ensure that the stream
can keep finding new photos made from the stream. This allows the program to fill
in image numbers like 004 or 149.
Note: this will not loop at 999, the program will look for 1000 after 999.
"""
#IMAGE_PATH = "/Users/Leo/Desktop/pyparrot-1.2.1/Test file/images/image_%03d.png"
IMAGE_PATH = "/Users/amy/repos/pyparrot/images/image_%03d.png"
"""
The URL or website name you would like to stream to. Unless you have a strong reason
to change this, keep this as "127.0.0.1"
"""
HOST_NAME = "127.0.0.1"
"""
The port youd like to stream to locally. Unless you have a strong reason to change
this, keep this as 9090.
"""
PORT_NUMBER = 9090
"""
Set this according to how we want to stream:
Stream in color -> >0 (1, 2, 873, etc.)
Stream in black and white -> 0
Stream in color with transparency -> <0 (-1, -6, -747, etc.)
"""
STREAMING_IMAGE_TYPE = 1
class CamHandler(BaseHTTPRequestHandler):
def do_GET(self):
"""
When we go to the URL to see the stream, we need to decide if we need to build
the screen or if we need to start loading images to view.
"GET / HTTP/1.1" - The request when we want to build the webpage
Note: self.path here is the first, lone "/"
"GET /cam.mjpg HTTP/1.1" - The request to start viewing the images for the stream
Note: self.path here is "/cam.mjpg"
"""
# If we haven't built the page yet, let's do that. Happens we first load the page.
if self.path.endswith('.html') or self.path == "/":
# Send HTTP Success (200) to let the browser know it's okay to continue and build the page.
self.send_response(200)
self.send_header('Content-type', 'text/html')
self.end_headers()
# Create html for image source using the host name and port provided in the program code
self.wfile.write('<html><head></head><body>'.encode())
self.wfile.write(('<img src="http://%s:%d/cam.mjpg"/>' % (HOST_NAME, PORT_NUMBER)).encode())
self.wfile.write('</body></html>'.encode())
# Page built. Let's bail.
return
if self.path.endswith('.mjpg'):
# Send HTTP Success (200) to let browser know to take page headers and start showing images
self.send_response(200)
self.send_header('Content-type', 'multipart/x-mixed-replace; boundary=--pngboundary')
self.end_headers()
# The name of the first picture will be 1, but the leading zeros are handled in the IMAGE_PATH variable
index = 1
while True:
try:
# Create path name with the index
path = IMAGE_PATH % (index)
# If our file doesn't exist, don't try to read it just yet.
if (not os.path.exists(path)) and (not os.path.isfile(path)):
print("File %s doesn't exist. Trying again." % (path))
# Go back to the try above
continue
# File exists. Let's try to read the image
img = cv2.imread(path, STREAMING_IMAGE_TYPE)
#print("Reading image with index of %d" % (index))
# Increase index by one to read the next image file next time
index = index + 1
# Encode the read png image as a buffer of bytes and write the image to our page
r, buf = cv2.imencode(".png", img)
self.wfile.write("--pngboundary\r\n".encode())
self.send_header('Content-type', 'image/png')
self.send_header('Content-length', str(len(buf)))
self.end_headers()
self.wfile.write(bytearray(buf))
self.wfile.write('\r\n'.encode())
except cv2.error:
"""
This can happen when the png is created from the stream, but it hasn't been completely
filled in. This will throw an error through opencv about trying to read an empty image.
Catch it here and return to the try statement above to keep the program from exiting.
"""
print("Trying to read an empty png. Let's wait and try again.")
continue
except KeyboardInterrupt:
"""
This happens when we input a kill command of some sort like command+c. Let the user know
we have successfully receive the exit command, and stop reading images to the web page.
"""
print("Leaving the stream")
break
return
def main():
"""
Builds an http page to see images in a stream as they are created in the IMAGE_PATH specified above.
"""
try:
# Build a server that will allow us to access it/send requests through a browser
server = HTTPServer(('', PORT_NUMBER), CamHandler)
print("Server started at \"http://%s:%d\"" % (HOST_NAME, PORT_NUMBER))
# Keep the server up until we close it below through a Keyboad Interruption
server.serve_forever()
# Command+c/Command+z will stop the server once the webpage above is also stopped.
except KeyboardInterrupt:
server.socket.close()
print("Terminated Vision program successfully")
"""
Convenience naming methodology to let use call the entire script through command line.
"""
if __name__ == '__main__':
main()

View File

@ -0,0 +1,109 @@
import untangle
import os
from os.path import join
class DroneCommandParser:
def __init__(self):
# store the commandsandsensors as they are called so you don't have to parse each time
self.command_tuple_cache = dict()
# parse the command files from XML (so we don't have to store ids and can use names
# for readability and portability!)
# grab module path per http://www.karoltomala.com/blog/?p=622
path = os.path.abspath(__file__)
dir_path = os.path.dirname(path)
self.common_commands = untangle.parse(join(dir_path, 'common.xml'))
self.minidrone_commands = untangle.parse(join(dir_path, 'minidrone.xml'))
self.ardrone3_commands = untangle.parse(join(dir_path, 'ardrone3.xml'))
def get_command_tuple(self, project, myclass, cmd):
"""
Parses the command XML for the specified class name and command name
:param myclass: class name (renamed to myclass to avoid reserved name) in the xml file
:param cmd: command to execute (from XML file)
:return:
"""
# only search if it isn't already in the cache
if (myclass, cmd) in self.command_tuple_cache:
return self.command_tuple_cache[(myclass, cmd)]
# pick the right command file to draw from
if (project == "ardrone3"):
my_file = self.ardrone3_commands
elif (project == "minidrone"):
my_file = self.minidrone_commands
else:
my_file = self.common_commands
# run the search first in minidrone xml and then hit common if that failed
project_id = int(my_file.project['id'])
for child in my_file.project.myclass:
if child['name'] == myclass:
class_id = int(child['id'])
#print child['name']
for subchild in child.cmd:
#print subchild
if subchild['name'] == cmd:
#print subchild['name']
cmd_id = int(subchild['id'])
# cache the result
self.command_tuple_cache[(myclass, cmd)] = (project_id, class_id, cmd_id)
return (project_id, class_id, cmd_id)
def get_command_tuple_with_enum(self, project, myclass, cmd, enum_name):
"""
Parses the command XML for the specified class name and command name and checks for enum_name
:param myclass: class name (renamed to myclass to avoid reserved name) in the xml file
:param cmd: command to execute (from XML file)
:return:
"""
# only search if it isn't already in the cache
if (myclass, cmd, enum_name) in self.command_tuple_cache:
#print("using the cache")
#print(self.command_tuple_cache[(myclass, cmd, enum_name)])
return self.command_tuple_cache[(myclass, cmd, enum_name)]
# pick the right command file to draw from
if (project == "ardrone3"):
my_file = self.ardrone3_commands
elif (project == "minidrone"):
my_file = self.minidrone_commands
else:
my_file = self.common_commands
# run the search first in minidrone xml and then hit common if that failed
project_id = int(my_file.project['id'])
for child in my_file.project.myclass:
if child['name'] == myclass:
class_id = int(child['id'])
#print child['name']
for subchild in child.cmd:
#print subchild
if subchild['name'] == cmd:
#print subchild['name']
cmd_id = int(subchild['id'])
for arg_child in subchild.arg:
if arg_child['type'] == "enum":
for e_idx, echild in enumerate(arg_child.enum):
if echild['name'] == enum_name:
enum_id = e_idx
# cache the result
self.command_tuple_cache[(myclass, cmd, enum_name)] = ((project_id, class_id, cmd_id), enum_id)
#print ((project_id, class_id, cmd_id), enum_id)
return ((project_id, class_id, cmd_id), enum_id)

View File

@ -0,0 +1,204 @@
"""
Sensor parser class: handles the XML parsing and gets the values but the actual data is stored with the drone itself
since it knows what to do with it.
"""
import struct
import untangle
from pyparrot.utils.colorPrint import color_print
import os
from os.path import join
def get_data_format_and_size(data, data_type):
"""
Internal function to convert data_type to the corresponding struct.pack format string
as per https://docs.python.org/2/library/struct.html#format-characters
Function contributed by awm102 on GitHub. Amy moved this to DroneSensorParser to be
more general, edited a bit to fit within the drone sensor parser as well.
:param data: the data that will be packed. Not actually used here unless the data_type is string, then
it is used to calculate the data size.
:param data_type: a string representing the data type
:return: a tuple of a string representing the struct.pack format for the data type and an int representing
the number of bytes
"""
if data_type == "u8" or data_type == "enum":
format_char = "<B"
data_size = 1
elif data_type == "i8":
format_char = "<b"
data_size = 1
elif data_type == "u16":
format_char = "<H"
data_size = 2
elif data_type == "i16":
format_char = "<h"
data_size = 2
elif data_type == "u32":
format_char = "<I"
data_size = 4
elif data_type == "i32":
format_char = "<i"
data_size = 4
elif data_type == "u64":
format_char = "<Q"
data_size = 8
elif data_type == "i64":
format_char = "<q"
data_size = 8
elif data_type == "float":
format_char = "<f"
data_size = 4
elif data_type == "double":
format_char = "<d"
data_size = 8
elif data_type == "string":
format_char = "<s"
data_size = len(data)
else:
format_char = ""
data_size = 0
return (format_char, data_size)
class DroneSensorParser:
def __init__(self, drone_type):
# grab module path per http://www.karoltomala.com/blog/?p=622
path = os.path.abspath(__file__)
dir_path = os.path.dirname(path)
self.common_sensors = untangle.parse(join(dir_path, 'common.xml'))
if (drone_type == "Minidrone"):
self.drone_sensors = untangle.parse(join(dir_path, 'minidrone.xml'))
else:
self.drone_sensors = untangle.parse(join(dir_path, 'ardrone3.xml'))
self.project_xmls = (self.drone_sensors, self.common_sensors)
self.sensor_tuple_cache = dict()
def extract_sensor_values(self, data):
"""
Extract the sensor values from the data in the BLE packet
:param data: BLE packet of sensor data
:return: a list of tuples of (sensor name, sensor value, sensor enum, header_tuple)
"""
sensor_list = []
#print("updating sensors with ")
try:
header_tuple = struct.unpack_from("<BBH", data)
except:
color_print("Error: tried to parse a bad sensor packet", "ERROR")
return None
#print(header_tuple)
(names, data_sizes) = self._parse_sensor_tuple(header_tuple)
#print("name of sensor is %s" % names)
#print("data size is %s" % data_sizes)
packet_offset = 4
if names is not None:
for idx, name in enumerate(names):
data_size = data_sizes[idx]
try:
# figure out how to parse the data
(format_string, new_offset) = get_data_format_and_size(data[packet_offset:], data_size)
if (new_offset == 0):
# this is usually a boolean flag stating that values have changed so set the value to True
# and let it return the name
sensor_data = True
else:
# real data, parse it
sensor_data = struct.unpack_from(format_string, data, offset=packet_offset)
sensor_data = sensor_data[0]
if (data_size == "string"):
packet_offset += len(sensor_data)
else:
packet_offset += new_offset
except Exception as e:
sensor_data = None
#print(header_tuple)
color_print("Error parsing data for sensor", "ERROR")
print(e)
print("name of sensor is %s" % names)
print("data size is %s" % data_sizes)
print(len(data))
print(4*(idx+1))
#print("%s %s %s" % (name,idx,sensor_data))
#color_print("updating the sensor!", "NONE")
sensor_list.append([name, sensor_data, self.sensor_tuple_cache, header_tuple])
return sensor_list
else:
color_print("Could not find sensor in list - ignoring for now. Packet info below.", "ERROR")
print(header_tuple)
#print(names)
return None
def _parse_sensor_tuple(self, sensor_tuple):
"""
Parses the sensor information from the command id bytes and returns the name
of the sensor and the size of the data (so it can be unpacked properly)
:param sensor_tuple: the command id tuple to be parsed (type, packet id, command tuple 3 levels deep)
:return: a tuple with (name of the sensor, data size to be used for grabbing the rest of the data)
"""
# grab the individual values
(project_id, myclass_id, cmd_id) = sensor_tuple
# return the cache if it is there
if (project_id, myclass_id, cmd_id) in self.sensor_tuple_cache:
return self.sensor_tuple_cache[(project_id, myclass_id, cmd_id)]
for project_xml in self.project_xmls:
#color_print("looking for project id %d in %s" % (project_id, project_xml))
if (project_id == int(project_xml.project['id'])):
#color_print("looking for myclass_id %d" % myclass_id)
for c in project_xml.project.myclass:
#color_print("looking for cmd_id %d" % cmd_id)
if int(c['id']) == myclass_id:
for cmd_child in c.cmd:
if int(cmd_child['id']) == cmd_id:
cmd_name = cmd_child['name']
sensor_names = list()
data_sizes = list()
if (hasattr(cmd_child, 'arg')):
for arg_child in cmd_child.arg:
sensor_name = cmd_name + "_" + arg_child['name']
data_size = arg_child['type']
# special case, if it is an enum, need to add the enum mapping into the cache
if (data_size == 'enum'):
enum_names = list()
for eitem in arg_child.enum:
#color_print(eitem)
enum_names.append(eitem['name'])
self.sensor_tuple_cache[sensor_name, "enum"] = enum_names
#color_print("added to sensor cache %s" % enum_names)
# save the name and sizes to a list
sensor_names.append(sensor_name)
data_sizes.append(data_size)
else:
# there is no sub-child argument meaning this is just a pure notification
# special case values just use the command name and None for size
sensor_names.append(cmd_name)
data_sizes.append(None)
# cache the results
self.sensor_tuple_cache[(project_id, myclass_id, cmd_id)] = (
sensor_names, data_sizes)
return (sensor_names, data_sizes)
# didn't find it, return an error
# cache the results
self.sensor_tuple_cache[(project_id, myclass_id, cmd_id)] = (None, None)
return (None, None)

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,612 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--
Copyright (C) 2014 Parrot SA
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in
the documentation and/or other materials provided with the
distribution.
* Neither the name of Parrot nor the names
of its contributors may be used to endorse or promote products
derived from this software without specific prior written
permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
SUCH DAMAGE.
-->
<feature id="134" name="follow_me">
FollowMe feature
<enums>
<enum name="mode">
FollowMe mode
<value name="none">
No follow me
</value>
<value name="look_at">
Look at the target without moving automatically
</value>
<value name="geographic">
Follow the target keeping the same vector
</value>
<value name="relative">
Follow the target keeping the same orientation to its direction
</value>
</enum>
<enum name="behavior">
FollowMe behavior
<value name="idle">
Drone is not moving according to the target
This means that at least one required input is missing
</value>
<value name="follow">
Follow the target
</value>
<value name="look_at">
Look at the target without moving
</value>
</enum>
<enum name="input">
Input values used by the FollowMe
<value name="drone_calibrated">
Drone is calibrated
</value>
<value name="drone_gps_good_accuracy">
Drone gps has fixed and has a good accuracy
</value>
<value name="target_gps_good_accuracy">
Target gps data is known and has a good accuracy
</value>
<value name="target_barometer_ok">
Target barometer data is available
</value>
<value name="drone_far_enough">
Drone is far enough from the target
</value>
<value name="drone_high_enough">
Drone is high enough from the ground
</value>
<value name="image_detection">
Target detection is done by image detection among other things
</value>
</enum>
<enum name="geo_rel_configure_param">
Geographic and Relative follow me configuration parameters
<value name="distance">
Distance configuration
</value>
<value name="elevation">
Elevation configuration
</value>
<value name="azimuth">
Azimuth configuration
</value>
</enum>
<enum name="animation">
FollowMe animation type
<value name="none">
No animation
</value>
<value name="helicoid">
Turn around the target
</value>
<value name="swing">
Pass by the zenith and change of side
</value>
<value name="boomerang">
Fly far from the target and fly back
</value>
<value name="candle">
Move to the target and go high when it is near
</value>
<value name="dolly_slide">
Fly in line
</value>
</enum>
<enum name="helicoid_configure_param">
Helicoid animation configuration parameters.
<value name="speed">
Speed parameter
</value>
<value name="revolution_nb">
Number of turn
</value>
<value name="vertical_distance">
Vertical distance
</value>
</enum>
<enum name="swing_configure_param">
Swing configure parameters.
<value name="speed">
Speed parameter
</value>
<value name="vertical_distance">
Vertical distance
</value>
</enum>
<enum name="boomerang_configure_param">
Boomerang animation configure parameters.
<value name="speed">
Speed parameter
</value>
<value name="distance">
Distance
</value>
</enum>
<enum name="candle_configure_param">
Candle animation configure parameters.
<value name="speed">
Speed parameter
</value>
<value name="vertical_distance">
Follow the target keeping the same vector
</value>
</enum>
<enum name="dolly_slide_configure_param">
Dolly slide animation configure parameters.
<value name="speed">
Speed parameter
</value>
<value name="angle">
Angle
</value>
<value name="horizontal_distance">
Horizontal distance
</value>
</enum>
<enum name="image_detection_status">
State of the image detection
<value name="none">
No image detection
</value>
<value name="ok">
Image detection is considered ok by the drone
</value>
<value name="lost">
Image detection is considered lost or
in contradiction with gps value.
This state will remain until a new selection of the target is done
</value>
</enum>
</enums>
<msgs>
<cmd name="start" id="1">
<comment
title="Start followMe mode"
desc="Start a FollowMe with all its params set to the default params. \n
Sending this command will stop other running followMe."
support="090c:4.0.0"
result="Event [state](#134-3) is triggered.\n
Also triggers the event that informs about the current \n
configuration (if there is one) like event\n
[Geographic configuration](#134-4) or [Relative configuration](#134-6)"/>
<arg name="mode" type="enum:mode"/>
</cmd>
<cmd name="stop" id="2">
<comment
title="Stop current followMe"
desc="Stop current followMe."
support="090c:4.0.0"
result="Event [state](#134-3) is triggered with mode equals to none."/>
</cmd>
<evt name="state" id="3">
<comment
title="State of the FollowMe"
support="090c:4.0.0"
triggered="by any changes on the followme, like [start](#134-1),\n
[stop](#134-2), [start helicoid anim](#134-9)..."/>
<arg name="mode" type="enum:mode">
Mode asked by user
</arg>
<arg name="behavior" type="enum:behavior">
Behavior of the drone according to the asked mode
</arg>
<arg name="animation" type="enum:animation">
Current animation.
This parameter has been deprecated. Please use the animation feature.
</arg>
<arg name="animation_available" type="bitfield:u16:animation">
List of available animations
This parameter has been deprecated. Please use the animation feature.
</arg>
</evt>
<evt name="mode_info" id="4" type="MAP_ITEM:mode">
<comment
title="FollowMe mode info"
support="090c:4.0.0"
triggered="When the list of missing requirements or improvments changes"/>
<arg name="mode" type="enum:mode"/>
<arg name="missing_requirements" type="bitfield:u16:input">
List of missing requirements to enter this mode on start.
Bit is 0 if the input is not ok, 1 if the input is ok.
If at least one input is missing, drone won't able to follow the target.
It won't use any fallback either
</arg>
<arg name="improvements" type="bitfield:u16:input">
List of inputs that can improve the mode.
Bit is 0 if the input is not ok, 1 if the input is ok.
If at least one input is missing, a downgraded mode will be used. See behavior
</arg>
</evt>
<cmd name="configure_geographic" id="6">
<comment
title="Configure the geographic follow me"
desc="Configure the geographic FollowMe.\n
This should only be taken in account if arg behavior in [state](#134-3) is equal to Follow."
support="090c:4.0.0"
result="Event [Geographic config](#134-6) is sent and drone will move to respect the configuration."/>
<arg name="use_default" type="bitfield:u8:geo_rel_configure_param"/>
<arg name="distance" type="float">
The distance leader-follower in meter
Not used when arg start is at 0
</arg>
<arg name="elevation" type="float">
The elevation leader-follower in rad (not used when arg start is at 0)
</arg>
<arg name="azimuth" type="float">
The azimuth north-leader-follower in rad (not used when arg start is at 0)
</arg>
</cmd>
<evt name="geographic_config" id="7">
<comment
title="Geographic configuration changed"
desc="Geographic configuration changed.\n
This event is only valid when arg behavior in [state](#134-3) is equal to Follow."
support="090c:4.0.0"
triggered="By [start geographic](#134-1) or [configure geographic](#134-4)."/>
<arg name="use_default" type="bitfield:u8:geo_rel_configure_param"/>
<arg name="distance" type="float">
The distance leader-follower in meter
If distance is default, this value is the current drone distance
</arg>
<arg name="elevation" type="float">
The elevation leader-follower in rad
If elevation is default, this value is the current leader to drone elevation
</arg>
<arg name="azimuth" type="float">
The azimuth north-leader-follower in rad
If azimuth is default, this value is the current leader to drone azimuth
</arg>
</evt>
<cmd name="configure_relative" id="8">
<comment
title="Configure the relative follow me"
desc="Configure the relative FollowMe.\n
This should only be taken in account if arg behavior in [state](#134-3) is equal to Follow"
support="090c:4.0.0"
result="Event [Relative config](#134-6) is sent and drone will move to respect the configuration."/>
<arg name="use_default" type="bitfield:u8:geo_rel_configure_param"/>
<arg name="distance" type="float">
The distance leader-follower in meter
</arg>
<arg name="elevation" type="float">
The elevation leader-follower in rad
</arg>
<arg name="azimuth" type="float">
The azimuth north-leader-follower in rad
</arg>
</cmd>
<evt name="relative_config" id="9">
<comment
title="Relative configuration changed"
desc="Relative configuration changed.\n
This event is only valid when arg behavior in [state](#134-3) is equal to Follow."
support="090c:4.0.0"
triggered="By [start relative](#134-1) or [configure relative](#134-4)."/>
<arg name="use_default" type="bitfield:u8:geo_rel_configure_param"/>
<arg name="distance" type="float">
The distance leader-follower in meter
If distance is default, this value is the current drone distance
</arg>
<arg name="elevation" type="float">
The elevation leader-follower in rad
If elevation is default, this value is the current leader to drone elevation
</arg>
<arg name="azimuth" type="float">
The azimuth course-leader-follower in rad
If azimuth is default, this value is the current leader to drone azimuth
</arg>
</evt>
<evt name="target_trajectory" id="10" buffer="NON_ACK">
<comment
title="Target estimated trajectory"
support="090c:4.0.0"
triggered="Regularly when a FollowMe is started."/>
<arg name="latitude" type="double">
Target latitude (in degrees)
</arg>
<arg name="longitude" type="double">
Target longitude (in degrees)
</arg>
<arg name="altitude" type="float">
Target altitude (in meters, relative to sea level)
</arg>
<arg name="north_speed" type="float">
Target north speed (in m/s)
</arg>
<arg name="east_speed" type="float">
Target east speed (in m/s)
</arg>
<arg name="down_speed" type="float">
Target down speed (in m/s)
</arg>
</evt>
<!-- FollowMe Animations -->
<cmd name="stop_animation" id="11" deprecated="true">
<comment
title="Stop current followMe animation"
desc="Stop current followMe animation.\n
This message has been deprecated. Please use the animation feature."
support="090c:4.0.0"
result="FollowMe animation will stop. Event [state](#134-2) is triggered."/>
</cmd>
<cmd name="start_helicoid_anim" id="12" deprecated="true">
<comment
title="Start a helicoid animation"
desc="Start a helicoid animation.\n
The helicoid animation allows the drone to revolve around the target while going up, with a fixed radius.\n
This message has been deprecated. Please use the animation feature."
support="090c:4.0.0"
result="Animation is started and event [state](#134-2) is triggered."/>
<arg name="use_default" type="bitfield:u8:helicoid_configure_param"/>
<arg name="speed" type="float">
The desired speed of the anim in m/s
Not used when speed_is_default is 1
</arg>
<arg name="revolution_number" type="float">
The number of revolution (in turn)
Negative value is infinite
Example: 1.5 makes an entire turn plus half of a turn
Not used when revolutionNb_is_default is 1
</arg>
<arg name="vertical_distance" type="float">
Distance that should be made by the product to reach the top of the helicoid in m
Not used when verticalDistance_is_default is 1
</arg>
</cmd>
<evt name="helicoid_anim_config" id="13" deprecated="true">
<comment
title="Helicoid animation configuration"
desc="Helicoid animation configuration.\n
This should only be taken in account if arg animation in [state](#134-3) is equal to helicoid.\n
This message has been deprecated. Please use the animation feature."
support="090c:4.0.0"
triggered="by a [start helicoid animation](#134-9)."/>
<arg name="use_default" type="bitfield:u8:helicoid_configure_param"/>
<arg name="speed" type="float">
The speed of the anim in m/s
</arg>
<arg name="revolution_nb" type="float">
The number of revolution (in turn)
Negative value is infinite
</arg>
<arg name="vertical_distance" type="float">
Distance that will be made by the product to reach the top of the helicoid in m
</arg>
</evt>
<cmd name="start_swing_anim" id="14" deprecated="true">
<comment
title="Start a swing animation"
desc="Start a swing animation.\n
The swing animation enables a vertical point of view while the drone passes over the target.\n
This message has been deprecated. Please use the animation feature."
support="090c:4.0.0"
result="Animation is started and event [state](#134-2) is triggered."/>
<arg name="use_default" type="bitfield:u8:swing_configure_param"/>
<arg name="speed" type="float">
The desired speed of the anim in m/s
Not used when speed_is_default is 1
Not used when start is 0
</arg>
<arg name="vertical_distance" type="float">
Distance that should be made by the product to reach the top of the swing in m
Not used when verticalDistance_is_default is 1
Not used when start is 0
</arg>
</cmd>
<evt name="swing_anim_config" id="15" deprecated="true">
<comment
title="Swing animation configuration changed"
desc="Swing animation configuration changed.\n
This should only be taken in account if arg animation in [state](#134-3) is equal to swing.\n
This message has been deprecated. Please use the animation feature."
support="090c:4.0.0"
triggered="by a [start swing animation](#134-11)."/>
<arg name="use_default" type="bitfield:u8:swing_configure_param"/>
<arg name="speed" type="float">
The speed of the anim in m/s
</arg>
<arg name="vertical_distance" type="float">
Distance that will be made by the product to reach the top of the swing in m
</arg>
</evt>
<cmd name="start_boomerang_anim" id="16" deprecated="true">
<comment
title="Start a boomerang animation"
desc="Start a boomerang animation.\n
The boomerang animation enables a zoom-out/zoom-in trajectory while preserving the framing chosen by the user.\n
This message has been deprecated. Please use the animation feature."
support="090c:4.0.0"
result="Animation is started and event [state](#134-2) is triggered."/>
<arg name="use_default" type="bitfield:u8:boomerang_configure_param"/>
<arg name="speed" type="float">
The desired speed of the anim in m/s
Not used when speed_is_default is 1
Not used when start is 0
</arg>
<arg name="distance" type="float">
Distance that should be made by the product to reach its return point in m
Not used when distance_is_default is 1
Not used when start is 0
</arg>
</cmd>
<evt name="boomerang_anim_config" id="17" deprecated="true">
<comment
title="Boomerang animation configuration changed"
desc="Boomerang animation configuration changed.\n
This should only be taken in account if arg animation in [state](#134-3) is equal to boomerang.\n
This message has been deprecated. Please use the animation feature."
support="090c:4.0.0"
triggered="by a [start boomerang animation](#134-13)."/>
<arg name="use_default" type="bitfield:u8:boomerang_configure_param"/>
<arg name="speed" type="float">
The speed of the anim in m/s
</arg>
<arg name="distance" type="float">
Distance that will be made by the product to reach its return point in m
</arg>
</evt>
<cmd name="start_candle_anim" id="18" deprecated="true">
<comment
title="Start a candle animation"
desc="Start a candle animation.\n
The candle animation enables a zoom-in directly on the target followed by a vertical zoom-out.\n
This message has been deprecated. Please use the animation feature."
support="090c:4.0.0"
result="Animation is started and event [state](#134-2) is triggered."/>
<arg name="use_default" type="bitfield:u8:candle_configure_param"/>
<arg name="speed" type="float">
The desired speed of the anim in m/s
Not used when speed_is_default is 1
Not used when start is 0
</arg>
<arg name="vertical_distance" type="float">
Distance that should be made by the product to reach the top of the vertical zoom-out in m
Not used when verticalDistance_is_default is 1
Not used when start is 0
</arg>
</cmd>
<evt name="candle_anim_config" id="19" deprecated="true">
<comment
title="Candle animation configuration changed"
desc="Candle animation configuration changed.\n
This should only be taken in account if arg animation in [state](#134-3) is equal to candle.\n
This message has been deprecated. Please use the animation feature."
support="090c:4.0.0"
triggered="by a [start candle animation](#134-15)."/>
<arg name="use_default" type="bitfield:u8:candle_configure_param"/>
<arg name="speed" type="float">
The speed of the anim in m/s
</arg>
<arg name="vertical_distance" type="float">
Distance that will be made by the product to reach the top of the vertical zoom-out in m
</arg>
</evt>
<cmd name="start_dolly_slide_anim" id="20" deprecated="true">
<comment
title="Start a dolly slide animation"
desc="Start a dolly slide animation.\n
Allows the drone to catch up to the target before flying past it, creating a zoom-in/zoom_out effect without a curved path.\n
This message has been deprecated. Please use the animation feature."
support="090c:4.0.0"
result="Animation is started and event [state](#134-2) is triggered."/>
<arg name="use_default" type="bitfield:u8:dolly_slide_configure_param"/>
<arg name="speed" type="float">
The desired speed of the anim in m/s
Not used when speed_is_default is 1
Not used when start is 0
</arg>
<arg name="angle" type="float">
Desired angle Product-User-Target in rad
Not used when angle_is_default is 1
Not used when start is 0
</arg>
<arg name="horizontal_distance" type="float">
Distance that should be made by the product to reach its target in m
Not used when horizontalDistance_is_default is 1
Not used when start is 0
</arg>
</cmd>
<evt name="dolly_slide_anim_config" id="21" deprecated="true">
<comment
title="DollySlide animation configuration changed"
desc="DollySlide animation configuration changed.\n
This should only be taken in account if arg animation in [state](#134-3) is equal to dolly_slide.\n
This message has been deprecated. Please use the animation feature."
support="090c:4.0.0"
triggered="by a [start dolly slide animation](#134-17)."/>
<arg name="use_default" type="bitfield:u8:dolly_slide_configure_param"/>
<arg name="speed" type="float">
The speed of the anim in m/s
</arg>
<arg name="angle" type="float">
Angle Product-User-Target in rad
</arg>
<arg name="horizontal_distance" type="float">
Distance that will be made by the product to reach its target in m
</arg>
</evt>
<cmd name="target_framing_position" id="22">
<comment
title="Set the target framing"
desc="Set the desired target framing in the video."
support="090c:4.0.0"
result="Event [target framing position](#134-20) is triggered."/>
<arg name="horizontal" type="i8">
Horizontal position in the video (in %, from left to right)
</arg>
<arg name="vertical" type="i8">
Vertical position in the video (in %, from bottom to top)
</arg>
</cmd>
<evt name="target_framing_position_changed" id="23">
<comment
title="Desired target framing"
support="090c:4.0.0"
triggered="by [set target framing](#134-19)."/>
<arg name="horizontal" type="i8">
Horizontal position in the video (in %, from left to right)
</arg>
<arg name="vertical" type="i8">
Vertical position in the video (in %, from bottom to top)
</arg>
</evt>
<cmd name="target_image_detection" id="24">
<comment
title="Send vision detection results"
desc="Send vision detection results."
support="090c:4.0.0"
result="If drone is in FollowMe, is will look at the target according to\n
the chosen [framing position](#134-20)."/>
<arg name="target_azimuth" type="float">
Horizontal north-drone-target angle in radian
</arg>
<arg name="target_elevation" type="float">
Vertical angle horizon-drone-target in radian
</arg>
<arg name="change_of_scale" type="float">
Normalized relative radial speed in 1/second
</arg>
<arg name="confidence_index" type="u8">
Confidence index of the detection (from 0 to 255, the highest is the best)
</arg>
<arg name="is_new_selection" type="u8">
Boolean. 1 if the selection is new, 0 otherwise
</arg>
<arg name="timestamp" type="u64">
Acquisition time of processed picture in millisecond
</arg>
</cmd>
<evt name="target_image_detection_state" id="25">
<comment
title="State of the image detection"
support="090c:4.0.0"
triggered="By a possible wrong [target image detection](#134-24)."/>
<arg name="state" type="enum:image_detection_status"/>
</evt>
</msgs>
</feature>

View File

@ -0,0 +1,109 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--
Copyright (C) 2014 Parrot SA
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in
the documentation and/or other materials provided with the
distribution.
* Neither the name of Parrot nor the names
of its contributors may be used to endorse or promote products
derived from this software without specific prior written
permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
SUCH DAMAGE.
-->
<feature id="133" name="generic">
All generic messages
<enums>
<enum name="list_flags">
Flags use by maps and lists
<value name="First">
indicate it's the first element of the list.
</value>
<value name="Last">
indicate it's the last element of the list.
</value>
<value name="Empty">
indicate the list is empty (implies First/Last). All other arguments should be ignored.
</value>
<value name="Remove">
This value should be removed from the existing list.
</value>
</enum>
</enums>
<multisettings>
<multisetting name="DroneSettings">
Drone settings
<member link="ardrone3.PilotingSettings.MaxAltitude"></member>
<member link="ardrone3.PilotingSettings.MaxTilt"></member>
<member link="ardrone3.PilotingSettings.MaxDistance"></member>
<member link="ardrone3.PilotingSettings.NoFlyOverMaxDistance"></member>
<member link="ardrone3.SpeedSettings.MaxVerticalSpeed"></member>
<member link="ardrone3.SpeedSettings.MaxRotationSpeed"></member>
<member link="ardrone3.SpeedSettings.MaxPitchRollRotationSpeed"></member>
<member link="ardrone3.GPSSettings.ReturnHomeDelay"></member>
<member link="ardrone3.GPSSettings.HomeType"></member>
<member link="ardrone3.PictureSettings.VideoStabilizationMode"></member>
<member link="ardrone3.PilotingSettings.BankedTurn"></member>
</multisetting>
<multisetting name="DroneSettingsChanged">
Drone settings changed
<member link="ardrone3.PilotingSettingsState.MaxAltitudeChanged"></member>
<member link="ardrone3.PilotingSettingsState.MaxTiltChanged"></member>
<member link="ardrone3.PilotingSettingsState.MaxDistanceChanged"></member>
<member link="ardrone3.PilotingSettingsState.NoFlyOverMaxDistanceChanged"></member>
<member link="ardrone3.SpeedSettingsState.MaxVerticalSpeedChanged"></member>
<member link="ardrone3.SpeedSettingsState.MaxRotationSpeedChanged"></member>
<member link="ardrone3.SpeedSettingsState.MaxPitchRollRotationSpeedChanged"></member>
<member link="ardrone3.GPSSettingsState.ReturnHomeDelayChanged"></member>
<member link="ardrone3.GPSSettingsState.HomeTypeChanged"></member>
<member link="ardrone3.PictureSettingsState.VideoStabilizationModeChanged"></member>
<member link="ardrone3.PilotingSettingsState.BankedTurnChanged"></member>
</multisetting>
</multisettings>
<msgs>
<cmd name="default" id="1">
<comment
title="default"
desc="default"
support="none"
result="default"/>
</cmd>
<cmd name="SetDroneSettings" id="2">
<arg name="settings" type="multisetting:DroneSettings">
<comment
title="SetDroneSettings"
desc="Set several drone settings in only one command."
support="none"
result="Drone settings are set.\n
Then, event [DroneSettingsChanged](#133-3) is triggered."/>
</arg>
</cmd>
<evt name="DroneSettingsChanged" id="3">
<arg name="settings" type="multisetting:DroneSettingsChanged">
<comment
title="Drone Settings"
desc="Informs that several drones settings changed."
support="none"
triggered="by [SetDroneSettings](#133-2)."/>
</arg>
</evt>
</msgs>
</feature>

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,267 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--
Copyright (C) 2014 Parrot SA
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in
the documentation and/or other materials provided with the
distribution.
* Neither the name of Parrot nor the names
of its contributors may be used to endorse or promote products
derived from this software without specific prior written
permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
SUCH DAMAGE.
-->
<feature id="135" name="wifi">
All commands/events related to the Wifi
<enums>
<enum name="band">
The band : 2.4 Ghz or 5 Ghz
<value name="2_4_ghz">
2.4 GHz band
</value>
<value name="5_ghz">
5 GHz band
</value>
</enum>
<enum name="selection_type">
The wifi selection type available
<value name="auto_all">
Auto selection on all channels
</value>
<value name="auto_2_4_ghz">
Auto selection 2.4ghz
</value>
<value name="auto_5_ghz">
Auto selection 5 ghz
</value>
<value name="manual">
manual selection
</value>
</enum>
<enum name="security_type">
The type of wifi security (open, wpa2)
<value name="open">
Wifi is not protected by any security (default)
</value>
<value name="wpa2">
Wifi is protected by wpa2
</value>
</enum>
<enum name="security_key_type">
Type of the key sent
<value name="plain">
Key is plain text, not encrypted
</value>
</enum>
<enum name="environment">
Type of environment
<value name="indoor">
indoor environment
</value>
<value name="outdoor">
outdoor environment
</value>
</enum>
<enum name="country_selection">
Type of country selection
<value name="manual">
Manual selection.
</value>
<value name="auto">
Automatic selection.
</value>
</enum>
</enums>
<msgs>
<cmd name="scan" id="1">
<comment
title="Scan wifi network"
desc="Launches wifi network scan for a given band to get a list of all wifi networks found by the drone."
support="0901;0902;0905;0906;090c"
result="Event [WifiScanListChanged](#135-2) is triggered with all networks found."/>
<arg name="band" type="bitfield:u8:band"/>
</cmd>
<evt name="scanned_item" id="2" type="MAP_ITEM:ssid">
<comment
title="Wifi scan results"
desc="Wifi scan results."
support="0901;0902;0905;0906;090c"
triggered="Triggered for each wifi scanned after a [ScanWifi](#135-1)."/>
<arg name="ssid" type="string">
SSID of the AP
</arg>
<arg name="rssi" type="i16">
RSSI of the AP.
</arg>
<arg name="band" type="enum:band">
</arg>
<arg name="channel" type="u8">
Channel of the AP
</arg>
<arg name="list_flags" type="bitfield:u8:list_flags"/>
<!-- implicit
<arg name="list_flags" type="u8">
List entry attribute Bitfield.
0x01: First: indicate it's the first element of the list.
0x02: Last: indicate it's the last element of the list.
0x04: Empty: indicate the list is empty (implies First/Last). All other arguments should be ignored.
0x08: Remove: This value should be removed from the existing list.
</arg>
-->
</evt>
<cmd name="update_authorized_channels" id="3">
<comment
title="Get all available Wifi channels"
desc="Get all available Wifi channels.\nThe list of available Wifi channels is related to the country of the drone. You can get this country with the event [WifiCountryChanged](#wifi-CountryChanged)."
support="0901;0902;0905;0906;090c"
result="Event [AvailableChannelListChanged](#135-4) is triggered with all authorized channels."/>
</cmd>
<evt name="authorized_channel" id="4" type="LIST_ITEM">
<comment
title="Available channel results"
desc="Available channel results."
support="0901;0902;0905;0906;090c"
triggered="Triggered for each channels found after a [UpdateAvailableChannels](#135-3)."/>
<arg name="band" type="enum:band">
</arg>
<arg name="channel" type="u8">
The channel number
</arg>
<arg name="environment" type="bitfield:u8:environment"/>
<arg name="list_flags" type="bitfield:u8:list_flags"/>
<!-- implicit
<arg name="list_flags" type="u8">
List entry attribute Bitfield.
0x01: First: indicate it's the first element of the list.
0x02: Last: indicate it's the last element of the list.
0x04: Empty: indicate the list is empty (implies First/Last). All other arguments should be ignored.
0x08: Remove: This value should be removed from the existing list.
</arg>
-->
</evt>
<cmd name="set_ap_channel" id="5">
<comment
title="Wifi selection"
desc="Select channel of choosen band to put the drone's access point on this channel."
support="0901;0902;0905;0906;090c"
result="The wifi channel changes according to given parameters. Watch out, a disconnection might appear.\nThen, event [WifiSelectionChanged](#135-6) is triggered."/>
<arg name="type" type="enum:selection_type"/>
<arg name="band" type="enum:band" desc="Used only when type is manual"/>
<arg name="channel" type="u8">
The channel you want to select. Used only when type is manual.
</arg>
</cmd>
<evt name="ap_channel_changed" id="6">
<comment
title="Wifi selection changed"
desc="Wifi selection changed."
support="0901;0902;0905;0906;090c"
triggered="Triggered by [WifiSelection](#135-5)."/>
<arg name="type" type="enum:selection_type"/>
<arg name="band" type="enum:band"/>
<arg name="channel" type="u8">
The channel of the drone's access point
</arg>
</evt>
<cmd name="set_security" id="7">
<comment
title="Set the wifi security"
desc="Set the wifi security.\nThe security is changed on the next boot."
support="0901;0902;0905;0906;090c:3.1.0"
result="The wifi security is set.\nThen, event [WifiSecurityChanged](#135-8) is triggered."/>
<arg name="type" type="enum:security_type"/>
<arg name="key" type="string">
The key to secure the network. Not used if type is open
</arg>
<arg name="key_type" type="enum:security_key_type"/>
</cmd>
<evt name="security_changed" id="8">
<comment
title="Wifi security changed"
support="0901;0902;0905;0906;090c:3.1.0"
triggered="Triggered by [SetWifiSecurity](#135-7)."/>
<arg name="key" type="string">
The key to secure the network. Not used if type is open
</arg>
<arg name="key_type" type="enum:security_type"/>
</evt>
<cmd name="set_country" id="9">
<comment
title="Set the wifi country"
desc="Set the wifi country."
support="0901;0902;0905;0906;090c"
result="The country of the product is changed.\nThen, it will trigger [CountryChanged](#135-10)."/>
<arg name="selection_mode" type="enum:country_selection"/>
<arg name="code" type="string">
Country code with ISO 3166 format. Not used if automatic is 1.
</arg>
</cmd>
<evt name="country_changed" id="10">
<comment
title="Wifi country changed"
desc="Wifi country changed."
support="0901;0902;0905;0906;090c"
triggered="Triggered by [SetCountry](#135-9)."/>
<arg name="selection_mode" type="enum:country_selection"/>
<arg name="code" type="string">
Country code with ISO 3166 format, empty string means unknown country.
</arg>
</evt>
<cmd name="set_environment" id="11">
<comment
title="Set indoor/outdoor wifi settings"
desc="Set indoor or outdoor wifi settings."
support="0901;0902;0905;0906;090c"
result="The product change its indoor/outdoor wifi settings.\nThen, it will trigger [OutdoorChanged](#135-12).\nAccording to the country (defined by [SetAutoCountry](#wifi-AutoCountry) or [SetCountry](#wifi-Country)) laws the drone might change its wifi band and channel. So a disconnection might appear."/>
<arg name="environment" type="enum:environment"/>
</cmd>
<evt name="environment_changed" id="12">
<comment
title="Outdoor setting changed"
desc="Status of the wifi config : either indoor or outdoor."
support="0901;0902;0905;0906;090c"
triggered="Triggered by [SetOutdoor](#135-11)."/>
<arg name="environment" type="enum:environment">
1 if it uses outdoor wifi settings, 0 otherwise
</arg>
</evt>
<evt name="rssi_changed" id="13">
<comment
title="Rssi changed"
desc="Rssi Changed. This is an information about the Wifi link quality."
support="0901;0902;0905;0906;090c"
triggered="Triggered regularly when the link quality changes."/>
<arg name="rssi" type="i16">
Rssi on the connected wifi network. Rssi values are generally between -30 and -120dBm. The nearest of 0 is the better.
</arg>
</evt>
<evt name="supported_countries" id="14">
<comment
title="Supported countries"
desc="List of countries supported by the drone."
support="none"
triggered="when the supported countries list changed."/>
<arg name="countries" type="string">
List of country code in ISO 3166 format separated by ";"
</arg>
</evt>
</msgs>
</feature>

Binary file not shown.

After

Width:  |  Height:  |  Size: 371 KiB

View File

@ -0,0 +1,590 @@
from bluepy.btle import Peripheral, UUID, DefaultDelegate, BTLEException
from pyparrot.utils.colorPrint import color_print
import struct
import time
from pyparrot.commandsandsensors.DroneSensorParser import get_data_format_and_size
from datetime import datetime
class MinidroneDelegate(DefaultDelegate):
"""
Handle BLE notififications
"""
def __init__(self, handle_map, minidrone, ble_connection):
DefaultDelegate.__init__(self)
self.handle_map = handle_map
self.minidrone = minidrone
self.ble_connection = ble_connection
color_print("initializing notification delegate", "INFO")
def handleNotification(self, cHandle, data):
#print "handling notificiation from channel %d" % cHandle
#print "handle map is %s " % self.handle_map[cHandle]
#print "channel map is %s " % self.minidrone.characteristic_receive_uuids[self.handle_map[cHandle]]
#print "data is %s " % data
channel = self.ble_connection.characteristic_receive_uuids[self.handle_map[cHandle]]
(packet_type, packet_seq_num) = struct.unpack('<BB', data[0:2])
raw_data = data[2:]
if channel == 'ACK_DRONE_DATA':
# data received from drone (needs to be ack on 1e)
#color_print("calling update sensors ack true", "WARN")
self.minidrone.update_sensors(packet_type, None, packet_seq_num, raw_data, ack=True)
elif channel == 'NO_ACK_DRONE_DATA':
# data from drone (including battery and others), no ack
#color_print("drone data - no ack needed")
self.minidrone.update_sensors(packet_type, None, packet_seq_num, raw_data, ack=False)
elif channel == 'ACK_COMMAND_SENT':
# ack 0b channel, SEND_WITH_ACK
#color_print("Ack! command received!")
self.ble_connection._set_command_received('SEND_WITH_ACK', True)
elif channel == 'ACK_HIGH_PRIORITY':
# ack 0c channel, SEND_HIGH_PRIORITY
#color_print("Ack! high priority received")
self.ble_connection._set_command_received('SEND_HIGH_PRIORITY', True)
else:
color_print("unknown channel %s sending data " % channel, "ERROR")
color_print(cHandle)
class BLEConnection:
def __init__(self, address, minidrone):
"""
Initialize with its BLE address - if you don't know the address, call findMinidrone
and that will discover it for you.
:param address: unique address for this minidrone
:param minidrone: the Minidrone object for this minidrone (needed for callbacks for sensors)
"""
self.address = address
self.drone_connection = Peripheral()
self.minidrone = minidrone
# the following UUID segments come from the Minidrone and from the documenation at
# http://forum.developer.parrot.com/t/minidrone-characteristics-uuid/4686/3
# the 3rd and 4th bytes are used to identify the service
self.service_uuids = {
'fa00': 'ARCOMMAND_SENDING_SERVICE',
'fb00': 'ARCOMMAND_RECEIVING_SERVICE',
'fc00': 'PERFORMANCE_COUNTER_SERVICE',
'fd21': 'NORMAL_BLE_FTP_SERVICE',
'fd51': 'UPDATE_BLE_FTP',
'fe00': 'UPDATE_RFCOMM_SERVICE',
'1800': 'Device Info',
'1801': 'unknown',
}
# the following characteristic UUID segments come from the documentation at
# http://forum.developer.parrot.com/t/minidrone-characteristics-uuid/4686/3
# the 4th bytes are used to identify the characteristic
# the usage of the channels are also documented here
# http://forum.developer.parrot.com/t/ble-characteristics-of-minidrones/5912/2
self.characteristic_send_uuids = {
'0a': 'SEND_NO_ACK', # not-ack commandsandsensors (PCMD only)
'0b': 'SEND_WITH_ACK', # ack commandsandsensors (all piloting commandsandsensors)
'0c': 'SEND_HIGH_PRIORITY', # emergency commandsandsensors
'1e': 'ACK_COMMAND' # ack for data sent on 0e
}
# counters for each packet (required as part of the packet)
self.characteristic_send_counter = {
'SEND_NO_ACK': 0,
'SEND_WITH_ACK': 0,
'SEND_HIGH_PRIORITY': 0,
'ACK_COMMAND': 0,
'RECEIVE_WITH_ACK': 0
}
# the following characteristic UUID segments come from the documentation at
# http://forum.developer.parrot.com/t/minidrone-characteristics-uuid/4686/3
# the 4th bytes are used to identify the characteristic
# the types of commandsandsensors and data coming back are also documented here
# http://forum.developer.parrot.com/t/ble-characteristics-of-minidrones/5912/2
self.characteristic_receive_uuids = {
'0e': 'ACK_DRONE_DATA', # drone data that needs an ack (needs to be ack on 1e)
'0f': 'NO_ACK_DRONE_DATA', # data from drone (including battery and others), no ack
'1b': 'ACK_COMMAND_SENT', # ack 0b channel, SEND_WITH_ACK
'1c': 'ACK_HIGH_PRIORITY', # ack 0c channel, SEND_HIGH_PRIORITY
}
# these are the FTP incoming and outcoming channels
# the handling characteristic seems to be the one to send commandsandsensors to (per the SDK)
# information gained from reading ARUTILS_BLEFtp.m in the SDK
self.characteristic_ftp_uuids = {
'22': 'NORMAL_FTP_TRANSFERRING',
'23': 'NORMAL_FTP_GETTING',
'24': 'NORMAL_FTP_HANDLING',
'52': 'UPDATE_FTP_TRANSFERRING',
'53': 'UPDATE_FTP_GETTING',
'54': 'UPDATE_FTP_HANDLING',
}
# FTP commandsandsensors (obtained via ARUTILS_BLEFtp.m in the SDK)
self.ftp_commands = {
"list": "LIS",
"get": "GET"
}
# need to save for communication (but they are initialized in connect)
self.services = None
self.send_characteristics = dict()
self.receive_characteristics = dict()
self.handshake_characteristics = dict()
self.ftp_characteristics = dict()
self.data_types = {
'ACK': 1,
'DATA_NO_ACK': 2,
'LOW_LATENCY_DATA': 3,
'DATA_WITH_ACK': 4
}
# store whether a command was acked
self.command_received = {
'SEND_WITH_ACK': False,
'SEND_HIGH_PRIORITY': False,
'ACK_COMMAND': False
}
# instead of parsing the XML file every time, cache the results
self.command_tuple_cache = dict()
self.sensor_tuple_cache = dict()
# maximum number of times to try a packet before assuming it failed
self.max_packet_retries = 3
def connect(self, num_retries):
"""
Connects to the drone and re-tries in case of failure the specified number of times
:param: num_retries is the number of times to retry
:return: True if it succeeds and False otherwise
"""
# first try to connect to the wifi
try_num = 1
connected = False
while (try_num < num_retries and not connected):
try:
self._connect()
connected = True
except BTLEException:
color_print("retrying connections", "INFO")
try_num += 1
# fall through, return False as something failed
return connected
def _reconnect(self, num_retries):
"""
Reconnect to the drone (assumed the BLE crashed)
:param: num_retries is the number of times to retry
:return: True if it succeeds and False otherwise
"""
try_num = 1
success = False
while (try_num < num_retries and not success):
try:
color_print("trying to re-connect to the minidrone at address %s" % self.address, "WARN")
self.drone_connection.connect(self.address, "random")
color_print("connected! Asking for services and characteristics", "SUCCESS")
success = True
except BTLEException:
color_print("retrying connections", "WARN")
try_num += 1
if (success):
# do the magic handshake
self._perform_handshake()
return success
def _connect(self):
"""
Connect to the minidrone to prepare for flying - includes getting the services and characteristics
for communication
:return: throws an error if the drone connection failed. Returns void if nothing failed.
"""
color_print("trying to connect to the minidrone at address %s" % self.address, "INFO")
self.drone_connection.connect(self.address, "random")
color_print("connected! Asking for services and characteristics", "SUCCESS")
# re-try until all services have been found
allServicesFound = False
# used for notifications
handle_map = dict()
while not allServicesFound:
# get the services
self.services = self.drone_connection.getServices()
# loop through the services
for s in self.services:
hex_str = self._get_byte_str_from_uuid(s.uuid, 3, 4)
# store the characteristics for receive & send
if (self.service_uuids[hex_str] == 'ARCOMMAND_RECEIVING_SERVICE'):
# only store the ones used to receive data
for c in s.getCharacteristics():
hex_str = self._get_byte_str_from_uuid(c.uuid, 4, 4)
if hex_str in self.characteristic_receive_uuids:
self.receive_characteristics[self.characteristic_receive_uuids[hex_str]] = c
handle_map[c.getHandle()] = hex_str
elif (self.service_uuids[hex_str] == 'ARCOMMAND_SENDING_SERVICE'):
# only store the ones used to send data
for c in s.getCharacteristics():
hex_str = self._get_byte_str_from_uuid(c.uuid, 4, 4)
if hex_str in self.characteristic_send_uuids:
self.send_characteristics[self.characteristic_send_uuids[hex_str]] = c
elif (self.service_uuids[hex_str] == 'UPDATE_BLE_FTP'):
# store the FTP info
for c in s.getCharacteristics():
hex_str = self._get_byte_str_from_uuid(c.uuid, 4, 4)
if hex_str in self.characteristic_ftp_uuids:
self.ftp_characteristics[self.characteristic_ftp_uuids[hex_str]] = c
elif (self.service_uuids[hex_str] == 'NORMAL_BLE_FTP_SERVICE'):
# store the FTP info
for c in s.getCharacteristics():
hex_str = self._get_byte_str_from_uuid(c.uuid, 4, 4)
if hex_str in self.characteristic_ftp_uuids:
self.ftp_characteristics[self.characteristic_ftp_uuids[hex_str]] = c
# need to register for notifications and write 0100 to the right handles
# this is sort of magic (not in the docs!) but it shows up on the forum here
# http://forum.developer.parrot.com/t/minimal-ble-commands-to-send-for-take-off/1686/2
# Note this code snippet below more or less came from the python example posted to that forum (I adapted it to my interface)
for c in s.getCharacteristics():
if self._get_byte_str_from_uuid(c.uuid, 3, 4) in \
['fb0f', 'fb0e', 'fb1b', 'fb1c', 'fd22', 'fd23', 'fd24', 'fd52', 'fd53', 'fd54']:
self.handshake_characteristics[self._get_byte_str_from_uuid(c.uuid, 3, 4)] = c
# check to see if all 8 characteristics were found
allServicesFound = True
for r_id in self.characteristic_receive_uuids.values():
if r_id not in self.receive_characteristics:
color_print("setting to false in receive on %s" % r_id)
allServicesFound = False
for s_id in self.characteristic_send_uuids.values():
if s_id not in self.send_characteristics:
color_print("setting to false in send")
allServicesFound = False
for f_id in self.characteristic_ftp_uuids.values():
if f_id not in self.ftp_characteristics:
color_print("setting to false in ftp")
allServicesFound = False
# and ensure all handshake characteristics were found
if len(self.handshake_characteristics.keys()) != 10:
color_print("setting to false in len")
allServicesFound = False
# do the magic handshake
self._perform_handshake()
# initialize the delegate to handle notifications
self.drone_connection.setDelegate(MinidroneDelegate(handle_map, self.minidrone, self))
def _perform_handshake(self):
"""
Magic handshake
Need to register for notifications and write 0100 to the right handles
This is sort of magic (not in the docs!) but it shows up on the forum here
http://forum.developer.parrot.com/t/minimal-ble-commandsandsensors-to-send-for-take-off/1686/2
:return: nothing
"""
color_print("magic handshake to make the drone listen to our commandsandsensors")
# Note this code snippet below more or less came from the python example posted to that forum (I adapted it to my interface)
for c in self.handshake_characteristics.values():
# for some reason bluepy characteristic handle is two lower than what I need...
# Need to write 0x0100 to the characteristics value handle (which is 2 higher)
self.drone_connection.writeCharacteristic(c.handle + 2, struct.pack("<BB", 1, 0))
def disconnect(self):
"""
Disconnect the BLE connection. Always call this at the end of your programs to
cleanly disconnect.
:return: void
"""
self.drone_connection.disconnect()
def _get_byte_str_from_uuid(self, uuid, byte_start, byte_end):
"""
Extract the specified byte string from the UUID btle object. This is an ugly hack
but it was necessary because of the way the UUID object is represented and the documentation
on the byte strings from Parrot. You give it the starting byte (counting from 1 since
that is how their docs count) and the ending byte and it returns that as a string extracted
from the UUID. It is assumed it happens before the first - in the UUID.
:param uuid: btle UUID object
:param byte_start: starting byte (counting from 1)
:param byte_end: ending byte (counting from 1)
:return: string with the requested bytes (to be used as a key in the lookup tables for services)
"""
uuid_str = format("%s" % uuid)
idx_start = 2 * (byte_start - 1)
idx_end = 2 * (byte_end)
my_hex_str = uuid_str[idx_start:idx_end]
return my_hex_str
def send_turn_command(self, command_tuple, degrees):
"""
Build the packet for turning and send it
:param command_tuple: command tuple from the parser
:param degrees: how many degrees to turn
:return: True if the command was sent and False otherwise
"""
self.characteristic_send_counter['SEND_WITH_ACK'] = (self.characteristic_send_counter['SEND_WITH_ACK'] + 1) % 256
packet = struct.pack("<BBBBHh", self.data_types['DATA_WITH_ACK'],
self.characteristic_send_counter['SEND_WITH_ACK'],
command_tuple[0], command_tuple[1], command_tuple[2],
degrees)
return self.send_command_packet_ack(packet)
def send_auto_takeoff_command(self, command_tuple):
"""
Build the packet for auto takeoff and send it
:param command_tuple: command tuple from the parser
:return: True if the command was sent and False otherwise
"""
# print command_tuple
self.characteristic_send_counter['SEND_WITH_ACK'] = (
self.characteristic_send_counter[
'SEND_WITH_ACK'] + 1) % 256
packet = struct.pack("<BBBBHB", self.data_types['DATA_WITH_ACK'],
self.characteristic_send_counter['SEND_WITH_ACK'],
command_tuple[0], command_tuple[1], command_tuple[2],
1)
return self.send_command_packet_ack(packet)
def send_command_packet_ack(self, packet):
"""
Sends the actual packet on the ack channel. Internal function only.
:param packet: packet constructed according to the command rules (variable size, constructed elsewhere)
:return: True if the command was sent and False otherwise
"""
try_num = 0
self._set_command_received('SEND_WITH_ACK', False)
while (try_num < self.max_packet_retries and not self.command_received['SEND_WITH_ACK']):
color_print("sending command packet on try %d" % try_num, 2)
self._safe_ble_write(characteristic=self.send_characteristics['SEND_WITH_ACK'], packet=packet)
#self.send_characteristics['SEND_WITH_ACK'].write(packet)
try_num += 1
color_print("sleeping for a notification", 2)
#notify = self.drone.waitForNotifications(1.0)
self.smart_sleep(0.5)
#color_print("awake %s " % notify, 2)
return self.command_received['SEND_WITH_ACK']
def send_pcmd_command(self, command_tuple, roll, pitch, yaw, vertical_movement, duration):
"""
Send the PCMD command with the specified roll, pitch, and yaw
:param command_tuple: command tuple per the parser
:param roll:
:param pitch:
:param yaw:
:param vertical_movement:
:param duration:
"""
start_time = time.time()
while (time.time() - start_time < duration):
self.characteristic_send_counter['SEND_NO_ACK'] = (
self.characteristic_send_counter['SEND_NO_ACK'] + 1) % 256
packet = struct.pack("<BBBBHBbbbbI", self.data_types['DATA_NO_ACK'],
self.characteristic_send_counter['SEND_NO_ACK'],
command_tuple[0], command_tuple[1], command_tuple[2],
1, int(roll), int(pitch), int(yaw), int(vertical_movement), 0)
self._safe_ble_write(characteristic=self.send_characteristics['SEND_NO_ACK'], packet=packet)
# self.send_characteristics['SEND_NO_ACK'].write(packet)
notify = self.drone_connection.waitForNotifications(0.1)
def send_noparam_command_packet_ack(self, command_tuple):
"""
Send a command on the ack channel - where all commandsandsensors except PCMD go, per
http://forum.developer.parrot.com/t/ble-characteristics-of-minidrones/5912/2
the id of the last command sent (for use in ack) is the send counter (which is incremented before sending)
Ensures the packet was received or sends it again up to a maximum number of times.
:param command_tuple: 3 tuple of the command bytes. 0 padded for 4th byte
:return: True if the command was sent and False otherwise
"""
self.characteristic_send_counter['SEND_WITH_ACK'] = (self.characteristic_send_counter['SEND_WITH_ACK'] + 1) % 256
packet = struct.pack("<BBBBH", self.data_types['DATA_WITH_ACK'], self.characteristic_send_counter['SEND_WITH_ACK'],
command_tuple[0], command_tuple[1], command_tuple[2])
return self.send_command_packet_ack(packet)
def send_enum_command_packet_ack(self, command_tuple, enum_value, usb_id=None):
"""
Send a command on the ack channel with enum parameters as well (most likely a flip).
All commandsandsensors except PCMD go on the ack channel per
http://forum.developer.parrot.com/t/ble-characteristics-of-minidrones/5912/2
the id of the last command sent (for use in ack) is the send counter (which is incremented before sending)
:param command_tuple: 3 tuple of the command bytes. 0 padded for 4th byte
:param enum_value: the enum index
:return: nothing
"""
self.characteristic_send_counter['SEND_WITH_ACK'] = (self.characteristic_send_counter['SEND_WITH_ACK'] + 1) % 256
if (usb_id is None):
packet = struct.pack("<BBBBBBI", self.data_types['DATA_WITH_ACK'], self.characteristic_send_counter['SEND_WITH_ACK'],
command_tuple[0], command_tuple[1], command_tuple[2], 0,
enum_value)
else:
color_print((self.data_types['DATA_WITH_ACK'], self.characteristic_send_counter['SEND_WITH_ACK'],
command_tuple[0], command_tuple[1], command_tuple[2], 0, usb_id, enum_value), 1)
packet = struct.pack("<BBBBHBI", self.data_types['DATA_WITH_ACK'], self.characteristic_send_counter['SEND_WITH_ACK'],
command_tuple[0], command_tuple[1], command_tuple[2],
usb_id, enum_value)
return self.send_command_packet_ack(packet)
def send_param_command_packet(self, command_tuple, param_tuple=None, param_type_tuple=0, ack=True):
"""
Send a command packet with parameters. Ack channel is optional for future flexibility,
but currently commands are always send over the Ack channel so it defaults to True.
Contributed by awm102 on github. Edited by Amy McGovern to work for BLE commands also.
:param: command_tuple: the command tuple derived from command_parser.get_command_tuple()
:param: param_tuple (optional): the parameter values to be sent (can be found in the XML files)
:param: param_size_tuple (optional): a tuple of strings representing the data type of the parameters
e.g. u8, float etc. (can be found in the XML files)
:param: ack (optional): allows ack to be turned off if required
:return:
"""
# Create lists to store the number of bytes and pack chars needed for parameters
# Default them to zero so that if no params are provided the packet size is correct
param_size_list = [0] * len(param_tuple)
pack_char_list = [0] * len(param_tuple)
if param_tuple is not None:
# Fetch the parameter sizes. By looping over the param_tuple we only get the data
# for requested parameters so a mismatch in params and types does not matter
for i, param in enumerate(param_tuple):
pack_char_list[i], param_size_list[i] = get_data_format_and_size(param, param_type_tuple[i])
if ack:
ack_string = 'SEND_WITH_ACK'
data_ack_string = 'DATA_WITH_ACK'
else:
ack_string = 'SEND_NO_ACK'
data_ack_string = 'DATA_NO_ACK'
# Construct the base packet
self.characteristic_send_counter['SEND_WITH_ACK'] = (self.characteristic_send_counter['SEND_WITH_ACK'] + 1) % 256
# TODO: Amy changed this to match the BLE packet structure but needs to fully test it
packet = struct.pack("<BBBBH", self.data_types[data_ack_string],
self.characteristic_send_counter[ack_string],
command_tuple[0], command_tuple[1], command_tuple[2])
if param_tuple is not None:
# Add in the parameter values based on their sizes
for i, param in enumerate(param_tuple):
packet += struct.pack(pack_char_list[i], param)
# TODO: Fix this to not go with ack always
return self.send_command_packet_ack(packet)
def _set_command_received(self, channel, val):
"""
Set the command received on the specified channel to the specified value (used for acks)
:param channel: channel
:param val: True or False
:return:
"""
self.command_received[channel] = val
def _safe_ble_write(self, characteristic, packet):
"""
Write to the specified BLE characteristic but first ensure the connection is valid
:param characteristic:
:param packet:
:return:
"""
success = False
while (not success):
try:
characteristic.write(packet)
success = True
except BTLEException:
color_print("reconnecting to send packet", "WARN")
self._reconnect(3)
def ack_packet(self, buffer_id, packet_id):
"""
Ack the packet id specified by the argument on the ACK_COMMAND channel
:param packet_id: the packet id to ack
:return: nothing
"""
#color_print("ack last packet on the ACK_COMMAND channel", "INFO")
self.characteristic_send_counter['ACK_COMMAND'] = (self.characteristic_send_counter['ACK_COMMAND'] + 1) % 256
packet = struct.pack("<BBB", self.data_types['ACK'], self.characteristic_send_counter['ACK_COMMAND'],
packet_id)
#color_print("sending packet %d %d %d" % (self.data_types['ACK'], self.characteristic_send_counter['ACK_COMMAND'],
# packet_id), "INFO")
self._safe_ble_write(characteristic=self.send_characteristics['ACK_COMMAND'], packet=packet)
#self.send_characteristics['ACK_COMMAND'].write(packet)
def smart_sleep(self, timeout):
"""
Sleeps the requested number of seconds but wakes up for notifications
Note: NEVER use regular time.sleep! It is a blocking sleep and it will likely
cause the BLE to disconnect due to dropped notifications. Always use smart_sleep instead!
:param timeout: number of seconds to sleep
:return:
"""
start_time = datetime.now()
new_time = datetime.now()
diff = (new_time - start_time).seconds + ((new_time - start_time).microseconds / 1000000.0)
while (diff < timeout):
try:
notify = self.drone_connection.waitForNotifications(0.1)
except:
color_print("reconnecting to wait", "WARN")
self._reconnect(3)
new_time = datetime.now()
diff = (new_time - start_time).seconds + ((new_time - start_time).microseconds / 1000000.0)

View File

@ -0,0 +1,731 @@
"""
Holds all the data and commands needed to fly a Bebop drone.
Author: Amy McGovern, dramymcgovern@gmail.com
"""
from zeroconf import ServiceBrowser, Zeroconf
from datetime import datetime
import time
import socket
import ipaddress
import json
from pyparrot.utils.colorPrint import color_print
import struct
import threading
from pyparrot.commandsandsensors.DroneSensorParser import get_data_format_and_size
class mDNSListener(object):
"""
This is adapted from the listener code at
https://pypi.python.org/pypi/zeroconf
"""
def __init__(self, wifi_connection):
self.wifi_connection = wifi_connection
def remove_service(self, zeroconf, type, name):
#print("Service %s removed" % (name,))
pass
def add_service(self, zeroconf, type, name):
info = zeroconf.get_service_info(type, name)
print("Service %s added, service info: %s" % (name, info))
self.wifi_connection._connect_listener_called(info)
class WifiConnection:
def __init__(self, drone, drone_type="Bebop2", ip_address=None):
"""
Can be a connection to a Bebop, Bebop2 or a Mambo right now
:param type: type of drone to connect to
"""
self.is_connected = False
if (drone_type not in ("Bebop", "Bebop2", "Mambo", "Disco")):
color_print("Error: only type Bebop Disco and Mambo are currently supported", "ERROR")
return
self.drone = drone
self.drone_type = drone_type
self.udp_send_port = 44444 # defined during the handshake except not on Mambo after 3.0.26 firmware
self.udp_receive_port = 43210
self.is_listening = True # for the UDP listener
self.ip_address = ip_address
if (drone_type is "Bebop"):
self.mdns_address = "_arsdk-0901._udp.local."
#Bebop video streaming
self.stream_port = 55004
self.stream_control_port = 55005
elif (drone_type is "Bebop2"):
self.mdns_address = "_arsdk-090c._udp.local."
#Bebop video streaming
self.stream_port = 55004
self.stream_control_port = 55005
elif (drone_type is "Disco"):
self.mdns_address = "_arsdk-090e._udp.local."
#Bebop video streaming
self.stream_port = 55004
self.stream_control_port = 55005
elif (drone_type is "Mambo"):
self.mdns_address = "_arsdk-090b._udp.local."
# map of the data types by name (for outgoing packets)
self.data_types_by_name = {
'ACK' : 1,
'DATA_NO_ACK': 2,
'LOW_LATENCY_DATA': 3,
'DATA_WITH_ACK' : 4
}
# map of the incoming data types by number (to figure out if we need to ack etc)
self.data_types_by_number = {
1 : 'ACK',
2 : 'DATA_NO_ACK',
3 : 'LOW_LATENCY_DATA',
4 : 'DATA_WITH_ACK'
}
self.sequence_counter = {
'PONG': 0,
'SEND_NO_ACK': 0,
'SEND_WITH_ACK': 0,
'SEND_HIGH_PRIORITY': 0,
'VIDEO_ACK': 0,
'ACK_DRONE_DATA': 0,
'NO_ACK_DRONE_DATA': 0,
'VIDEO_DATA': 0,
}
self.buffer_ids = {
'PING': 0, # pings from device
'PONG': 1, # respond to pings
'SEND_NO_ACK': 10, # not-ack commandsandsensors (piloting and camera rotations)
'SEND_WITH_ACK': 11, # ack commandsandsensors (all piloting commandsandsensors)
'SEND_HIGH_PRIORITY': 12, # emergency commandsandsensors
'VIDEO_ACK': 13, # ack for video
'ACK_DRONE_DATA' : 127, # drone data that needs an ack
'NO_ACK_DRONE_DATA' : 126, # data from drone (including battery and others), no ack
'VIDEO_DATA' : 125, # video data
'ACK_FROM_SEND_WITH_ACK': 139 # 128 + buffer id for 'SEND_WITH_ACK' is 139
}
self.data_buffers = (self.buffer_ids['ACK_DRONE_DATA'], self.buffer_ids['NO_ACK_DRONE_DATA'])
# store whether a command was acked
self.command_received = {
'SEND_WITH_ACK': False,
'SEND_HIGH_PRIORITY': False,
'ACK_COMMAND': False
}
# maximum number of times to try a packet before assuming it failed
self.max_packet_retries = 1
# threading lock for waiting
self._lock = threading.Lock()
def connect(self, num_retries):
"""
Connects to the drone
:param num_retries: maximum number of retries
:return: True if the connection succeeded and False otherwise
"""
if (self.ip_address is None) and ("Mambo" not in self.drone_type):
print("Setting up mDNS listener since this is not a Mambo")
#parrot's latest mambo firmware (3.0.26 broke all of the mDNS services so this is (temporarily) commented
#out but it is backwards compatible and will work with the hard-coded addresses for now.
zeroconf = Zeroconf()
listener = mDNSListener(self)
print("Making a browser for %s" % self.mdns_address)
browser = ServiceBrowser(zeroconf, self.mdns_address , listener)
# basically have to sleep until the info comes through on the listener
num_tries = 0
while (num_tries < num_retries and not self.is_connected):
time.sleep(1)
num_tries += 1
# if we didn't hear the listener, return False
if (not self.is_connected):
color_print("connection failed: did you remember to connect your machine to the Drone's wifi network?", "ERROR")
return False
else:
browser.cancel()
# perform the handshake and get the UDP info
handshake = self._handshake(num_retries)
if (handshake):
self._create_udp_connection()
self.listener_thread = threading.Thread(target=self._listen_socket)
self.listener_thread.start()
color_print("Success in setting up the wifi network to the drone!", "SUCCESS")
return True
else:
color_print("Error: TCP handshake failed.", "ERROR")
return False
def _listen_socket(self):
"""
Listens to the socket and sleeps in between receives.
Runs forever (until disconnect is called)
"""
print("starting listening at ")
data = None
while (self.is_listening):
try:
(data, address) = self.udp_receive_sock.recvfrom(66000)
except socket.timeout:
print("timeout - trying again")
except:
pass
self.handle_data(data)
color_print("disconnecting", "INFO")
self.disconnect()
def handle_data(self, data):
"""
Handles the data as it comes in
:param data: raw data packet
:return:
"""
# got the idea to of how to handle this data nicely (handling the perhaps extra data in the packets)
# and unpacking the critical info first (id, size etc) from
# https://github.com/N-Bz/bybop/blob/8d4c569c8e66bd1f0fdd768851409ca4b86c4ecd/src/Bybop_NetworkAL.py
my_data = data
while (my_data):
#print("inside loop to handle data ")
(data_type, buffer_id, packet_seq_id, packet_size) = struct.unpack('<BBBI', my_data[0:7])
recv_data = my_data[7:packet_size]
#print("\tgot a data type of of %d " % data_type)
#print("\tgot a buffer id of of %d " % buffer_id)
#print("\tgot a packet seq id of of %d " % packet_seq_id)
#print("\tsize is %d" % packet_size)
self.handle_frame(data_type, buffer_id, packet_seq_id, recv_data)
# loop in case there is more data
my_data = my_data[packet_size:]
#print("assigned more data")
#print("ended loop handling data")
def handle_frame(self, packet_type, buffer_id, packet_seq_id, recv_data):
if (buffer_id == self.buffer_ids['PING']):
#color_print("this is a ping! need to pong", "INFO")
self._send_pong(recv_data)
if (self.data_types_by_number[packet_type] == 'ACK'):
#print("setting command received to true")
ack_seq = int(struct.unpack("<B", recv_data)[0])
self._set_command_received('SEND_WITH_ACK', True, ack_seq)
self.ack_packet(buffer_id, ack_seq)
elif (self.data_types_by_number[packet_type] == 'DATA_NO_ACK'):
#print("DATA NO ACK")
if (buffer_id in self.data_buffers):
self.drone.update_sensors(packet_type, buffer_id, packet_seq_id, recv_data, ack=False)
elif (self.data_types_by_number[packet_type] == 'LOW_LATENCY_DATA'):
print("Need to handle Low latency data")
elif (self.data_types_by_number[packet_type] == 'DATA_WITH_ACK'):
#print("DATA WITH ACK")
if (buffer_id in self.data_buffers):
self.drone.update_sensors(packet_type, buffer_id, packet_seq_id, recv_data, ack=True)
else:
color_print("HELP ME", "ERROR")
print("got a different type of data - help")
def _send_pong(self, data):
"""
Send a PONG back to a PING
:param data: data that needs to be PONG/ACK'd
:return: nothing
"""
size = len(data)
self.sequence_counter['PONG'] = (self.sequence_counter['PONG'] + 1) % 256
packet = struct.pack("<BBBI", self.data_types_by_name['DATA_NO_ACK'], self.buffer_ids['PONG'],
self.sequence_counter['PONG'], size + 7)
packet += data
self.safe_send(packet)
def _set_command_received(self, channel, val, seq_id):
"""
Set the command received on the specified channel to the specified value (used for acks)
:param channel: channel
:param val: True or False
:return:
"""
self.command_received[(channel, seq_id)] = val
def _is_command_received(self, channel, seq_id):
"""
Is the command received?
:param channel: channel it was sent on
:param seq_id: sequence id of the command
:return:
"""
return self.command_received[(channel, seq_id)]
def _handshake(self, num_retries):
"""
Performs the handshake over TCP to get all the connection info
:return: True if it worked and False otherwise
"""
# create the TCP socket for the handshake
tcp_sock = socket.socket(family=socket.AF_INET, type=socket.SOCK_STREAM)
#print (self.connection_info.address, self.connection_info.port)
#print(ipaddress.IPv4Address(self.connection_info.address))
# connect
# handle the broken mambo firmware by hard-coding the port and IP address
if ("Mambo" in self.drone_type):
self.drone_ip = "192.168.99.3"
tcp_sock.connect(("192.168.99.3", 44444))
else:
if (self.ip_address is None):
self.drone_ip = ipaddress.IPv4Address(self.connection_info.address).exploded
tcp_sock.connect((self.drone_ip, self.connection_info.port))
else:
self.drone_ip = ipaddress.IPv4Address(self.ip_address).exploded
tcp_sock.connect((self.drone_ip, 44444))
# send the handshake information
if(self.drone_type in ("Bebop", "Bebop2", "Disco")):
# For Bebop add video stream ports to the json request
json_string = json.dumps({"d2c_port":self.udp_receive_port,
"controller_type":"computer",
"controller_name":"pyparrot",
"arstream2_client_stream_port":self.stream_port,
"arstream2_client_control_port":self.stream_control_port})
else:
json_string = json.dumps({"d2c_port":self.udp_receive_port,
"controller_type":"computer",
"controller_name":"pyparrot"})
json_obj = json.loads(json_string)
print(json_string)
try:
# python 3
tcp_sock.send(bytes(json_string, 'utf-8'))
except:
# python 2
tcp_sock.send(json_string)
# wait for the response
finished = False
num_try = 0
while (not finished and num_try < num_retries):
data = tcp_sock.recv(4096).decode('utf-8')
if (len(data) > 0):
my_data = data[0:-1]
self.udp_data = json.loads(str(my_data))
# if the drone refuses the connection, return false
if (self.udp_data['status'] != 0):
return False
print(self.udp_data)
self.udp_send_port = self.udp_data['c2d_port']
print("c2d_port is %d" % self.udp_send_port)
finished = True
else:
num_try += 1
# cleanup
tcp_sock.close()
return finished
def _create_udp_connection(self):
"""
Create the UDP connection
"""
self.udp_send_sock = socket.socket(family=socket.AF_INET, type=socket.SOCK_DGRAM)
#self.udp_send_sock.connect((self.drone_ip, self.udp_send_port))
self.udp_receive_sock = socket.socket(family=socket.AF_INET, type=socket.SOCK_DGRAM)
# don't use the connect, use bind instead
# learned from bybop code
# https://github.com/N-Bz/bybop/blob/8d4c569c8e66bd1f0fdd768851409ca4b86c4ecd/src/Bybop_NetworkAL.py
#self.udp_receive_sock.connect((self.drone_ip, self.udp_receive_port))
self.udp_receive_sock.settimeout(5.0)
#Some computers having connection refused error (error was some kind of that, I dont remember actually)
#These new setsockopt lines solving it (at least at my device)
self.udp_receive_sock.setsockopt(socket.SOL_SOCKET,socket.SO_REUSEADDR,1)
self.udp_send_sock.setsockopt(socket.SOL_SOCKET,socket.SO_REUSEADDR,1)
self.udp_receive_sock.bind(('0.0.0.0', int(self.udp_receive_port)))
def _connect_listener_called(self, connection_info):
"""
Save the connection info and set the connected to be true. This si called within the listener
for the connection.
:param connection_info:
:return:
"""
self.connection_info = connection_info
self.is_connected = True
def disconnect(self):
"""
Disconnect cleanly from the sockets
"""
self.is_listening = False
# Sleep for a moment to allow all socket activity to cease before closing
# This helps to avoids a Winsock error regarding a operations on a closed socket
self.smart_sleep(0.5)
# then put the close in a try/except to catch any further winsock errors
# the errors seem to be mostly occurring on windows for some reason
try:
self.udp_receive_sock.close()
self.udp_send_sock.close()
except:
pass
def safe_send(self, packet):
packet_sent = False
#print "inside safe send"
try_num = 0
while (not packet_sent and try_num < self.max_packet_retries):
try:
self.udp_send_sock.sendto(packet, (self.drone_ip, self.udp_send_port))
packet_sent = True
except:
#print "resetting connection"
self.udp_send_sock = socket.socket(family=socket.AF_INET, type=socket.SOCK_DGRAM)
#self.udp_send_sock.connect((self.drone_ip, self.udp_send_port))
try_num += 1
def send_command_packet_ack(self, packet, seq_id):
"""
Sends the actual packet on the ack channel. Internal function only.
:param packet: packet constructed according to the command rules (variable size, constructed elsewhere)
:return: True if the command was sent and False otherwise
"""
try_num = 0
self._set_command_received('SEND_WITH_ACK', False, seq_id)
while (try_num < self.max_packet_retries and not self._is_command_received('SEND_WITH_ACK', seq_id)):
color_print("sending packet on try %d", try_num)
self.safe_send(packet)
try_num += 1
self.smart_sleep(0.5)
return self._is_command_received('SEND_WITH_ACK', seq_id)
def send_command_packet_noack(self, packet):
"""
Sends the actual packet on the No-ack channel. Internal function only.
:param packet: packet constructed according to the command rules (variable size, constructed elsewhere)
:return: True if the command was sent and False otherwise
"""
try_num = 0
color_print("sending packet on try %d", try_num)
self.safe_send(packet)
def send_noparam_high_priority_command_packet(self, command_tuple):
"""
Send a no parameter command packet on the high priority channel
:param command_tuple:
:return:
"""
self.sequence_counter['SEND_HIGH_PRIORITY'] = (self.sequence_counter['SEND_HIGH_PRIORITY'] + 1) % 256
packet = struct.pack("<BBBIBBH", self.data_types_by_name['LOW_LATENCY_DATA'],
self.buffer_ids['SEND_HIGH_PRIORITY'],
self.sequence_counter['SEND_HIGH_PRIORITY'], 11,
command_tuple[0], command_tuple[1], command_tuple[2])
self.safe_send(packet)
def send_noparam_command_packet_ack(self, command_tuple):
"""
Send a no parameter command packet on the ack channel
:param command_tuple:
:return:
"""
self.sequence_counter['SEND_WITH_ACK'] = (self.sequence_counter['SEND_WITH_ACK'] + 1) % 256
packet = struct.pack("<BBBIBBH", self.data_types_by_name['DATA_WITH_ACK'],
self.buffer_ids['SEND_WITH_ACK'],
self.sequence_counter['SEND_WITH_ACK'], 11,
command_tuple[0], command_tuple[1], command_tuple[2])
return self.send_command_packet_ack(packet, self.sequence_counter['SEND_WITH_ACK'])
def send_param_command_packet(self, command_tuple, param_tuple=None, param_type_tuple=0,ack=True):
"""
Send a command packet with parameters. Ack channel is optional for future flexibility,
but currently commands are always send over the Ack channel so it defaults to True.
Contributed by awm102 on github
:param: command_tuple: the command tuple derived from command_parser.get_command_tuple()
:param: param_tuple (optional): the parameter values to be sent (can be found in the XML files)
:param: param_size_tuple (optional): a tuple of strings representing the data type of the parameters
e.g. u8, float etc. (can be found in the XML files)
:param: ack (optional): allows ack to be turned off if required
:return:
"""
# TODO: This function could potentially be extended to encompass send_noparam_command_packet_ack
# and send_enum_command_packet_ack if desired for more modular code.
# TODO: The function could be improved by looking up the parameter data types in the xml files
# in the same way the send_enum_command_packet_ack does.
# Create lists to store the number of bytes and pack chars needed for parameters
# Default them to zero so that if no params are provided the packet size is correct
param_size_list = [0] * len(param_tuple)
pack_char_list = [0] * len(param_tuple)
if param_tuple is not None:
# Fetch the parameter sizes. By looping over the param_tuple we only get the data
# for requested parameters so a mismatch in params and types does not matter
for i,param in enumerate(param_tuple):
pack_char_list[i], param_size_list[i] = get_data_format_and_size(param, param_type_tuple[i])
if ack:
ack_string = 'SEND_WITH_ACK'
data_ack_string = 'DATA_WITH_ACK'
else:
ack_string = 'SEND_NO_ACK'
data_ack_string = 'DATA_NO_ACK'
# Construct the base packet
self.sequence_counter[ack_string] = (self.sequence_counter[ack_string] + 1) % 256
# Calculate packet size:
# base packet <BBBIBBH is 11 bytes, param_size_list can be added up
packet_size = 11 + sum(param_size_list)
packet = struct.pack("<BBBIBBH", self.data_types_by_name[data_ack_string],
self.buffer_ids[ack_string],
self.sequence_counter[ack_string], packet_size,
command_tuple[0], command_tuple[1], command_tuple[2])
if param_tuple is not None:
# Add in the parameter values based on their sizes
for i,param in enumerate(param_tuple):
packet += struct.pack(pack_char_list[i],param)
if ack:
return self.send_command_packet_ack(packet, self.sequence_counter['SEND_WITH_ACK'])
else:
return self.send_command_packet_noack(packet)
def send_single_pcmd_command(self, command_tuple, roll, pitch, yaw, vertical_movement):
"""
Send a single PCMD command with the specified roll, pitch, and yaw. Note
this will not make that command run forever. Instead it sends ONCE. This can be used
in a loop (in your agent) that makes more smooth control than using the duration option.
:param command_tuple: command tuple per the parser
:param roll:
:param pitch:
:param yaw:
:param vertical_movement:
"""
self.sequence_counter['SEND_NO_ACK'] = (self.sequence_counter['SEND_NO_ACK'] + 1) % 256
packet = struct.pack("<BBBIBBHBbbbbI",
self.data_types_by_name['DATA_NO_ACK'],
self.buffer_ids['SEND_NO_ACK'],
self.sequence_counter['SEND_NO_ACK'],
20,
command_tuple[0], command_tuple[1], command_tuple[2],
1, int(roll), int(pitch), int(yaw), int(vertical_movement), 0)
self.safe_send(packet)
def send_pcmd_command(self, command_tuple, roll, pitch, yaw, vertical_movement, duration):
"""
Send the PCMD command with the specified roll, pitch, and yaw
:param command_tuple: command tuple per the parser
:param roll:
:param pitch:
:param yaw:
:param vertical_movement:
:param duration:
"""
start_time = datetime.now()
new_time = datetime.now()
diff = (new_time - start_time).seconds + ((new_time - start_time).microseconds / 1000000.0)
while (diff < duration):
self.send_single_pcmd_command(command_tuple, roll, pitch, yaw, vertical_movement)
self.smart_sleep(0.1)
new_time = datetime.now()
diff = (new_time - start_time).seconds + ((new_time - start_time).microseconds / 1000000.0)
def send_fly_relative_command(self, command_tuple, change_x, change_y, change_z, change_angle):
"""
Send the packet to fly relative (this is Bebop only).
:param command_tuple: command tuple per the parser
:param change_x: change in x
:param change_y: change in y
:param change_z: change in z
:param change_angle: change in angle
"""
self.sequence_counter['SEND_WITH_ACK'] = (self.sequence_counter['SEND_WITH_ACK'] + 1) % 256
packet = struct.pack("<BBBIBBHffff",
self.data_types_by_name['DATA_WITH_ACK'],
self.buffer_ids['SEND_WITH_ACK'],
self.sequence_counter['SEND_WITH_ACK'],
27,
command_tuple[0], command_tuple[1], command_tuple[2],
change_x, change_y, change_z, change_angle)
self.safe_send(packet)
def send_turn_command(self, command_tuple, degrees):
"""
Build the packet for turning and send it
:param command_tuple: command tuple from the parser
:param degrees: how many degrees to turn
:return: True if the command was sent and False otherwise
"""
self.sequence_counter['SEND_WITH_ACK'] = (self.sequence_counter['SEND_WITH_ACK'] + 1) % 256
packet = struct.pack("<BBBIBBHh",
self.data_types_by_name['DATA_WITH_ACK'],
self.buffer_ids['SEND_WITH_ACK'],
self.sequence_counter['SEND_WITH_ACK'],
13,
command_tuple[0], command_tuple[1], command_tuple[2],
degrees)
return self.send_command_packet_ack(packet, self.sequence_counter['SEND_WITH_ACK'])
def send_camera_move_command(self, command_tuple, pan, tilt):
"""
Send the packet to move the camera (this is Bebop only).
:param command_tuple: command tuple per the parser
:param pan:
:param tilt:
"""
self.sequence_counter['SEND_WITH_ACK'] = (self.sequence_counter['SEND_WITH_ACK'] + 1) % 256
packet = struct.pack("<BBBIBBHff",
self.data_types_by_name['DATA_WITH_ACK'],
self.buffer_ids['SEND_WITH_ACK'],
self.sequence_counter['SEND_WITH_ACK'],
19,
command_tuple[0], command_tuple[1], command_tuple[2],
pan, tilt)
self.safe_send(packet)
def send_enum_command_packet_ack(self, command_tuple, enum_value, usb_id=None):
"""
Send a command on the ack channel with enum parameters as well (most likely a flip).
All commandsandsensors except PCMD go on the ack channel per
http://forum.developer.parrot.com/t/ble-characteristics-of-minidrones/5912/2
the id of the last command sent (for use in ack) is the send counter (which is incremented before sending)
:param command_tuple: 3 tuple of the command bytes. 0 padded for 4th byte
:param enum_value: the enum index
:return: nothing
"""
self.sequence_counter['SEND_WITH_ACK'] = (self.sequence_counter['SEND_WITH_ACK'] + 1) % 256
if (usb_id is None):
packet = struct.pack("<BBBIBBHI", self.data_types_by_name['DATA_WITH_ACK'],
self.buffer_ids['SEND_WITH_ACK'],
self.sequence_counter['SEND_WITH_ACK'], 15,
command_tuple[0], command_tuple[1], command_tuple[2],
enum_value)
else:
packet = struct.pack("<BBBIBBHBI", self.data_types_by_name['DATA_WITH_ACK'],
self.buffer_ids['SEND_WITH_ACK'],
self.sequence_counter['SEND_WITH_ACK'], 16,
command_tuple[0], command_tuple[1], command_tuple[2],
usb_id, enum_value)
return self.send_command_packet_ack(packet, self.sequence_counter['SEND_WITH_ACK'])
def smart_sleep(self, timeout):
"""
Sleeps the requested number of seconds but wakes up for notifications
Note: time.sleep misbehaves for the BLE connections but seems ok for wifi.
I encourage you to use smart_sleep since it handles the sleeping in a thread-safe way.
:param timeout: number of seconds to sleep
:return:
"""
start_time = datetime.now()
new_time = datetime.now()
diff = (new_time - start_time).seconds + ((new_time - start_time).microseconds / 1000000.0)
while (diff < timeout):
time.sleep(0.1)
new_time = datetime.now()
diff = (new_time - start_time).seconds + ((new_time - start_time).microseconds / 1000000.0)
def ack_packet(self, buffer_id, packet_id):
"""
Ack the packet id specified by the argument on the ACK_COMMAND channel
:param packet_id: the packet id to ack
:return: nothing
"""
#color_print("ack: buffer id of %d and packet id of %d" % (buffer_id, packet_id))
new_buf_id = (buffer_id + 128) % 256
if (new_buf_id not in self.sequence_counter):
self.sequence_counter[new_buf_id] = 0
else:
self.sequence_counter[new_buf_id] = (self.sequence_counter[new_buf_id] + 1) % 256
packet = struct.pack("<BBBIB", self.data_types_by_name['ACK'], new_buf_id,
self.sequence_counter[new_buf_id], 8,
packet_id)
self.safe_send(packet)

View File

@ -0,0 +1,49 @@
"""
Find the BLE address for a mambo. To run this,
sudo python findMambo.py
Note that the sudo is necessary for BLE permissions on linux. It is only needed on
this program and nothing else.
Author: Amy McGovern
"""
try:
from bluepy.btle import Scanner, DefaultDelegate
BLEAvailable = True
except:
BLEAvailable = False
class ScanDelegate(DefaultDelegate):
def __init__(self):
DefaultDelegate.__init__(self)
def handleDiscovery(self, dev, isNewDev, isNewData):
if isNewDev:
print("Discovered device", dev.addr)
elif isNewData:
print("Received new data from", dev.addr)
def main():
scanner = Scanner().withDelegate(ScanDelegate())
devices = scanner.scan(10.0)
for dev in devices:
#print "Device %s (%s), RSSI=%d dB" % (dev.addr, dev.addrType, dev.rssi)
for (adtype, desc, value) in dev.getScanData():
#print " %s = %s" % (desc, value)
if (desc == "Complete Local Name"):
if ("Mambo" in value):
print("FOUND A MAMBO!")
print("Device %s (%s), RSSI=%d dB" % (dev.addr, dev.addrType, dev.rssi))
print(" %s = %s" % (desc, value))
elif ("Swing" in value):
print("FOUND A SWING!")
print("Device %s (%s), RSSI=%d dB" % (dev.addr, dev.addrType, dev.rssi))
print(" %s = %s" % (desc, value))
if __name__ == "__main__":
main()

View File

@ -0,0 +1,58 @@
"""
A non-blocking stream reader (used to solve the process communciation with ffmpeg)
This code is almost directly from:
http://eyalarubas.com/python-subproc-nonblock.html
Amy McGovern (dramymcgovern@gmail.com) modified to allow the thread to end nicely
and also to not throw an error if the stream ends, since our code already will know that
from parsing (and the programs are not expected to run forever)
"""
from threading import Thread
from queue import Queue, Empty
import time
class NonBlockingStreamReader:
def __init__(self, stream):
'''
stream: the stream to read from.
Usually a process' stdout or stderr.
'''
self._s = stream
self._q = Queue()
self.is_running = True
self._t = Thread(target = self._populateQueue,
args = (self._s, self._q))
self._t.daemon = True
self._t.start() #start collecting lines from the stream
def _populateQueue(self, stream, queue):
'''
Collect lines from 'stream' and put them in 'quque'.
'''
while self.is_running:
line = stream.readline()
if line:
queue.put(line)
else:
self.finish_reader()
time.sleep(0.001)
def readline(self, timeout = None):
try:
return self._q.get(block = timeout is not None,
timeout = timeout)
except Empty:
return None
def finish_reader(self):
#print("Finishing the non-blocking reader")
self.is_running = False
class UnexpectedEndOfStream(Exception): pass

View File

@ -0,0 +1,3 @@
c=IN IP4 192.168.42.1
m=video 55004 RTP/AVP 96
a=rtpmap:96 H264/90000

View File

@ -0,0 +1,28 @@
"""
Print messages in color
"""
def color_print(print_str, type="NONE"):
# handle null cases
if (print_str is None):
print_str = ""
if (type is "ERROR"):
# red
print('\033[38;5;196m %s \033[0m' % print_str)
elif (type is "WARN"):
# orange
print('\033[38;5;202m %s \033[0m' % print_str)
elif (type is "SUCCESS"):
# green
print('\033[38;5;22m %s \033[0m' % print_str)
elif (type is "INFO"):
# blue
print('\033[38;5;33m %s \033[0m' % print_str)
elif (type is "NONE" or type is "DEFAULT"):
# black
print('\033[0m %s \033[0m' % print_str)

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,8 @@
# .readthedocs.yml
build:
image: latest
python:
version: 3.6
setup_py_install: true

View File

@ -0,0 +1,203 @@
"""
Setup for pyparrot based on the sample one found below:
A setuptools based setup module.
See:
https://packaging.python.org/en/latest/distributing.html
https://github.com/pypa/sampleproject
"""
# Always prefer setuptools over distutils
from setuptools import setup, find_packages
# To use a consistent encoding
from codecs import open
from os import path
here = path.abspath(path.dirname(__file__))
# Get the long description from the README file
with open(path.join(here, 'README.md'), encoding='utf-8') as f:
long_description = f.read()
# Arguments marked as "Required" below must be included for upload to PyPI.
# Fields marked as "Optional" may be commented out.
setup(
# This is the name of your project. The first time you publish this
# package, this name will be registered for you. It will determine how
# users can install this project, e.g.:
#
# $ pip install sampleproject
#
# And where it will live on PyPI: https://pypi.org/project/sampleproject/
#
# There are some restrictions on what makes a valid project name
# specification here:
# https://packaging.python.org/specifications/core-metadata/#name
name='pyparrot', # Required
# Versions should comply with PEP 440:
# https://www.python.org/dev/peps/pep-0440/
#
# For a discussion on single-sourcing the version across setup.py and the
# project code, see
# https://packaging.python.org/en/latest/single_source_version.html
version='1.5.19', # Required
# This is a one-line description or tagline of what your project does. This
# corresponds to the "Summary" metadata field:
# https://packaging.python.org/specifications/core-metadata/#summary
description='Python interface to control Parrot drones', # Required
# This is an optional longer description of your project that represents
# the body of text which users will see when they visit PyPI.
#
# Often, this is the same as your README, so you can just read it in from
# that file directly (as we have already done above)
#
# This field corresponds to the "Description" metadata field:
# https://packaging.python.org/specifications/core-metadata/#description-optional
long_description=long_description, # Optional
# Denotes that our long_description is in Markdown; valid values are
# text/plain, text/x-rst, and text/markdown
#
# Optional if long_description is written in reStructuredText (rst) but
# required for plain-text or Markdown; if unspecified, "applications should
# attempt to render [the long_description] as text/x-rst; charset=UTF-8 and
# fall back to text/plain if it is not valid rst" (see link below)
#
# This field corresponds to the "Description-Content-Type" metadata field:
# https://packaging.python.org/specifications/core-metadata/#description-content-type-optional
long_description_content_type='text/markdown; charset=UTF-8; variant=GFM', # Optional (see note above)
# This should be a valid link to your project's main homepage.
#
# This field corresponds to the "Home-Page" metadata field:
# https://packaging.python.org/specifications/core-metadata/#home-page-optional
url='https://github.com/amymcgovern/pyparrot', # Optional
# This should be your name or the name of the organization which owns the
# project.
author='Amy McGovern', # Optional
# This should be a valid email address corresponding to the author listed
# above.
author_email='dramymcgovern@gmail.com', # Optional
# Classifiers help users find your project by categorizing it.
#
# For a list of valid classifiers, see https://pypi.org/classifiers/
classifiers=[ # Optional
# How mature is this project? Common values are
# 3 - Alpha
# 4 - Beta
# 5 - Production/Stable
'Development Status :: 4 - Beta',
# Indicate who your project is intended for
'Intended Audience :: Developers ',
'Intended Audience :: Education',
'Topic :: Education ',
'Topic :: Software Development',
# Pick your license as you wish
'License :: OSI Approved :: MIT License',
# Specify the Python versions you support here. In particular, ensure
# that you indicate whether you support Python 2, Python 3 or both.
'Programming Language :: Python :: 3',
'Programming Language :: Python :: 3.4',
'Programming Language :: Python :: 3.5',
'Programming Language :: Python :: 3.6',
],
# This field adds keywords for your project which will appear on the
# project page. What does your project relate to?
#
# Note that this is a string of words separated by whitespace, not a list.
keywords='python parrot drone education programming', # Optional
# You can just specify package directories manually here if your project is
# simple. Or you can use find_packages().
#
# Alternatively, if you just want to distribute a single Python file, use
# the `py_modules` argument instead as follows, which will expect a file
# called `my_module.py` to exist:
#
# py_modules=["my_module"],
#
packages=find_packages(exclude=['contrib', 'docs', 'tests']), # Required
include_package_data=True,
# This field lists other packages that your project depends on to run.
# Any package you put here will be installed by pip when your project is
# installed, so they must be valid existing projects.
#
# For an analysis of "install_requires" vs pip's requirements files see:
# https://packaging.python.org/en/latest/requirements.html
install_requires=['untangle'], # Optional
# this only runs on python 3
python_requires='>=3',
# List additional groups of dependencies here (e.g. development
# dependencies). Users will be able to install these using the "extras"
# syntax, for example:
#
# $ pip install sampleproject[dev]
#
# Similar to `install_requires` above, these must be valid existing
# projects.
#extras_require={ # Optional
# 'dev': ['check-manifest'],
# 'test': ['coverage'],
#},
# If there are data files included in your packages that need to be
# installed, specify them here.
#
# If using Python 2.6 or earlier, then these have to be included in
# MANIFEST.in as well.
#package_data={ # Optional
# 'sample': ['package_data.dat'],
#},
# Although 'package_data' is the preferred approach, in some case you may
# need to place data files outside of your packages. See:
# http://docs.python.org/3.4/distutils/setupscript.html#installing-additional-files
#
# In this case, 'data_file' will be installed into '<sys.prefix>/my_data'
# data_files=[('my_data', ['data/data_file'])], # Optional
# To provide executable scripts, use entry points in preference to the
# "scripts" keyword. Entry points provide cross-platform support and allow
# `pip` to create the appropriate form of executable for the target
# platform.
#
# For example, the following would provide a command called `sample` which
# executes the function `main` from this package when invoked:
entry_points={ # Optional
'console_scripts': [
'find_mambo=pyparrot.scripts.findMambo:main',
],
},
# List additional URLs that are relevant to your project as a dict.
#
# This field corresponds to the "Project-URL" metadata fields:
# https://packaging.python.org/specifications/core-metadata/#project-url-multiple-use
#
# Examples listed include a pattern for specifying where the package tracks
# issues, where the source is hosted, where to say thanks to the package
# maintainers, and where to support the project financially. The key is
# what's used to render the link text on PyPI.
project_urls={ # Optional
'Bug Reports': 'https://github.com/amymcgovern/pyparrot/issues',
'Funding': 'https://www.oufoundation.org/portal',
'Say Thanks!': 'https://saythanks.io/to/amymcgovern',
'Source': 'https://github.com/amymcgovern/pyparrot/',
},
)