diff --git a/README.md b/README.md index 3d766027c..4226ec68f 100644 --- a/README.md +++ b/README.md @@ -24,7 +24,7 @@ Once you have built your car you can use it like this. 3. Go to `:8887` on your phone or computer to start driving your car. - Use the [demos](demos) to see how to record driving data, train autopilots and more. + Use the [scripts](scripts) for more tools to manipulate datasets and train autopilots. diff --git a/demos/drive_sim.py b/demos/drive_sim.py deleted file mode 100644 index 642224c42..000000000 --- a/demos/drive_sim.py +++ /dev/null @@ -1,34 +0,0 @@ -""" -Run a fake car on the same machine as your server. Fake images are -created for the camera. - -""" - - -import os - -import donkey as dk - - -#X, Y = dk.datasets.moving_square(n_frames=1000) - -sh = dk.sessions.SessionHandler('/home/wroscoe/donkey_data/sessions') -s = sh.load('test') -X, Y = s.load_dataset() - - -camera_sim = dk.sensors.ImgArrayCamera(X) #For testing - -no_steering = dk.actuators.BaseSteeringActuator() -no_throttle = dk.actuators.BaseThrottleActuator() - -remote_pilot = dk.remotes.RemoteClient('http://localhost:8887', vehicle_id='mycar') - - -car = dk.vehicles.BaseVehicle(camera=camera_sim, - steering_actuator=no_steering, - throttle_actuator=no_throttle, - pilot=remote_pilot) - -#start the drive loop -car.start() diff --git a/demos/serve_no_pilot.py b/demos/serve_no_pilot.py deleted file mode 100644 index 16f6c220f..000000000 --- a/demos/serve_no_pilot.py +++ /dev/null @@ -1,19 +0,0 @@ -""" -Script to start server to drive your car. -""" - -import donkey as dk - - -#setup how server will save files and which pilot to use -pilot = dk.pilots.BasePilot() - -sessions_path = '~/donkey_data/sessions' -sh = dk.sessions.SessionHandler(sessions_path=sessions_path) -session = sh.new() - -#start server -w = dk.remotes.RemoteServer(session, pilot, port=8886) -w.start() - -#in a browser go to localhost:8887 to drive your car diff --git a/demos/serve_pilot.py b/demos/serve_pilot.py deleted file mode 100644 index 4e8b2c7d3..000000000 --- a/demos/serve_pilot.py +++ /dev/null @@ -1,23 +0,0 @@ -""" -Script to start server to drive your car. -""" - -import donkey as dk - -import keras - -#Load a trained keras model and use it in the KerasAngle pilot -#model_file = '/home/wroscoe/code/donkey/whiteline_model.hdf5' -model_file = '/home/ubuntu/will_car/ac_all-cnn3_full1-valloss623.82' -model = keras.models.load_model(model_file) -pilot = dk.pilots.KerasAngle(model=model, throttle=20) - -#specify where sessions data should be saved -sh = dk.sessions.SessionHandler(sessions_path='~/donkey_data/sessions') -session = sh.new() - -#start server -w = dk.remotes.RemoteServer(session, pilot, port=8886) -w.start() - -#in a browser go to localhost:8887 to drive your car diff --git a/demos/train_download.py b/demos/train_download.py deleted file mode 100644 index 9ee0cbadb..000000000 --- a/demos/train_download.py +++ /dev/null @@ -1,18 +0,0 @@ -''' -Example how to download a pickled dataset from a url. -''' -import donkey as dk - - -print('Downloading file, this could take some time.) -url = 'https://s3.amazonaws.com/donkey_resources/port.pkl' -X, Y = dk.datasets.load_url(url) - -print('Loading Model.') -model = dk.models.cnn3_full1() - -print('Fitting Model.') -model.fit(X,Y, nb_epoch=10, validation_split=0.2) - - -model.save('test_model') \ No newline at end of file diff --git a/demos/train_generator.py b/demos/train_generator.py deleted file mode 100644 index a781405b8..000000000 --- a/demos/train_generator.py +++ /dev/null @@ -1,35 +0,0 @@ -""" -For large sessions that won't fit in memory you'll need to use a generator. - -This example shows how to use a generator and only save the model that has -the lowest validation loss. -""" - -import donkey as dk -from keras.callbacks import ModelCheckpoint - -#Read in pictures and velocities and create a predictor -sh = dk.sessions.SessionHandler(sessions_path='~/donkey_data/sessions/') -s = sh.load('test') - - -#split training and test data. -all_imgs = s.img_paths() -train_imgs, test_imgs = dk.utils.split_list(all_imgs, test_frac=.8, sequential=True) - -train_gen = s.load_generator(add_dim=True, img_paths=train_imgs) -test_gen = s.load_generator(add_dim=True, img_paths=test_imgs) - - -# Use a checkpoint to save best model after each epoch -filepath="best_model.hdf5" -checkpoint = ModelCheckpoint(filepath, monitor='val_loss', verbose=1, - save_best_only=True, mode='min') -callbacks_list = [checkpoint] - -#use 3 layer convolution netowrk with one fully connected -model = dk.models.cnn3_full1() - -#fit model with generator -model.fit_generator(train_gen, samples_per_epoch=70, nb_epoch=8, - validation_data=test_gen, nb_val_samples=100, callbacks=callbacks_list) \ No newline at end of file diff --git a/docs/01-build_a_car.md b/docs/01-build_a_car.md index 5d88470d0..20c137061 100644 --- a/docs/01-build_a_car.md +++ b/docs/01-build_a_car.md @@ -1,101 +1,3 @@ -# Get Started -This doc will walk you through how to setup your donkey. - - -## Bill of Materials. -#### Required -* Raspberry Pi 3 B ($35) -* Raspberry Pi Camera ($15) -* Micro USB power adapter. ($9) -* USB Battery Pack ($15) -* USB Keyboard -* USB Mouse -* Monitor -* HDMI cable (to connect monitor to PI) ($7) -* Micro SD Card (campatible with Raspberry Pi) ($8) -* Servo Sheild ($15) -* RC CAR (($120-300)) - -#### Optional -* Xbox 360 Controller -* Xbox USB Adapter - - - -## Setup -These instructions are based on [Geoff Boeing's post on setting up scientific python on a Raspberry Pi](http://geoffboeing.com/2016/03/scientific-python-raspberry-pi/). - -#### Boot your Raspberry Pi -These instructions assume you're using Ubuntu operationg system. If you don't have Ubuntu, try using the NOOB method. - -1. Download recent Disk image. I use Jessie. -2. Extract disk image from zip file. -3. Open Ubuntu's "Startup Disk Creator" application. -4. Insert micro usb disk via a usb adapter. This disk should show up in the Startup Disk Creator app. -5. Select your RPi .img file and click create disk. -6. Once the img has been created, take the SD card from your computer and put it in your RPi. -7. Connect your Monitor with your HDMI cable, your mouse and keyboard and then finally power up the RPi by plugging in the Micro USB power adaptor. - - -#### Install Basic Libraries -Since the RPi is not as powerful as a laptop, it can take a long time to install python packages (ie. numpy & PIL) using pip. Luckly Adafruit has precompiled these libraries into packages that can be installed via `apt-get`. - -1. Open a terminal (Ctrl-Alt-t) and upgrade your system packages. - - ``` - sudo apt-get update - sudo apt-get upgrade - ``` -2. Save These initial conditions. - - ``` - dpkg -l > ~/Desktop/packages.list - pip freeze > ~/Desktop/pip-freeze-initial.list - ``` - -3. Install the necessary libraries - - ``` - sudo apt-get install xsel xclip libxml2-dev libxslt-dev libzmq-dev libspatialindex-dev virtualenv - ``` -4. Pandas & Jupyter Requirements - ``` - sudo apt-get install python3-lxml python3-h5py python3-numexpr python3-dateutil python3-tz python3-bs4 python3-xlrd python3-tables python3-sqlalchemy python3-xlsxwriter python3-httplib2 python3-zmq - ``` -5. Scientific Python - ``` - sudo apt-get install python3-numpy python3-matplotlib python3-scipy python3-pandas - ``` - -#### Install your Camera -Follow the instructions [here](https://www.raspberrypi.org/learning/getting-started-with-picamera/worksheet/). - - -1. Connect your camera to the RPi. -2. Enable your camera in the Menu > Preferences > Raspberry Pi Config -3. Restart your Pi. `sudo reboot` - - -#### Connect your servo sheild. - -1. Assemble and test your servo shield with the instructions given by Adafruit. - - -#### Install Donkey - - -clone repo & create virtual env - -``` -mkdir code -cd code -git clone http://github.com/wroscoe/donkey.git - -mkdir car -cd car -virtualenv --system-site-packages -p python3 env -source env/bin/activate -pip install -e ../donkey[pi] -``` - +# Build a donkey vehicle. +Anyone can build their own robocar that runs Donkey. Once you have the parts it will take ~4hrs to start driving. See the [detailed instructions](https://docs.google.com/document/d/11IPqZcDcLTd2mtYaR5ONpDxFgL9Y1nMNTDvEarST8Wk/edit). \ No newline at end of file diff --git a/docs/02-start_driving.md b/docs/02-start_driving.md index 6957a7b93..cf379a787 100644 --- a/docs/02-start_driving.md +++ b/docs/02-start_driving.md @@ -16,4 +16,16 @@ Now that you have built your car, you'll want to drive it. sudo nmap -sP 192.168.1.0/24 | awk '/^Nmap/{ip=$NF}/B8:27:EB/{print ip}' ``` 3. Connect to your pi by running `ssh pi@` -4. Run the `drive_pi.py` demo script +4. Activate your python virtual environment + ``` + cd donkey + source env/bin/activate + ``` +5. Start your drive script. + ``` + python demos/drive_pi.py + ``` ` + + +#### Control your car +You can now control your car with the virtual joystic on your computer or your phone. diff --git a/docs/99-Contribute.md b/docs/99-Contribute.md index e8e7bab00..8871198ac 100644 --- a/docs/99-Contribute.md +++ b/docs/99-Contribute.md @@ -7,6 +7,18 @@ This is an opensource project to help accelerate the developement of self drivin 3. Fork the code, make your change and submit a pull request. +###Guiding Developement Principles +* **Modularity**: A self driving system is composed of standalone, independently configurable modules that can be connected modules. + +* **Minimalism**: Each component should be kept short (<100 lines of code). Each peice of code should be transparent apon first reading. No black magic, it slows the speed of innovation. + +* **Extensiblity**: New components should be simple to create by following a template. + +* **Python**: Keep it simple. + +***These guidelines are nearly copied from Keras because they are so good*** + + ## Tests Make sure all tests pass before submitting your pull request. diff --git a/docs/datasets.md b/docs/datasets.md new file mode 100644 index 000000000..8da73f5be --- /dev/null +++ b/docs/datasets.md @@ -0,0 +1,24 @@ +# Datasets + +Donkey has several builtin datasets to help users test their autopilots and confirm that they can learn from image sequences. + +## Moving Square +A single color moving square bounces around the screen. + +Outputs: +* X - 120x160px image of moving square on black background. +* Y - x and y cordinates of center of square in the image. (use options to only return x or y) + + + +## Driving Datasets + +### Line Following + + +### Lane Keeping + + +### Sidewalk + +### \ No newline at end of file diff --git a/docs/Mechanical_Hardware_Instructions.md b/docs/hardware/README.md similarity index 100% rename from docs/Mechanical_Hardware_Instructions.md rename to docs/hardware/README.md diff --git a/hardware/Adjustable Camera Holder.stl b/docs/hardware/camera_holder.stl similarity index 100% rename from hardware/Adjustable Camera Holder.stl rename to docs/hardware/camera_holder.stl diff --git a/Hardware/Car Top Plate - Helion Conquest.dwg b/docs/hardware/hellion_conquest-base_plates.dwg similarity index 100% rename from Hardware/Car Top Plate - Helion Conquest.dwg rename to docs/hardware/hellion_conquest-base_plates.dwg diff --git a/hardware/Roll Cage 2nd Version.stl b/docs/hardware/hellion_conquest-roll_bars.stl similarity index 100% rename from hardware/Roll Cage 2nd Version.stl rename to docs/hardware/hellion_conquest-roll_bars.stl diff --git a/docs/hardware/hellion_conquest-top_plate.dwg b/docs/hardware/hellion_conquest-top_plate.dwg new file mode 100644 index 000000000..740399db7 Binary files /dev/null and b/docs/hardware/hellion_conquest-top_plate.dwg differ diff --git a/Hardware/Car Top Plate - Trooper.dxf b/docs/hardware/trooper-top_plate.dxf similarity index 100% rename from Hardware/Car Top Plate - Trooper.dxf rename to docs/hardware/trooper-top_plate.dxf diff --git a/donkey/__init__.py b/donkey/__init__.py index 695b2159a..c6b811d5e 100644 --- a/donkey/__init__.py +++ b/donkey/__init__.py @@ -1,17 +1,18 @@ import os uname = os.uname() -if uname[1] != 'raspberrypi': +if not uname[4].startswith("arm"): from . import (utils, models, datasets, remotes, sensors, actuators, + mixers, vehicles, pilots, templates,) else: print('Detected running on rasberrypi. Only importing select modules.') - from . import actuators, remotes, sensors, vehicles + from . import actuators, mixers, remotes, sensors, vehicles diff --git a/donkey/actuators.py b/donkey/actuators.py index 1810ebe3a..ed861024f 100644 --- a/donkey/actuators.py +++ b/donkey/actuators.py @@ -7,8 +7,6 @@ # Import the PCA9685 module. - - # Uncomment to enable debug output. #import logging #logging.basicConfig(level=logging.DEBUG) @@ -23,44 +21,34 @@ def map_range(x, X_min, X_max, Y_min, Y_max): return int(y) +class Dummy_Controller: -class BaseSteeringActuator(): - ''' Placeholder until real logic is implemented ''' - - def update(self, angle): - print('BaseSteeringActuator.update: angle=%s' %angle) - -class BaseThrottleActuator(): - ''' Placeholder until real logic is implemented ''' - - def update(self, throttle): - print('BaseThrottleActuator.update: throttle=%s' %throttle) - - -class Adafruit_PCA9685_Actuator(): + def __init__(self, channel, frequency): + pass +class PCA9685_Controller: + # Init with 60hz frequency by default, good for servos. def __init__(self, channel, frequency=60): import Adafruit_PCA9685 # Initialise the PCA9685 using the default address (0x40). self.pwm = Adafruit_PCA9685.PCA9685() - # Set frequency to 60hz, good for servos. self.pwm.set_pwm_freq(frequency) self.channel = channel - -class PWMSteeringActuator(Adafruit_PCA9685_Actuator): - + def set_pulse(self, pulse): + self.pwm.set_pwm(self.channel, 0, pulse) + +class PWMSteeringActuator: #max angle wheels can turn LEFT_ANGLE = -45 RIGHT_ANGLE = 45 - def __init__(self, channel=1, - frequency=60, + def __init__(self, controller=None, left_pulse=290, right_pulse=490): - super().__init__(channel, frequency) + self.controller = controller self.left_pulse = left_pulse self.right_pulse = right_pulse @@ -70,22 +58,21 @@ def update(self, angle): self.LEFT_ANGLE, self.RIGHT_ANGLE, self.left_pulse, self.right_pulse) - self.pwm.set_pwm(self.channel, 0, pulse) - + self.controller.set_pulse(pulse) -class PWMThrottleActuator(Adafruit_PCA9685_Actuator): +class PWMThrottleActuator: MIN_THROTTLE = -100 MAX_THROTTLE = 100 - def __init__(self, channel=0, - frequency=60, + def __init__(self, controller=None, max_pulse=300, min_pulse=490, zero_pulse=350): - super().__init__(channel, frequency) + #super().__init__(channel, frequency) + self.controller = controller self.max_pulse = max_pulse self.min_pulse = min_pulse self.zero_pulse = zero_pulse @@ -95,7 +82,7 @@ def __init__(self, channel=0, def calibrate(self): #Calibrate ESC (TODO: THIS DOES NOT WORK YET) print('center: %s' % self.zero_pulse) - self.pwm.set_pwm(self.channel, 0, self.zero_pulse) #Set Max Throttle + self.controller.set_pulse(self.zero_pulse) #Set Max Throttle time.sleep(1) @@ -112,19 +99,5 @@ def update(self, throttle): print('pulse: %s' % pulse) sys.stdout.flush() - self.pwm.set_pwm(self.channel, 0, pulse) + self.controller.set_pulse(pulse) return '123' - - - - - - - - - - - - - - diff --git a/donkey/mixers.py b/donkey/mixers.py new file mode 100644 index 000000000..63aca0ee6 --- /dev/null +++ b/donkey/mixers.py @@ -0,0 +1,57 @@ +import time +import sys +from donkey import actuators + +class BaseMixer(): + + def update_angle(self, angle): + print('BaseSteeringActuator.update: angle=%s' %angle) + + def update_throttle(self, throttle): + print('BaseThrottleActuator.update: throttle=%s' %throttle) + + def update(self, angle=0, throttle=0): + '''Convenience function to update + angle and throttle at the same time''' + self.update_angle(angle) + self.update_throttle(throttle) + + +class FrontSteeringMixer(BaseMixer): + + def __init__(self, + steering_actuator=None, + throttle_actuator=None): + self.steering_actuator = steering_actuator + self.throttle_actuator = throttle_actuator + + def update_angle(self, angle): + self.steering_actuator.update(angle) + + def update_throttle(self, throttle): + self.throttle_actuator.update(throttle) + + +class DifferentialSteeringMixer(BaseMixer): + + def __init__(self, + left_actuator=None, + right_actuator=None, + angle_throttle_multiplier = 1.0): + self.left_actuator = left_actuator + self.right_actuator = right_actuator + self.angle = 0 + self.throttle = 0 + self.angle_throttle_multiplier = angle_throttle_multiplier + + def update_angle(self, angle): + self.angle = angle + self.update_actuators() + + def update_throttle(self, throttle): + self.throttle = throttle + self.update_actuators() + + def update_actuators(self): + self.left_actuator.update(self.throttle - self.angle * angle_throttle_multiplier) + self.right_actuator.update(self.throttle + self.angle * angle_throttle_multiplier) diff --git a/donkey/models.py b/donkey/models.py index 6252329e6..25fbfb9cc 100644 --- a/donkey/models.py +++ b/donkey/models.py @@ -6,7 +6,7 @@ """ -from keras.layers import Input, LSTM, Dense, merge +from keras.layers import Input, Dense, merge from keras.models import Model from keras.models import Sequential from keras.layers import Convolution2D, MaxPooling2D, SimpleRNN, Reshape, BatchNormalization @@ -78,59 +78,6 @@ def cnn3_full1_rnn1(): return model -def cnn1_full1(): - - img_in = Input(shape=(120, 160, 3), name='img_in') - angle_in = Input(shape=(1,), name='angle_in') - - x = Convolution2D(1, 3, 3)(img_in) - x = Activation('relu')(x) - x = MaxPooling2D(pool_size=(2, 2))(x) - - merged = Flatten()(x) - - x = Dense(32)(merged) - x = Activation('linear')(x) - x = Dropout(.05)(x) - - angle_out = Dense(1, name='angle_out')(x) - - model = Model(input=[img_in], output=[angle_out]) - model.compile(optimizer='adam', loss='mean_squared_error') - return model - - -def norm_cnn3_full1(): - - img_in = Input(shape=(120, 160, 3), name='img_in') - angle_in = Input(shape=(1,), name='angle_in') - - x = BatchNormalization()(img_in) - x = Convolution2D(8, 3, 3)(x) - x = Activation('relu')(x) - x = MaxPooling2D(pool_size=(2, 2))(x) - - x = Convolution2D(16, 3, 3)(x) - x = Activation('relu')(x) - x = MaxPooling2D(pool_size=(2, 2))(x) - - x = Convolution2D(32, 3, 3)(x) - x = Activation('relu')(x) - x = MaxPooling2D(pool_size=(2, 2))(x) - - merged = Flatten()(x) - - x = Dense(256)(merged) - x = Activation('linear')(x) - x = Dropout(.2)(x) - - angle_out = Dense(1, name='angle_out')(x) - - model = Model(input=[img_in], output=[angle_out]) - model.compile(optimizer='adam', loss='mean_squared_error') - return model - - def vision_2D(dropout_frac=.2): ''' Network with 4 convolutions, 2 residual shortcuts to predict angle. diff --git a/donkey/pilots.py b/donkey/pilots.py index 5657c3db7..15ee6678a 100644 --- a/donkey/pilots.py +++ b/donkey/pilots.py @@ -7,9 +7,14 @@ ''' import os -import numpy as np - +import math import random +from operator import itemgetter +from datetime import datetime + +import numpy as np +import cv2 +import keras from donkey import utils @@ -18,7 +23,10 @@ class BasePilot(): Base class to define common functions. When creating a class, only override the funtions you'd like to replace. ''' - + def __init__(self, name=None, last_modified=None): + self.name = name + self.last_modified = last_modified + def decide(self, img_arr): angle = 0 speed = 0 @@ -28,13 +36,19 @@ def decide(self, img_arr): return angle, speed + def load(self): + return self + + + class SwervePilot(BasePilot): ''' Example predictor that should not be used. ''' - def __init__(self): + def __init__(self, **kwargs): self.angle= random.randrange(-45, 46) self.throttle = 20 + super().__init__(**kwargs) def decide(self, img_arr): @@ -45,11 +59,16 @@ def decide(self, img_arr): return self, angle, self.throttle -class KerasAngle(): - def __init__(self, model, throttle): - self.model = model + + +class KerasAngle(BasePilot): + def __init__(self, model_path, throttle=25, **kwargs): + self.model_path = model_path + self.model = None #load() loads the model self.throttle = throttle self.last_angle = 0 + super().__init__(**kwargs) + def decide(self, img_arr): img_arr = img_arr.reshape((1,) + img_arr.shape) @@ -63,3 +82,169 @@ def decide(self, img_arr): return angle, self.throttle + def load(self): + + self.model = keras.models.load_model(self.model_path) + return self + + + + + +class OpenCVLineDetector(BasePilot): + + def __init__(self, M=None, blur_pixels=5, canny_threshold1=100, canny_threshold2=130, + rho=2, theta=.02, min_line_length=80, max_gap=20, hough_threshold=9, + throttle=30, **kwargs): + + + self.blur_pixels = blur_pixels + self.canny_threshold1 = canny_threshold1 + self.canny_threshold2 = canny_threshold2 + self.hough_threshold = hough_threshold + self.min_line_length = min_line_length + self.max_gap = max_gap + self.rho = rho + self.theta = theta + if M is not None: + self.M = M + else: + self.M = self.get_M() + + self.throttle = throttle + + super().__init__(**kwargs) + + + def decide(self, img_arr): + lines = self.get_lines(img_arr, + self.M, + self.blur_pixels, + self.canny_threshold1, + self.canny_threshold2, + self.hough_threshold, + self.min_line_length, + self.max_gap, + self.rho, + self.theta, + ) + #print(lines) + if lines is not None: + line_data = self.compute_lines(lines) + clustered = self.cluster_angles(line_data) + #print('clustered: ', clustered) + angle = self.decide_angle(clustered), self.throttle + else: + angle = 0 + return angle, self.throttle + + + + def get_M(self): + M = np.array([[ 2.43902439e+00, 6.30081301e+00, -6.15853659e+01], + [ -4.30211422e-15, 1.61246610e+01, -6.61644977e+01], + [ -1.45283091e-17, 4.06504065e-02, 1.00000000e+00]]) + return M + + @staticmethod + def get_lines(img, M, blur_pixels, canny_threshold1, canny_threshold2, + hough_threshold, min_line_length, max_gap, rho, theta ): + + img_gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY) + img_blur = cv2.blur(img_gray,(blur_pixels,blur_pixels)) + img_canny = cv2.Canny(img_blur, canny_threshold1, canny_threshold2) + lines = cv2.HoughLinesP(img_canny, rho, theta, hough_threshold, min_line_length, max_gap) + + if lines is not None: + lines = lines.reshape((lines.shape[0],2,2)) + lines = lines.astype(float) + lines = cv2.perspectiveTransform(lines, M) + return lines + + + @classmethod + def line_length(cls, arr): + l = math.sqrt( (arr[0,0] - arr[1,0])**2 + (arr[0,1] - arr[1,1])**2 ) + return l + + + @classmethod + def line_angle(cls, arr): + dx = arr[1,0] - arr[0,0] + dy = arr[1,1] - arr[0,1] + rads = math.atan2(-dy,dx) + rads %= 2*math.pi + degs = -math.degrees(rads) + if degs <= -180: + degs = degs + 180 + + degs = degs + 90 + return degs + + + @classmethod + def compute_lines(cls, lines): + + line_data = [] + for line in lines: + line_data.append([cls.line_angle(line), cls.line_length(line)]) + + sorted(line_data, key=itemgetter(0)) + return line_data + + @staticmethod + def cluster_angles(line_data): + clusters = [] + last_angle = -180 + for a, l in line_data: + if abs(last_angle - a) > 20: + clusters.append([(a,l)]) + else: + clusters[-1].append((a,l)) + return clusters + + + @classmethod + def decide_angle(cls, clustered_angles): + max_length = 0 + max_cluster_id = -1 + for i, c in enumerate(clustered_angles): + #sum lenght of lines found in clusters, filter out angles > 80 (likely in horizon) + cluster_length = sum([l for a, l in c if abs(a) < 80]) + #print('cluster length', cluster_length) + if cluster_length > max_length: + max_length = cluster_length + max_cluster_id = i + + if max_cluster_id>-1: + angles = [a for a, l in clustered_angles[max_cluster_id]] + #return average angle of cluster + return sum(angles)/len(angles) + #print(angles) + else: + return 0 + + +class PilotHandler(): + """ Convinience class to load default pilots """ + def __init__(self, models_path): + + self.models_path = os.path.expanduser(models_path) + + + def pilots_from_models(self): + """ Load pilots from keras models saved in the models directory. """ + models_list = [f for f in os.scandir(self.models_path)] + pilot_list = [] + for d in models_list: + last_modified = datetime.fromtimestamp(d.stat().st_mtime) + pilot = KerasAngle(d.path, throttle=25, name=d.name, + last_modified=last_modified) + pilot_list.append(pilot) + return pilot_list + + def default_pilots(self): + """ Load pilots from models and add CV pilots """ + pilot_list = self.pilots_from_models() + pilot_list.append(OpenCVLineDetector(name='OpenCV')) + return pilot_list \ No newline at end of file diff --git a/donkey/remotes.py b/donkey/remotes.py index e91461104..c25b5828d 100644 --- a/donkey/remotes.py +++ b/donkey/remotes.py @@ -1,5 +1,6 @@ """ -Classes used to communicate between vehicle and server. +Classes needed to run a webserver so that the donkey can +be controlled remotely by the user or an auto pilot. """ import time @@ -22,18 +23,21 @@ class RemoteClient(): ''' - Class used by vehicle to send driving data and recieve predictions. + Class used by a vehicle to send driving data and + recieve predictions from a remote webserver. ''' def __init__(self, remote_url, vehicle_id='mycar'): - self.record_url = remote_url + '/' + vehicle_id + '/drive/' + self.control_url = remote_url + '/api/vehicles/control/' + vehicle_id + '/' + self.last_milliseconds = 0 def decide(self, img_arr, angle, throttle, milliseconds): ''' - Accepts: image and control attributes and saves - them to learn how to drive.''' + Posts current car sensor data to webserver and returns + angle and throttle recommendations. + ''' #load features data = { @@ -43,112 +47,205 @@ def decide(self, img_arr, angle, throttle, milliseconds): } - r = requests.post(self.record_url, - files={'img': dk.utils.arr_to_binary(img_arr), - 'json': json.dumps(data)}) #hack to put json in file + r = None + + while r == None: + #Try connecting to server until connection is made. + + try: + start = time.time() + r = requests.post(self.control_url, + files={'img': dk.utils.arr_to_binary(img_arr), + 'json': json.dumps(data)}) #hack to put json in file + end = time.time() + lag = end-start + except (requests.ConnectionError) as err: + print("Vehicle could not connect to server. Make sure you've " + + "started your server and you're referencing the right port.") + time.sleep(3) + + data = json.loads(r.text) angle = int(float(data['angle'])) throttle = int(float(data['throttle'])) - print('remote client: %s' %r.text) + + print('vehicle <> server: request lag: %s' %lag) return angle, throttle +class DonkeyPilotApplication(tornado.web.Application): -class RemoteServer(): - ''' - Class used to create server that accepts driving data, records it, - runs a predictor and returns the predictions. - ''' - - def __init__(self, session, pilot, port=8887): - - self.port = int(port) - self.session = session - self.pilot = pilot - - vehicle_data = {'user_angle': 0, - 'user_throttle': 0, - 'drive_mode':'user', - 'milliseconds': 0, - 'recording': False} - + def __init__(self, data_path='~/donkey_data/'): + ''' + Create and publish variables needed on many of + the web handlers. + ''' - self.vehicles = {'mycar':vehicle_data} + self.vehicles = {} this_dir = os.path.dirname(os.path.realpath(__file__)) self.static_file_path = os.path.join(this_dir, 'templates', 'static') - print(self.static_file_path) - - def start(self): - ''' - Start the webserver. - ''' + self.data_path = os.path.expanduser(data_path) + self.sessions_path = os.path.join(self.data_path, 'sessions') + self.models_path = os.path.join(self.data_path, 'models') + + ph = dk.pilots.PilotHandler(self.models_path) + self.pilots = ph.default_pilots() - #load features - app = tornado.web.Application([ + + handlers = [ #temporary redirect until vehicles is not a singleton - (r"/", tornado.web.RedirectHandler, - dict(url="/mycar/")), + (r"/", HomeView), - (r"/?(?P[A-Za-z0-9-]+)?/", VehicleHandler), + (r"/vehicles/", VehicleListView), - (r"/?(?P[A-Za-z0-9-]+)?/control/", - ControllerHandler, - dict(vehicles = self.vehicles) - ), - (r"/?(?P[A-Za-z0-9-]+)?/mjpeg/?(?P[^/]*)?", - CameraMJPEGHandler, - dict(vehicles = self.vehicles) + (r"/vehicles/?(?P[A-Za-z0-9-]+)?/", + VehicleView), + + + (r"/api/vehicles/?(?P[A-Za-z0-9-]+)?/", + VehicleAPI), + + + (r"/api/vehicles/drive/?(?P[A-Za-z0-9-]+)?/", + DriveAPI), + + (r"/api/vehicles/video/?(?P[A-Za-z0-9-]+)?", + VideoAPI ), - (r"/?(?P[A-Za-z0-9-]+)?/drive/", - DriveHandler, - dict(pilot=self.pilot, session=self.session, vehicles=self.vehicles) + + (r"/api/vehicles/control/?(?P[A-Za-z0-9-]+)?/", + ControlAPI), + + + (r"/sessions/", SessionListView), + + (r"/sessions/?(?P[^/]+)?/", + SessionView), + + (r"/session_image/?(?P[^/]+)?/?(?P[^/]+)?", + SessionImageView ), + + (r"/pilots/", PilotListView), + + + (r"/static/(.*)", tornado.web.StaticFileHandler, {"path": self.static_file_path}), - ], debug=True) + ] + + settings = {'debug': True} + + super().__init__(handlers, **settings) - app.listen(self.port) + def start(self, port=8887): + ''' Start the tornado webserver. ''' + print(port) + self.port = int(port) + self.listen(self.port) tornado.ioloop.IOLoop.instance().start() - return True + def get_vehicle(self, vehicle_id): + ''' Returns vehicle if it exists or creates a new one ''' + + if vehicle_id not in self.vehicles: + print('new vehicle') + sh = dk.sessions.SessionHandler(self.sessions_path) + self.vehicles[vehicle_id] = dict({ + 'id': vehicle_id, + 'user_angle': 0, + 'user_throttle': 0, + 'drive_mode':'user', + 'milliseconds': 0, + 'recording': False, + 'pilot': dk.pilots.BasePilot(), + 'session': sh.new()}) + + #eprint(self.vehicles) + return self.vehicles[vehicle_id] + + +##################### +# # +# vehicles # +# # +##################### +class HomeView(tornado.web.RequestHandler): + def get(self): + self.render("templates/home.html") -class VehicleHandler(tornado.web.RequestHandler): + +class VehicleListView(tornado.web.RequestHandler): + def get(self): + ''' + Serves a list of the vehicles posting requests to the server. + ''' + data = {'vehicles':self.application.vehicles} + + self.render("templates/vehicle_list.html", **data) + + +class VehicleView(tornado.web.RequestHandler): def get(self, vehicle_id): ''' - Serves web page used to control the vehicle. + Serves page for users to control the vehicle. ''' - self.render("templates/monitor.html") + + + V = self.application.get_vehicle(vehicle_id) + pilots = self.application.pilots + data = {'vehicle': V, 'pilots': pilots} + print(data) + self.render("templates/vehicle.html", **data) + + +class VehicleAPI(tornado.web.RequestHandler): + + + def post(self, vehicle_id): + ''' + Currently this only changes the pilot. + ''' + + V = self.application.get_vehicle(vehicle_id) + + data = tornado.escape.json_decode(self.request.body) + print(data) + pilot = next(filter(lambda p: p.name == data['pilot'], self.application.pilots)) + V['pilot'] = pilot.load() + -class ControllerHandler(tornado.web.RequestHandler): - def initialize(self, vehicles): - self.vehicles = vehicles +class DriveAPI(tornado.web.RequestHandler): def post(self, vehicle_id): ''' Receive post requests as user changes the angle and throttle of the vehicle on a the index webpage ''' + + V = self.application.get_vehicle(vehicle_id) + data = tornado.escape.json_decode(self.request.body) angle = data['angle'] throttle = data['throttle'] - V = self.vehicles[vehicle_id] + #Set recording mode if data['recording'] == 'true': @@ -174,29 +271,26 @@ def post(self, vehicle_id): -class DriveHandler(tornado.web.RequestHandler): - def initialize(self, session, pilot, vehicles): - #the parrent controller - self.pilot = pilot - self.session = session - self.vehicles = vehicles +class ControlAPI(tornado.web.RequestHandler): def post(self, vehicle_id): ''' - Receive post requests from vehicle with camera image. - Return the angle and throttle the car should be goin. + Receive post requests from a vehicle and returns + the angle and throttle the car should use. Depending on + the drive mode the values can come from the user or + an autopilot. ''' + + V = self.application.get_vehicle(vehicle_id) + img = self.request.files['img'][0]['body'] img = Image.open(io.BytesIO(img)) img_arr = dk.utils.img_to_arr(img) - #Hack to take json from a file - #data = json.loads(self.request.files['json'][0]['body'].decode("utf-8") ) - - #Get angle/throttle from pilot loaded by the server. - pilot_angle, pilot_throttle = self.pilot.decide(img_arr) - V = self.vehicles[vehicle_id] + #Get angle/throttle from pilot loaded by the server. + pilot_angle, pilot_throttle = V['pilot'].decide(img_arr) + V['img'] = img V['pilot_angle'] = pilot_angle V['pilot_throttle'] = pilot_throttle @@ -204,7 +298,7 @@ def post(self, vehicle_id): if V['recording'] == True: #save image with encoded angle/throttle values - self.session.put(img, + V['session'].put(img, angle=V['user_angle'], throttle=V['user_throttle'], milliseconds=V['milliseconds']) @@ -218,23 +312,21 @@ def post(self, vehicle_id): angle, throttle = V['pilot_angle'], V['pilot_throttle'] print('%s: A: %s T:%s' %(V['drive_mode'], angle, throttle)) + #retun angel/throttle values to vehicle with json response self.write(json.dumps({'angle': str(angle), 'throttle': str(throttle)})) -class CameraMJPEGHandler(tornado.web.RequestHandler): - def initialize(self, vehicles): - self.vehicles = vehicles - - +class VideoAPI(tornado.web.RequestHandler): + ''' + Serves a MJPEG of the images posted from the vehicle. + ''' @tornado.web.asynchronous @tornado.gen.coroutine - def get(self, vehicle_id, file): - ''' - Show a video of the pictures captured by the vehicle. - ''' + def get(self, vehicle_id): + ioloop = tornado.ioloop.IOLoop.current() self.set_header("Content-type", "multipart/x-mixed-replace;boundary=--boundarydonotcross") @@ -246,7 +338,7 @@ def get(self, vehicle_id, file): if self.served_image_timestamp + interval < time.time(): - img = self.vehicles[vehicle_id]['img'] + img = self.application.vehicles[vehicle_id]['img'] img = dk.utils.img_to_binary(img) self.write(my_boundary) @@ -258,3 +350,104 @@ def get(self, vehicle_id, file): else: yield tornado.gen.Task(ioloop.add_timeout, ioloop.time() + interval) + +##################### +# # +# pilots # +# # +##################### + + +class PilotListView(tornado.web.RequestHandler): + def get(self): + ''' + Render a list of pilots. + ''' + ph = dk.pilots.PilotHandler(self.application.models_path) + pilots = ph.default_pilots() + data = {'pilots': pilots} + self.render("templates/pilots_list.html", **data) + + + + +##################### +# # +# sessions # +# # +##################### + + + +class SessionImageView(tornado.web.RequestHandler): + def get(self, session_id, img_name): + ''' Returns jpg images from a session folder ''' + + sessions_path = self.application.sessions_path + path = os.path.join(sessions_path, session_id, img_name) + f = Image.open(path) + o = io.BytesIO() + f.save(o, format="JPEG") + s = o.getvalue() + + self.set_header('Content-type', 'image/jpg') + self.set_header('Content-length', len(s)) + + self.write(s) + + + +class SessionListView(tornado.web.RequestHandler): + + def get(self): + ''' + Serves a page showing a list of all the session folders. + TODO: Move this list creation to the session handler. + ''' + + session_dirs = [f for f in os.scandir(self.application.sessions_path) if f.is_dir() ] + data = {'session_dirs': session_dirs} + self.render("templates/session_list.html", **data) + + + +class SessionView(tornado.web.RequestHandler): + + def get(self, session_id): + ''' + Shows all the images saved in the session. + TODO: Add pagination. + ''' + from operator import itemgetter + + + sessions_path = self.application.sessions_path + path = os.path.join(sessions_path, session_id) + imgs = [dk.utils.merge_two_dicts({'name':f.name}, dk.sessions.parse_img_filepath(f.path)) for f in os.scandir(path) if f.is_file() ] + + sorted_imgs = sorted(imgs, key=itemgetter('name')) + session = {'name':session_id, 'imgs': sorted_imgs[:100]} + data = {'session': session} + self.render("templates/session.html", **data) + + def post(self, session_id): + ''' + Deletes selected images + ''' + + data = tornado.escape.json_decode(self.request.body) + + if data['action'] == 'delete_images': + sessions_path = self.application.sessions_path + path = os.path.join(sessions_path, session_id) + + for i in data['imgs']: + os.remove(os.path.join(path, i)) + print('%s removed' %i) + + + + + + + diff --git a/donkey/sessions.py b/donkey/sessions.py index 04ff15686..0c0d21c84 100644 --- a/donkey/sessions.py +++ b/donkey/sessions.py @@ -28,14 +28,9 @@ def put(self, img, angle=None, throttle=None, milliseconds=None): self.frame_count += 1 - file_name = str("%s/" % self.session_dir + - "frame_" + str(self.frame_count).zfill(5) + - "_ttl_" + str(throttle) + - "_agl_" + str(angle) + - "_mil_" + str(milliseconds) + - '.jpg') + filepath = create_img_filepath(self.session_dir, self.frame_count, angle, throttle, milliseconds) - img.save(file_name, 'jpeg') + img.save(filepath, 'jpeg') def get(self, file_path): @@ -47,19 +42,13 @@ def get(self, file_path): img_arr = np.array(img) - f = file_path.split('/')[-1] - f = f.split('.')[0] - f = f.split('_') - - throttle = int(f[3]) - angle = int(f[5]) - milliseconds = int(f[7]) - - data = {'throttle':throttle, 'angle':angle, 'milliseconds': milliseconds} + data = parse_img_filename(path) return img_arr, data + + def img_paths(self): """ Returns a list of file paths for the images in the session. @@ -246,3 +235,25 @@ def pickle_sessions(sessions_folder, session_names, file_path): with open(file_path, 'wb') as f: pkl = pickle.dump((X,Y), f) + + +def parse_img_filepath(filepath): + f = filepath.split('/')[-1] + f = f.split('.')[0] + f = f.split('_') + + throttle = int(f[3]) + angle = int(f[5]) + milliseconds = int(f[7]) + + data = {'throttle':throttle, 'angle':angle, 'milliseconds': milliseconds} + return data + +def create_img_filepath(directory, frame_count, angle, throttle, milliseconds): + filepath = str("%s/" % directory + + "frame_" + str(frame_count).zfill(5) + + "_ttl_" + str(throttle) + + "_agl_" + str(angle) + + "_mil_" + str(milliseconds) + + '.jpg') + return filepath \ No newline at end of file diff --git a/donkey/templates/base.html b/donkey/templates/base.html new file mode 100644 index 000000000..69f91675e --- /dev/null +++ b/donkey/templates/base.html @@ -0,0 +1,58 @@ + + + + + Donkey Monitor + + + + + + + + + + + + + + + + + + + + + + + {% block content %}{% end %} + + diff --git a/donkey/templates/home.html b/donkey/templates/home.html new file mode 100644 index 000000000..505bf5d43 --- /dev/null +++ b/donkey/templates/home.html @@ -0,0 +1,26 @@ + +{% extends "base.html" %} +{% block content %} +
+ +

Donkey

+ +

Your donkey is ready to ride

+ +

Using this web interface you can do the following

+ +
    +
  • Drive your car.
  • +
  • View data collected from your car.
  • +
+ + +

Features we are working on include:

+
    +
  • Train & debug models from web.
  • +
  • Browse library of driving models and download them.
  • +
  • Combine models
  • + +
+
+{% end %} diff --git a/donkey/templates/pilots_list.html b/donkey/templates/pilots_list.html new file mode 100644 index 000000000..cf24d24d4 --- /dev/null +++ b/donkey/templates/pilots_list.html @@ -0,0 +1,23 @@ + +{% extends "base.html" %} +{% block content %} +
+

Pilots

+ + + +
+{% end %} diff --git a/donkey/templates/session.html b/donkey/templates/session.html new file mode 100644 index 000000000..9b50120f7 --- /dev/null +++ b/donkey/templates/session.html @@ -0,0 +1,74 @@ + +{% extends "base.html" %} +{% block content %} + + + + + + + + +

Sessions {{ escape(session['name'])}}

+ + + + + +
+ {% for img in session['imgs'] %} +
+ + +
Angle: {{img['angle']}}
+
+ + {% end %} +
+ + + + + +{% end %} \ No newline at end of file diff --git a/donkey/templates/session_list.html b/donkey/templates/session_list.html new file mode 100644 index 000000000..a958d729d --- /dev/null +++ b/donkey/templates/session_list.html @@ -0,0 +1,23 @@ + +{% extends "base.html" %} +{% block content %} +
+

Sessions

+ + + +
+{% end %} diff --git a/donkey/templates/static/main.js b/donkey/templates/static/main.js index 264e3816b..0df17b4a2 100644 --- a/donkey/templates/static/main.js +++ b/donkey/templates/static/main.js @@ -1,180 +1,193 @@ -$( document ).ready(function() { - console.log( "document ready!" ); - velocity.bind() - - var joystick_options = { - zone: document.getElementById('joystick_container'), // active zone - color: '#668AED', - size: 350, - }; - - var manager = nipplejs.create(joystick_options); - - bindNipple(manager); - -}); - - -//Defaults -var postLoopRunning=false; -var sendURL = "control/" - - -function sendControl(angle, throttle, drive_mode, recording) { - //Send post request to server. - data = JSON.stringify({ 'angle': angle, - 'throttle':throttle, - 'drive_mode':drive_mode, - 'recording':recording}) - $.post(sendURL, data) -} - - -// Send control updates to the server every .1 seconds. -function postLoop () { - setTimeout(function () { - sendControl($('#angleInput').val(), - $('#throttleInput').val(), - 'user', - 'true') - - if (postLoopRunning) { - postLoop(); - } else { - // Send zero angle, throttle and stop recording - sendControl(0, 0, 'user', 'false') - } - }, 100) -} - - -function bindNipple(manager) { - manager.on('start end', function(evt, data) { - $('#angleInput').val(0); - $('#throttleInput').val(0); - - if (!postLoopRunning) { - postLoopRunning=true; - postLoop(); - } else { - postLoopRunning=false; - } - }).on('move', function(evt, data) { - angle = data['angle']['radian'] - distance = data['distance'] +var driveHandler = (function() { + //functions used to drive the vehicle. - $('#angleInput').val(Math.round(distance * Math.cos(angle)/2)); - $('#throttleInput').val(Math.round(distance * Math.sin(angle)/2)); - }); -} + var angle = 0 + var throttle = 0 + var driveMode = 'user' + var recording = false + var pilot = 'None' + var angleEl = "#angleInput" + var throttleEl = "#throttleInput" -$(document).keydown(function(e) { - if(e.which == 73) { - // 'i' throttle up - velocity.throttleUp() - } + var joystick_options = {} + var joystickLoopRunning=false; + var vehicle_id = "" + var driveURL = "" + var vehicleURL = "" - if(e.which == 75) { - // 'k' slow down - velocity.throttleDown() - } + var load = function() { - if(e.which == 74) { - // 'j' turn left - velocity.angleLeft() - } + vehicle_id = $('#vehicle_id').data('id') + driveURL = '/api/vehicles/drive/' + vehicle_id + "/" + vehicleURL = '/api/vehicles/' + vehicle_id + "/" - if(e.which == 76) { - // 'l' turn right - velocity.angleRight() - } + bindKeys() + bindPilotSelect() - if(e.which == 65) { - // 'a' turn on auto mode - velocity.updateDriveMode('auto') - } - if(e.which == 68) { - // 'a' turn on auto mode - velocity.updateDriveMode('user') - } - if(e.which == 83) { - // 'a' turn on auto mode - velocity.updateDriveMode('auto_angle') + joystick_options = { + zone: document.getElementById('joystick_container'), // active zone + color: '#668AED', + size: 350, + }; + + var manager = nipplejs.create(joystick_options); + + bindNipple(manager) + }; + + + + var bindKeys = function() { + //Bind a function to capture the coordinates of the click. + $(angleEl).change(function(e) { + postDrive() + }); + $(throttleEl).change(function(e) { + postDrive() + }); + + $(document).keydown(function(e) { + if(e.which == 73) { + // 'i' throttle up + throttleUp() + } + + if(e.which == 75) { + // 'k' slow down + throttleDown() + } + + if(e.which == 74) { + // 'j' turn left + angleLeft() + } + + if(e.which == 76) { + // 'l' turn right + angleRight() + } + + if(e.which == 65) { + // 'a' turn on auto mode + updateDriveMode('auto') + } + if(e.which == 68) { + // 'a' turn on auto mode + updateDriveMode('user') + } + if(e.which == 83) { + // 'a' turn on auto mode + updateDriveMode('auto_angle') + } + }); + }; + + + function bindNipple(manager) { + manager.on('start end', function(evt, data) { + $('#angleInput').val(0); + $('#throttleInput').val(0); + + if (!joystickLoopRunning) { + joystickLoopRunning=true; + joystickLoop(); + } else { + joystickLoopRunning=false; + } + + }).on('move', function(evt, data) { + radian = data['angle']['radian'] + distance = data['distance'] + + angle = Math.round(distance * Math.cos(radian)/2) + throttle = Math.round(distance/joystick_options['size']*200) + recording = true + + }); } -}); -var velocity = (function() { - //functions to change velocity of vehicle + var bindPilotSelect = function(){ + $('#pilot_select').on('change', function () { + pilot = $(this).val(); // get selected value + postPilot() + }); + }; - var angle = 0 - var throttle = 0 - var driveMode = 'user' - var angleEl = "#angleInput" - var throttleEl = "#throttleInput" - var sendURL = "control/" - var bind = function(data){ - //Bind a function to capture the coordinates of the click. - $(angleEl).change(function(e) { - sendVelocity() - }); - $(throttleEl).change(function(e) { - sendVelocity() - }); + var postPilot = function(){ + data = JSON.stringify({ 'pilot': pilot }) + console.log(data) + $.post(vehicleURL, data) + } + + + var updateDisplay = function() { + $(throttleEl).val(throttle); + $(angleEl).val(angle); + $('#driveMode').val(driveMode); }; - var sendVelocity = function() { + var postDrive = function() { //Send angle and throttle values - data = JSON.stringify({ 'angle': angle, 'throttle':throttle, 'drive_mode':driveMode, 'recording':'false'}) - $.post(sendURL, data) + updateDisplay() + data = JSON.stringify({ 'angle': angle, 'throttle':throttle, + 'drive_mode':driveMode, 'recording': recording}) + console.log(data) + $.post(driveURL, data) }; + + // Send control updates to the server every .1 seconds. + function joystickLoop () { + setTimeout(function () { + postDrive() + + if (joystickLoopRunning) { + joystickLoop(); + } else { + // Send zero angle, throttle and stop recording + angle = 0 + throttle = 0 + recording = 0 + postDrive() + } + }, 100) + } + var throttleUp = function(){ //Bind a function to capture the coordinates of the click. throttle = Math.min(throttle + 5, 400); - $(throttleEl).val(throttle) - sendVelocity() + postDrive() }; var throttleDown = function(){ //Bind a function to capture the coordinates of the click. throttle = Math.max(throttle - 10, -200); - $(throttleEl).val(throttle); - sendVelocity() + postDrive() }; var angleLeft = function(){ //Bind a function to capture the coordinates of the click. angle = Math.max(angle - 10, -90) - $(angleEl).val(angle); - sendVelocity() + postDrive() }; var angleRight = function(){ //Bind a function to capture the coordinates of the click. angle = Math.min(angle + 10, 90) - $(angleEl).val(angle); - sendVelocity() + postDrive() }; var updateDriveMode = function(mode){ //Bind a function to capture the coordinates of the click. driveMode = mode; - $('#driveMode').val(mode); - sendVelocity() + postDrive() }; - return { - bind: bind, - throttleUp: throttleUp, - throttleDown: throttleDown, - angleLeft: angleLeft, - angleRight: angleRight, - sendVelocity: sendVelocity, - updateDriveMode: updateDriveMode - }; + + return { load: load }; })(); diff --git a/donkey/templates/static/style.css b/donkey/templates/static/style.css index 107d99feb..30bbde9a4 100644 --- a/donkey/templates/static/style.css +++ b/donkey/templates/static/style.css @@ -25,3 +25,23 @@ } +div.img { + margin: 5px; + border: 1px solid #ccc; + float: left; + width: 180px; +} + +div.img:hover { + border: 1px solid #777; +} + +div.img img { + width: 100%; + height: auto; +} + +div.desc { + padding: 15px; + text-align: center; +} \ No newline at end of file diff --git a/donkey/templates/monitor.html b/donkey/templates/vehicle.html similarity index 66% rename from donkey/templates/monitor.html rename to donkey/templates/vehicle.html index 4531c7320..e06597e62 100644 --- a/donkey/templates/monitor.html +++ b/donkey/templates/vehicle.html @@ -1,26 +1,8 @@ - - - - - Donkey Monitor - - - - - - - - - - - - +{% extends "base.html" %} +{% block content %}
-

Donkey Control

+

Vehicle: {{vehicle['id']}}

Use this website to drive your vehicle. Data will only be recorded when you are actively steering.
@@ -28,11 +10,19 @@

Donkey Control

Image Stream (MJPEG)

- +

+ + Pilot: +
@@ -71,8 +61,20 @@

Donkey Control

Click/touch to use joystic.
+
+
- - - +
+ + + +{% end %} \ No newline at end of file diff --git a/donkey/templates/vehicle_list.html b/donkey/templates/vehicle_list.html new file mode 100644 index 000000000..0addcf4e8 --- /dev/null +++ b/donkey/templates/vehicle_list.html @@ -0,0 +1,23 @@ + +{% extends "base.html" %} +{% block content %} +
+

Vehicles

+ + + +
+{% end %} diff --git a/donkey/utils.py b/donkey/utils.py index 9be243e69..2017360d8 100644 --- a/donkey/utils.py +++ b/donkey/utils.py @@ -9,10 +9,6 @@ from PIL import Image import numpy as np -import envoy - - - ''' IMAGES ''' @@ -75,7 +71,7 @@ def binary_to_img(binary): def create_video(img_dir_path, output_video_path): - + import envoy # Setup path to the images with telemetry. full_path = os.path.join(img_dir_path, 'frame_*.png') @@ -230,4 +226,11 @@ def unbin_telemetry(y): def my_ip(): s = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) s.connect(('192.0.0.8', 1027)) - return s.getsockname()[0] \ No newline at end of file + return s.getsockname()[0] + + +def merge_two_dicts(x, y): + """Given two dicts, merge them into a new dict as a shallow copy.""" + z = x.copy() + z.update(y) + return z \ No newline at end of file diff --git a/donkey/vehicles.py b/donkey/vehicles.py index 791313da0..6b0f2487b 100644 --- a/donkey/vehicles.py +++ b/donkey/vehicles.py @@ -2,23 +2,19 @@ class BaseVehicle: def __init__(self, - drive_loop_delay = .2, + drive_loop_delay = .1, camera=None, - steering_actuator=None, - throttle_actuator=None, + actuator_mixer=None, pilot=None): self.drive_loop_delay = drive_loop_delay #how long to wait between loops #these need tobe updated when vehicle is defined self.camera = camera - self.steering_actuator = steering_actuator - self.throttle_actuator = throttle_actuator + self.actuator_mixer = actuator_mixer self.pilot = pilot - def start(self): - start_time = time.time() angle = 0 throttle = 0 @@ -36,11 +32,10 @@ def start(self): throttle, milliseconds) - self.steering_actuator.update(angle) - pulse = self.throttle_actuator.update(throttle) + self.actuator_mixer.update_angle(angle) + pulse = self.actuator_mixer.update_throttle(throttle) print(pulse) - #print current car state print('angle: %s throttle: %s' %(angle, throttle) ) - time.sleep(self.drive_loop_delay) + time.sleep(self.drive_loop_delay) \ No newline at end of file diff --git a/demos/train_model_search.py b/scripts/discover.py similarity index 87% rename from demos/train_model_search.py rename to scripts/discover.py index ab04abf5d..77ebc423b 100644 --- a/demos/train_model_search.py +++ b/scripts/discover.py @@ -26,11 +26,8 @@ #the models we want to test models = { - #'cnn3_full1_rnn1': dk.models.cnn3_full1_rnn1(), + 'cnn3_full1_rnn1': dk.models.cnn3_full1_rnn1(), 'cnn3_full1': dk.models.cnn3_full1(), - #'norm_cnn3_full1': dk.models.norm_cnn3_full1(), - 'norm_cnn3_full1': dk.models.norm_cnn3_full1(), - #'cnn1_full1': dk.models.cnn1_full1(), } @@ -49,7 +46,7 @@ X, Y = ds - hist = m.fit(X, Y, batch_size=32, nb_epoch=10, + hist = m.fit(X, Y, batch_size=32, nb_epoch=100, validation_split=.2, callbacks=callbacks_list) print(hist.history) diff --git a/demos/drive_pi.py b/scripts/drive.py similarity index 55% rename from demos/drive_pi.py rename to scripts/drive.py index 8dc96b8bb..e593da7a0 100644 --- a/demos/drive_pi.py +++ b/scripts/drive.py @@ -1,7 +1,7 @@ """ -Script to start controlling your car remotely via on Raspberry Pi that -constantly requests directions from a remote server. See serve_no_pilot.py -to start a server on your laptop. +Script to run on the Raspberry PI to start your vehicle's drive loop. The drive loop +will use post requests to the server specified in the remote argument. Use the +serve.py script to start the remote server. Usage: drive.py [--remote=] @@ -26,29 +26,32 @@ remote_url = args['--remote'] + mythrottlecontroller = dk.actuators.PCA9685_Controller(channel=0) + mysteeringcontroller = dk.actuators.PCA9685_Controller(channel=1) #Set up your PWM values for your steering and throttle actuator here. - mythrottle = dk.actuators.PWMThrottleActuator(channel=0, + mythrottle = dk.actuators.PWMThrottleActuator(controller=mythrottlecontroller, min_pulse=280, max_pulse=490, zero_pulse=350) - mysteering = dk.actuators.PWMSteeringActuator(channel=1, + mysteering = dk.actuators.PWMSteeringActuator(controller=mysteeringcontroller, left_pulse=300, right_pulse=400) + mymixer = dk.mixers.FrontSteeringMixer(mysteering, mythrottle) + #asych img capture from picamera mycamera = dk.sensors.PiVideoStream() #Get all autopilot signals from remote host mypilot = dk.remotes.RemoteClient(remote_url, vehicle_id='mycar') - #Create your car your car - car = dk.vehicles.BaseVehicle(camera=mycamera, - steering_actuator=mysteering, - throttle_actuator=mythrottle, + #Create your car + car = dk.vehicles.BaseVehicle(drive_loop_delay=.05, + camera=mycamera, + actuator_mixer=mymixer, pilot=mypilot) - #Start the drive loop car.start() diff --git a/scripts/munge.py b/scripts/munge.py new file mode 100644 index 000000000..fd527fde6 --- /dev/null +++ b/scripts/munge.py @@ -0,0 +1,17 @@ +""" +Script to provide commond line access to data manipulation functions. + +Usage: + munge.py [--sessions=] + + +Options: + --remote= recording session name +""" + +import donkey as dk + +dk.sessions.pickle_sessions(sessions_folder='/home/wroscoe/donkey_data/sessions/', + session_names=['ac_1130', 'ac_1150', 'ac_1240'], + #'wr_1030', 'wr_1115', 'wr_1150', 'wr_1240',] + file_path='/home/wroscoe/scale10-adam_cleaned.pkl') \ No newline at end of file diff --git a/scripts/serve.py b/scripts/serve.py new file mode 100644 index 000000000..fa872917b --- /dev/null +++ b/scripts/serve.py @@ -0,0 +1,56 @@ +""" +Script to start the server to controll your car remotely via on Raspberry Pi that +constantly requests directions from a remote server. + +Usage: + serve.py [--model=] + + +Options: + --model= path to model file +""" + +import os +from docopt import docopt + +import donkey as dk + + + +# Get args. +args = docopt(__doc__) + +""" +model_path = args['--model'] + +if model_path is None: + #setup how server will save files and which pilot to use + print('Starting servier without a pilot.') + pilot = dk.pilots.BasePilot() + +else: + import keras + #Load a trained keras model and use it in the KerasAngle pilot + #model_file = '/home/wroscoe/code/donkey/whiteline_model.hdf5' + model_file = model_path + + model = keras.models.load_model(model_file) + pilot = dk.pilots.KerasAngle(model=model, throttle=20) + + +sessions_path = '~/donkey_data/sessions' +sh = dk.sessions.SessionHandler(sessions_path=sessions_path) +session = sh.new() + +#start server +w = dk.remotes.RemoteServer(session, pilot) +w.start() + +#in a browser go to localhost:8887 to drive your car + + +""" + +#start server +w = dk.remotes.DonkeyPilotApplication() +w.start() \ No newline at end of file diff --git a/scripts/simulate.py b/scripts/simulate.py new file mode 100644 index 000000000..8c7a749ca --- /dev/null +++ b/scripts/simulate.py @@ -0,0 +1,32 @@ +""" +Run a fake car on the same machine as your server. Fake images are +created for the camera. + +""" + + +import os + +import donkey as dk + + +X, Y = dk.datasets.moving_square(n_frames=1000) + +#sh = dk.sessions.SessionHandler('/home/wroscoe/donkey_data/sessions') +#s = sh.load('test') +#X, Y = s.load_dataset() + + +camera_sim = dk.sensors.ImgArrayCamera(X) #For testing + +mixer = dk.mixers.BaseMixer() + +remote_pilot = dk.remotes.RemoteClient('http://localhost:8887', vehicle_id='mycar2') + + +car = dk.vehicles.BaseVehicle(camera=camera_sim, + actuator_mixer=mixer, + pilot=remote_pilot) + +#start the drive loop +car.start() diff --git a/demos/train.py b/scripts/train.py similarity index 74% rename from demos/train.py rename to scripts/train.py index 31959708b..ec8882b6a 100644 --- a/demos/train.py +++ b/scripts/train.py @@ -16,6 +16,11 @@ #X, Y = dk.datasets.moving_square(n_frames=2000, return_x=True, return_y=False) +print('Downloading file, this could take some time.) +url = 'https://s3.amazonaws.com/donkey_resources/port.pkl' +X, Y = dk.datasets.load_url(url) + +print('Loading Model.') model = dk.models.cnn3_full1() diff --git a/scripts/upload.py b/scripts/upload.py new file mode 100644 index 000000000..de1854714 --- /dev/null +++ b/scripts/upload.py @@ -0,0 +1,7 @@ +import donkey as dk + +sess + +dk.sessions.pickle_sessions(sessions_folder='/home/wroscoe/donkey_data/sessions/', + session_names=['f8'], + file_path='/home/wroscoe/f8.pkl') \ No newline at end of file diff --git a/setup.py b/setup.py index d6bcb4dcd..1660a0977 100644 --- a/setup.py +++ b/setup.py @@ -36,14 +36,15 @@ 'pillow', 'docopt==0.6.2', 'tornado', - 'requests' + 'requests', + 'envoy', ], extras_require={'server': [ 'keras', 'h5py', - 'envoy', - 'scikit-image' + 'scikit-image', + 'opencv-python' ], 'pi': [ 'picamera',