diff --git a/.travis.yml b/.travis.yml index 7bd0eb34f..80b2a91b1 100644 --- a/.travis.yml +++ b/.travis.yml @@ -2,7 +2,6 @@ language: python # This list should match the versions listed in setup.py python: -- 3.4 - 3.5 - 3.6 @@ -29,14 +28,23 @@ install: script: - pytest -v --cov=donkeycar donkeycar/tests +stages: + - name: deploy + if: branch = master + +jobs: + include: + - stage: deploy + python: 3.6 + script: skip + deploy: + provider: pypi + user: wroscoe + password: + secure: Y64NS2etlOIjKMTLQex+5H/QrKdBzwGjhZ9VVp1NXyx76oqg0ygn5lOPcMAvQbuJbGzT0E/5q/EDhJAh6YjyjVYAS2UgBUehpY5Nu0oYFTfWCTC9fbQRn0XRLXPeZR3BKZ1cAxDCMm4a6iZ4M8CqatN73IexcORCYgkIXZfGRVGcAdLonWzkXPqIwe287e7TiQAx6wM6e7k4DRRUFcrw56lLWTG6FEkauQDNXJFlySwesIgFni+K59tHcxP1U00NTV5utTaNzkkFwro4bp6EsVHEYr8Hgz2Sv0mxAggWmXaMGwILahTSVoRznFsik4r3DiOwVEAc+aeTHg9NJin5/ic4ShODMPKkBQInUNxgmE8cZy5EpZ+a9Xbp1dNt/+x56Bmz+bKoQq/e0ydIBNXCeaT41VFyJTjz9db01HwUPZHfp0NCyIo5QcknH98G0oLmaqv43qGJzmaQi0h4BkkmgI5HpkE12MSDC8QFsDKmOXlj/I4WEWXuPslhuKTgYNadFGdTkfbhnbMjRDkuNfL8YSXwnNDTcB5qT3hIYWGVKN2qAAljWniWHdQMMosMv7CwfoM7IO6apgBuvoMJOMunHEgyGDX5Hb1Y5YYa+OC/0eCfcIEScoPM0JHtMmznYlIv5vwx8B3yK0qk0W8nIv65bZvP5eYBF1zLgeE2FLsuc1o= + on: + tags: true + branch: master + after_success: -- codecov - -deploy: - provider: pypi - user: wroscoe - password: - secure: Y64NS2etlOIjKMTLQex+5H/QrKdBzwGjhZ9VVp1NXyx76oqg0ygn5lOPcMAvQbuJbGzT0E/5q/EDhJAh6YjyjVYAS2UgBUehpY5Nu0oYFTfWCTC9fbQRn0XRLXPeZR3BKZ1cAxDCMm4a6iZ4M8CqatN73IexcORCYgkIXZfGRVGcAdLonWzkXPqIwe287e7TiQAx6wM6e7k4DRRUFcrw56lLWTG6FEkauQDNXJFlySwesIgFni+K59tHcxP1U00NTV5utTaNzkkFwro4bp6EsVHEYr8Hgz2Sv0mxAggWmXaMGwILahTSVoRznFsik4r3DiOwVEAc+aeTHg9NJin5/ic4ShODMPKkBQInUNxgmE8cZy5EpZ+a9Xbp1dNt/+x56Bmz+bKoQq/e0ydIBNXCeaT41VFyJTjz9db01HwUPZHfp0NCyIo5QcknH98G0oLmaqv43qGJzmaQi0h4BkkmgI5HpkE12MSDC8QFsDKmOXlj/I4WEWXuPslhuKTgYNadFGdTkfbhnbMjRDkuNfL8YSXwnNDTcB5qT3hIYWGVKN2qAAljWniWHdQMMosMv7CwfoM7IO6apgBuvoMJOMunHEgyGDX5Hb1Y5YYa+OC/0eCfcIEScoPM0JHtMmznYlIv5vwx8B3yK0qk0W8nIv65bZvP5eYBF1zLgeE2FLsuc1o= - on: - tags: true - branch: master +- codecov \ No newline at end of file diff --git a/Dockerfile b/Dockerfile index 85c86590f..42d0f25f4 100644 --- a/Dockerfile +++ b/Dockerfile @@ -1,8 +1,29 @@ -FROM python:3 +FROM python:3.6 WORKDIR /app +# install donkey with tensorflow (cpu only version) +ADD ./setup.py /app/setup.py +ADD ./README.md /app/README.md +RUN pip install -e .[tf] + +# get testing requirements +RUN pip install -e .[dev] + +# setup jupyter notebook to run without password +RUN pip install jupyter notebook +RUN jupyter notebook --generate-config +RUN echo "c.NotebookApp.password = ''">>/root/.jupyter/jupyter_notebook_config.py +RUN echo "c.NotebookApp.token = ''">>/root/.jupyter/jupyter_notebook_config.py + +# add the whole app dir after install so the pip install isn't updated when code changes. ADD . /app -RUN pip install -e . +#start the jupyter notebook +CMD jupyter notebook --no-browser --ip 0.0.0.0 --port 8888 --allow-root --notebook-dir=/app/notebooks + +#port for donkeycar EXPOSE 8887 + +#port for jupyter notebook +EXPOSE 8888 \ No newline at end of file diff --git a/MANIFEST.in b/MANIFEST.in index e480beeb9..2d41b7d62 100644 --- a/MANIFEST.in +++ b/MANIFEST.in @@ -1,2 +1,3 @@ include donkeycar/templates/* -recursive-include donkeycar/parts/web_controller/templates/ * \ No newline at end of file +include VERSION +recursive-include donkeycar/parts/web_controller/templates/ * diff --git a/Makefile b/Makefile new file mode 100644 index 000000000..ae84f8859 --- /dev/null +++ b/Makefile @@ -0,0 +1,8 @@ + + +tests: + pytest + +package: + python setup.py sdist + diff --git a/README.md b/README.md index 560da9446..8be48f2cc 100644 --- a/README.md +++ b/README.md @@ -6,7 +6,7 @@ [![Py versions](https://img.shields.io/pypi/pyversions/donkeycar.svg)](https://img.shields.io/pypi/pyversions/donkeycar.svg) Donkeycar is minimalist and modular self driving library for Python. It is -developed for hobbiests and students with a focus on allowing fast experimentation and easy +developed for hobbyists and students with a focus on allowing fast experimentation and easy community contributions. #### Quick Links @@ -21,12 +21,11 @@ community contributions. * Compete in self driving races like [DIY Robocars](http://diyrobocars.com) * Experiment with autopilots, mapping computer vision and neural networks. * Log sensor data. (images, user inputs, sensor readings) -* Drive your car via a web or game controler. +* Drive your car via a web or game controller. * Leverage community contributed driving data. -* Use existing harsupport -supportdware CAD designs for upgrades. +* Use existing CAD models for design upgrades. -### Getting driving. +### Get driving. After building a Donkey2 you can turn on your car and go to http://localhost:8887 to drive. ### Modify your cars behavior. diff --git a/docs/guide/install_software.md b/docs/guide/install_software.md index 48f95e65a..ca08282b8 100644 --- a/docs/guide/install_software.md +++ b/docs/guide/install_software.md @@ -149,7 +149,7 @@ python -c "import donkeycar as dk; print(dk.__version__)" Now generate the drive script, config and folder structure for your car. ```bash -donkey createcar ~/ +donkey createcar ~/mycar ``` ---- diff --git a/docs/index.md b/docs/index.md index 3925c880c..dccaac730 100644 --- a/docs/index.md +++ b/docs/index.md @@ -7,9 +7,7 @@ developed with a focus on enabling fast experimentation and easy contribution. ### Build your own Donkey2 -Donkey2 is the standard car that most people build first. The parts cost about $250 to $300 - -and take 2 hours to assemble. Here are the main steps to build your own car: +Donkey2 is the standard car that most people build first. The parts cost about $250 to $300 and take 2 hours to assemble. Here are the main steps to build your own car: 1. [Assemble hardware.](guide/build_hardware.md) 2. [Install software.](guide/install_software.md) diff --git a/donkeycar/__init__.py b/donkeycar/__init__.py index b77608265..f6dac6b5e 100644 --- a/donkeycar/__init__.py +++ b/donkeycar/__init__.py @@ -1,9 +1,16 @@ -__version__ = '2.5.1' - -print('using donkey v{} ...'.format(__version__)) +import os +import pkg_resources # part of setuptools import sys +__version__ = pkg_resources.require("donkeycar")[0].version +print('using donkey version: {} ...'.format(__version__)) + + + +current_module = sys.modules[__name__] + + if sys.version_info.major < 3: msg = 'Donkey Requires Python 3.4 or greater. You are using {}'.format(sys.version) raise ValueError(msg) diff --git a/donkeycar/parts/actuator.py b/donkeycar/parts/actuator.py index 7af3a54f6..21c2611a6 100644 --- a/donkeycar/parts/actuator.py +++ b/donkeycar/parts/actuator.py @@ -7,6 +7,7 @@ import time import donkeycar as dk + class PCA9685: """ PWM motor controler using PCA9685 boards. @@ -20,11 +21,15 @@ def __init__(self, channel, frequency=60): self.channel = channel def set_pulse(self, pulse): - self.pwm.set_pwm(self.channel, 0, pulse) + try: + self.pwm.set_pwm(self.channel, 0, pulse) + except OSError as err: + print("Unexpected issue setting PWM (check wires to motor board): {0}".format(err)) def run(self, pulse): self.set_pulse(pulse) + class PWMSteering: """ Wrapper over a PWM motor cotnroller to convert angles to PWM pulses. @@ -33,25 +38,24 @@ class PWMSteering: RIGHT_ANGLE = 1 def __init__(self, controller=None, - left_pulse=290, - right_pulse=490): + left_pulse=290, right_pulse=490): self.controller = controller self.left_pulse = left_pulse self.right_pulse = right_pulse - def run(self, angle): - #map absolute angle to angle that vehicle can implement. - pulse = dk.util.data.map_range(angle, - self.LEFT_ANGLE, self.RIGHT_ANGLE, - self.left_pulse, self.right_pulse) + # map absolute angle to angle that vehicle can implement. + pulse = dk.util.data.map_range( + angle, + self.LEFT_ANGLE, self.RIGHT_ANGLE, + self.left_pulse, self.right_pulse + ) self.controller.set_pulse(pulse) def shutdown(self): - self.run(0) #set steering straight - + self.run(0) # set steering straight class PWMThrottle: @@ -60,38 +64,37 @@ class PWMThrottle: values to PWM pulses. """ MIN_THROTTLE = -1 - MAX_THROTTLE = 1 + MAX_THROTTLE = 1 - def __init__(self, controller=None, - max_pulse=300, - min_pulse=490, - zero_pulse=350): + def __init__(self, + controller=None, + max_pulse=300, + min_pulse=490, + zero_pulse=350): self.controller = controller self.max_pulse = max_pulse self.min_pulse = min_pulse self.zero_pulse = zero_pulse - #send zero pulse to calibrate ESC + # send zero pulse to calibrate ESC self.controller.set_pulse(self.zero_pulse) time.sleep(1) - def run(self, throttle): if throttle > 0: pulse = dk.util.data.map_range(throttle, - 0, self.MAX_THROTTLE, - self.zero_pulse, self.max_pulse) + 0, self.MAX_THROTTLE, + self.zero_pulse, self.max_pulse) else: pulse = dk.util.data.map_range(throttle, - self.MIN_THROTTLE, 0, - self.min_pulse, self.zero_pulse) + self.MIN_THROTTLE, 0, + self.min_pulse, self.zero_pulse) self.controller.set_pulse(pulse) def shutdown(self): - self.run(0) #stop vehicle - + self.run(0) # stop vehicle class Adafruit_DCMotor_Hat: @@ -114,14 +117,13 @@ def __init__(self, motor_num): self.speed = 0 self.throttle = 0 - def run(self, speed): """ Update the speed of the motor where 1 is full forward and -1 is full backwards. """ if speed > 1 or speed < -1: - raise ValueError( "Speed must be between 1(forward) and -1(reverse)") + raise ValueError("Speed must be between 1(forward) and -1(reverse)") self.speed = speed self.throttle = int(dk.util.data.map_range(abs(speed), -1, 1, -255, 255)) @@ -133,187 +135,5 @@ def run(self, speed): self.motor.setSpeed(self.throttle) - def shutdown(self): self.mh.getMotor(self.motor_num).run(Adafruit_MotorHAT.RELEASE) - -class Maestro: - """ - Pololu Maestro Servo controller - Use the MaestroControlCenter to set the speed & acceleration values to 0! - """ - import threading - - maestro_device = None - astar_device = None - maestro_lock = threading.Lock() - astar_lock = threading.Lock() - - def __init__(self, channel, frequency = 60): - import serial - - if Maestro.maestro_device == None: - Maestro.maestro_device = serial.Serial('/dev/ttyACM0', 115200) - - self.channel = channel - self.frequency = frequency - self.lturn = False - self.rturn = False - self.headlights = False - self.brakelights = False - - if Maestro.astar_device == None: - Maestro.astar_device = serial.Serial('/dev/ttyACM2', 115200, timeout= 0.01) - - def set_pulse(self, pulse): - # Recalculate pulse width from the Adafruit values - w = pulse * (1 / (self.frequency * 4096)) # in seconds - w *= 1000 * 1000 # in microseconds - w *= 4 # in quarter microsenconds the maestro wants - w = int(w) - - with Maestro.maestro_lock: - Maestro.maestro_device.write(bytearray([ 0x84, - self.channel, - (w & 0x7F), - ((w >> 7) & 0x7F)])) - - def set_turn_left(self, v): - if self.lturn != v: - self.lturn = v - b = bytearray('L' if v else 'l', 'ascii') - with Maestro.astar_lock: - Maestro.astar_device.write(b) - - def set_turn_right(self, v): - if self.rturn != v: - self.rturn = v - b = bytearray('R' if v else 'r', 'ascii') - with Maestro.astar_lock: - Maestro.astar_device.write(b) - - def set_headlight(self, v): - if self.headlights != v: - self.headlights = v - b = bytearray('H' if v else 'h', 'ascii') - with Maestro.astar_lock: - Maestro.astar_device.write(b) - - def set_brake(self, v): - if self.brakelights != v: - self.brakelights = v - b = bytearray('B' if v else 'b', 'ascii') - with Maestro.astar_lock: - Maestro.astar_device.write(b) - - def readline(self): - ret = None - with Maestro.astar_lock: - # expecting lines like - # E n nnn n - if Maestro.astar_device.inWaiting() > 8: - ret = Maestro.astar_device.readline() - - if ret != None: - ret = ret.rstrip() - - return ret - -class Teensy: - """ - Teensy Servo controller - """ - import threading - - teensy_device = None - astar_device = None - teensy_lock = threading.Lock() - astar_lock = threading.Lock() - - def __init__(self, channel, frequency = 60): - import serial - - if Teensy.teensy_device == None: - Teensy.teensy_device = serial.Serial('/dev/teensy', 115200, timeout = 0.01) - - self.channel = channel - self.frequency = frequency - self.lturn = False - self.rturn = False - self.headlights = False - self.brakelights = False - - if Teensy.astar_device == None: - Teensy.astar_device = serial.Serial('/dev/astar', 115200, timeout = 0.01) - - def set_pulse(self, pulse): - # Recalculate pulse width from the Adafruit values - w = pulse * (1 / (self.frequency * 4096)) # in seconds - w *= 1000 * 1000 # in microseconds - - with Teensy.teensy_lock: - Teensy.teensy_device.write(("%c %.1f\n" % (self.channel, w)).encode('ascii')) - - def set_turn_left(self, v): - if self.lturn != v: - self.lturn = v - b = bytearray('L' if v else 'l', 'ascii') - with Teensy.astar_lock: - Teensy.astar_device.write(b) - - def set_turn_right(self, v): - if self.rturn != v: - self.rturn = v - b = bytearray('R' if v else 'r', 'ascii') - with Teensy.astar_lock: - Teensy.astar_device.write(b) - - def set_headlight(self, v): - if self.headlights != v: - self.headlights = v - b = bytearray('H' if v else 'h', 'ascii') - with Teensy.astar_lock: - Teensy.astar_device.write(b) - - def set_brake(self, v): - if self.brakelights != v: - self.brakelights = v - b = bytearray('B' if v else 'b', 'ascii') - with Teensy.astar_lock: - Teensy.astar_device.write(b) - - def teensy_readline(self): - ret = None - with Teensy.teensy_lock: - # expecting lines like - # E n nnn n - if Teensy.teensy_device.inWaiting() > 8: - ret = Teensy.teensy_device.readline() - - if ret != None: - ret = ret.rstrip() - - return ret - - def astar_readline(self): - ret = None - with Teensy.astar_lock: - # expecting lines like - # E n nnn n - if Teensy.astar_device.inWaiting() > 8: - ret = Teensy.astar_device.readline() - - if ret != None: - ret = ret.rstrip() - - return ret - -class MockController(object): - def __init__(self): - pass - - def run(self, pulse): - pass - - def shutdown(self): - pass diff --git a/donkeycar/parts/autorope.py b/donkeycar/parts/autorope.py deleted file mode 100644 index c77207f9b..000000000 --- a/donkeycar/parts/autorope.py +++ /dev/null @@ -1,130 +0,0 @@ - -import time -import requests -from six.moves.urllib import parse -import calendar -import datetime - -from ..log import get_logger - -logger = get_logger(__name__) - - -def _api_encode(data): - for key, value in data.items(): - if value is None: - continue - elif isinstance(value, datetime.datetime): - yield (key, _encode_datetime(value)) - else: - yield (key, value) - - -def _build_api_url(url, query): - scheme, netloc, path, base_query, fragment = parse.urlsplit(url) - if base_query: - query = str('%s&%s' % (base_query, query)) - - return parse.urlunsplit((scheme, netloc, path, query, fragment)) - - -def _encode_datetime(dttime): - if dttime.tzinfo and dttime.tzinfo.utcoffset(dttime) is not None: - utc_timestamp = calendar.timegm(dttime.utctimetuple()) - else: - utc_timestamp = time.mktime(dttime.timetuple()) - - return int(utc_timestamp) - - -class AutoropeSession: - - def __init__(self, - token, - car_id, - controller_url=None, - api_base='https://rope.donkeycar.com/api/'): - - self.auth_token = token - self.car_id = car_id - self.connected = False - self.api_base = api_base - - try: - self.session_id = self.start_new_session(controller_url=controller_url) - logger.info('started new autorope session {}'.format(self.session_id)) - except Exception as e: - logger.info('Autorope part was unable to load. Goto rope.donkeycar.com for instructions') - logger.info(e) - - def start_new_session(self, controller_url=None): - resp = self.post_request('sessions/', - { - 'bot_name': self.car_id, - 'controller_url': controller_url - } - ) - if resp.status_code == 200: - resp_js = resp.json() - self.session_id = resp_js.get('id') - return self.session_id - else: - logger.info(resp.text) - return None - - def update(self): - self.measurements = self.lidar.iter_measurments(500) - for new_scan, quality, angle, distance in self.measurements: - angle = int(angle) - self.frame[angle] = 2 * distance / 3 + self.frame[angle] / 3 - if not self.on: - break - - def run_threaded(self): - return self.frame - - def _build_headers(self, headers={}): - - auth_header = {'Authorization': 'Token {}'.format(self.auth_token)} - headers.update(auth_header) - return headers - - def get_request(self, url, params={}, supplied_headers={}, format='json'): - # combine default params and given params - params_all = {} - params_all.update(params) - - abs_url = self.api_base + url - encoded_params = parse.urlencode(list(_api_encode(params_all))) - abs_url = _build_api_url(abs_url, encoded_params) - - # logger.info('abs_url: {}'.format(abs_url)) - headers = self._build_headers(supplied_headers) - - logger.info(headers) - logger.info(abs_url) - resp = requests.get(abs_url, headers=headers) - if format == 'json': - return resp - elif format == 'text': - return resp.text - elif format == 'gdf': - import tempfile - import geopandas as gp - file = tempfile.NamedTemporaryFile(suffix='.json', delete=False, mode='w') - file.write(resp.text) - file.close() - - gdf = gp.read_file(file.name) - return gdf - - - def post_request(self, url, data, params=None, supplied_headers={}, files=None): - abs_url = self.api_base + url - - encoded_params = parse.urlencode(list(_api_encode(params or {}))) - abs_url = _build_api_url(abs_url, encoded_params) - headers = self._build_headers(supplied_headers) - logger.info(abs_url) - resp = requests.post(abs_url, json=data, headers=headers, files=files) - return resp diff --git a/donkeycar/parts/camera.py b/donkeycar/parts/camera.py index 0b7ff84a0..fa6d2d6b1 100644 --- a/donkeycar/parts/camera.py +++ b/donkeycar/parts/camera.py @@ -4,23 +4,26 @@ from PIL import Image import glob + class BaseCamera: def run_threaded(self): return self.frame + class PiCamera(BaseCamera): def __init__(self, resolution=(120, 160), framerate=20): from picamera.array import PiRGBArray from picamera import PiCamera resolution = (resolution[1], resolution[0]) # initialize the camera and stream - self.camera = PiCamera() #PiCamera gets resolution (height, width) + self.camera = PiCamera() # PiCamera gets resolution (height, width) self.camera.resolution = resolution self.camera.framerate = framerate self.rawCapture = PiRGBArray(self.camera, size=resolution) self.stream = self.camera.capture_continuous(self.rawCapture, - format="rgb", use_video_port=True) + format="rgb", + use_video_port=True) # initialize the frame and the variable used to indicate # if the thread should be stopped @@ -30,7 +33,6 @@ def __init__(self, resolution=(120, 160), framerate=20): print('PiCamera loaded.. .warming camera') time.sleep(2) - def run(self): f = next(self.stream) frame = f.array @@ -57,111 +59,3 @@ def shutdown(self): self.stream.close() self.rawCapture.close() self.camera.close() - -class Webcam(BaseCamera): - def __init__(self, resolution = (160, 120), framerate = 20): - import pygame - import pygame.camera - - super().__init__() - - pygame.init() - pygame.camera.init() - l = pygame.camera.list_cameras() - self.cam = pygame.camera.Camera(l[0], resolution, "RGB") - self.resolution = resolution - self.cam.start() - self.framerate = framerate - - # initialize variable used to indicate - # if the thread should be stopped - self.frame = None - self.on = True - - print('WebcamVideoStream loaded.. .warming camera') - - time.sleep(2) - - def update(self): - from datetime import datetime, timedelta - import pygame.image - while self.on: - start = datetime.now() - - if self.cam.query_image(): - # snapshot = self.cam.get_image() - # self.frame = list(pygame.image.tostring(snapshot, "RGB", False)) - snapshot = self.cam.get_image() - snapshot1 = pygame.transform.scale(snapshot, self.resolution) - self.frame = pygame.surfarray.pixels3d(pygame.transform.rotate(pygame.transform.flip(snapshot1, True, False), 90)) - - stop = datetime.now() - s = 1 / self.framerate - (stop - start).total_seconds() - if s > 0: - time.sleep(s) - - self.cam.stop() - - def run_threaded(self): - return self.frame - - def shutdown(self): - # indicate that the thread should be stopped - self.on = False - print('stoping Webcam') - time.sleep(.5) - -class MockCamera(BaseCamera): - """ - Fake camera. Returns only a single static frame - """ - def __init__(self, resolution=(160, 120), image=None): - if image is not None: - self.frame = image - else: - self.frame = Image.new('RGB', resolution) - - def update(self): - pass - - def shutdown(self): - pass - -class ImageListCamera(BaseCamera): - """ - Use the images from a tub as a fake camera output - """ - def __init__(self, path_mask='~/mycar/data/**/*.jpg'): - self.image_filenames = glob.glob(os.path.expanduser(path_mask), recursive=True) - - def get_image_index(fnm): - sl = os.path.basename(fnm).split('_') - return int(sl[0]) - - """ - I feel like sorting by modified time is almost always - what you want. but if you tared and moved your data around, - sometimes it doesn't preserve a nice modified time. - so, sorting by image index works better, but only with one path. - """ - self.image_filenames.sort(key=get_image_index) - #self.image_filenames.sort(key=os.path.getmtime) - self.num_images = len(self.image_filenames) - print('%d images loaded.' % self.num_images) - print( self.image_filenames[:10]) - self.i_frame = 0 - self.frame = None - self.update() - - def update(self): - pass - - def run_threaded(self): - if self.num_images > 0: - self.i_frame = (self.i_frame + 1) % self.num_images - self.frame = Image.open(self.image_filenames[self.i_frame]) - - return np.asarray(self.frame) - - def shutdown(self): - pass diff --git a/donkeycar/parts/clock.py b/donkeycar/parts/clock.py index 0f099768f..51c70ac06 100644 --- a/donkeycar/parts/clock.py +++ b/donkeycar/parts/clock.py @@ -1,7 +1,7 @@ import datetime + class Timestamp(): def run(self,): return str(datetime.datetime.utcnow()) - diff --git a/donkeycar/parts/controller.py b/donkeycar/parts/controller.py deleted file mode 100644 index ea32bccaf..000000000 --- a/donkeycar/parts/controller.py +++ /dev/null @@ -1,392 +0,0 @@ - - -import array -import time -import struct - - -from donkeycar.parts.web_controller.web import LocalWebController - -class Joystick(): - """ - An interface to a physical joystick available at /dev/input - """ - access_url = None #required to be consistent with web controller - - def __init__(self, dev_fn='/dev/input/js0'): - self.axis_states = {} - self.button_states = {} - self.axis_map = [] - self.button_map = [] - self.jsdev = None - self.dev_fn = dev_fn - - # These constants were borrowed from linux/input.h - self.axis_names = { - 0x00 : 'x', - 0x01 : 'y', - 0x02 : 'z', - 0x03 : 'rx', - 0x04 : 'ry', - 0x05 : 'rz', - 0x06 : 'trottle', - 0x07 : 'rudder', - 0x08 : 'wheel', - 0x09 : 'gas', - 0x0a : 'brake', - 0x10 : 'hat0x', - 0x11 : 'hat0y', - 0x12 : 'hat1x', - 0x13 : 'hat1y', - 0x14 : 'hat2x', - 0x15 : 'hat2y', - 0x16 : 'hat3x', - 0x17 : 'hat3y', - 0x18 : 'pressure', - 0x19 : 'distance', - 0x1a : 'tilt_x', - 0x1b : 'tilt_y', - 0x1c : 'tool_width', - 0x20 : 'volume', - 0x28 : 'misc', - } - - self.button_names = { - 0x120 : 'trigger', - 0x121 : 'thumb', - 0x122 : 'thumb2', - 0x123 : 'top', - 0x124 : 'top2', - 0x125 : 'pinkie', - 0x126 : 'base', - 0x127 : 'base2', - 0x128 : 'base3', - 0x129 : 'base4', - 0x12a : 'base5', - 0x12b : 'base6', - - #PS3 sixaxis specific - 0x12c : "triangle", - 0x12d : "circle", - 0x12e : "cross", - 0x12f : 'square', - - 0x130 : 'a', - 0x131 : 'b', - 0x132 : 'c', - 0x133 : 'x', - 0x134 : 'y', - 0x135 : 'z', - 0x136 : 'tl', - 0x137 : 'tr', - 0x138 : 'tl2', - 0x139 : 'tr2', - 0x13a : 'select', - 0x13b : 'start', - 0x13c : 'mode', - 0x13d : 'thumbl', - 0x13e : 'thumbr', - - 0x220 : 'dpad_up', - 0x221 : 'dpad_down', - 0x222 : 'dpad_left', - 0x223 : 'dpad_right', - - # XBox 360 controller uses these codes. - 0x2c0 : 'dpad_left', - 0x2c1 : 'dpad_right', - 0x2c2 : 'dpad_up', - 0x2c3 : 'dpad_down', - } - - - def init(self): - from fcntl import ioctl - """ - call once to setup connection to dev/input/js0 and map buttons - """ - # Open the joystick device. - print('Opening %s...' % self.dev_fn) - self.jsdev = open(self.dev_fn, 'rb') - - # Get the device name. - buf = array.array('B', [0] * 64) - ioctl(self.jsdev, 0x80006a13 + (0x10000 * len(buf)), buf) # JSIOCGNAME(len) - self.js_name = buf.tobytes().decode('utf-8') - print('Device name: %s' % self.js_name) - - # Get number of axes and buttons. - buf = array.array('B', [0]) - ioctl(self.jsdev, 0x80016a11, buf) # JSIOCGAXES - self.num_axes = buf[0] - - buf = array.array('B', [0]) - ioctl(self.jsdev, 0x80016a12, buf) # JSIOCGBUTTONS - self.num_buttons = buf[0] - - # Get the axis map. - buf = array.array('B', [0] * 0x40) - ioctl(self.jsdev, 0x80406a32, buf) # JSIOCGAXMAP - - for axis in buf[:self.num_axes]: - axis_name = self.axis_names.get(axis, 'unknown(0x%02x)' % axis) - self.axis_map.append(axis_name) - self.axis_states[axis_name] = 0.0 - - # Get the button map. - buf = array.array('H', [0] * 200) - ioctl(self.jsdev, 0x80406a34, buf) # JSIOCGBTNMAP - - for btn in buf[:self.num_buttons]: - btn_name = self.button_names.get(btn, 'unknown(0x%03x)' % btn) - self.button_map.append(btn_name) - self.button_states[btn_name] = 0 - - return True - - - def show_map(self): - """ - list the buttons and axis found on this joystick - """ - print ('%d axes found: %s' % (self.num_axes, ', '.join(self.axis_map))) - print ('%d buttons found: %s' % (self.num_buttons, ', '.join(self.button_map))) - - - def poll(self): - """ - query the state of the joystick, returns button which was pressed, if any, - and axis which was moved, if any. button_state will be None, 1, or 0 if no changes, - pressed, or released. axis_val will be a float from -1 to +1. button and axis will - be the string label determined by the axis map in init. - """ - button = None - button_state = None - axis = None - axis_val = None - - # Main event loop - evbuf = self.jsdev.read(8) - - if evbuf: - tval, value, typev, number = struct.unpack('IhBB', evbuf) - - if typev & 0x80: - #ignore initialization event - return button, button_state, axis, axis_val - - if typev & 0x01: - button = self.button_map[number] - if button: - self.button_states[button] = value - button_state = value - - if typev & 0x02: - axis = self.axis_map[number] - if axis: - fvalue = value / 32767.0 - self.axis_states[axis] = fvalue - axis_val = fvalue - - return button, button_state, axis, axis_val - - -class JoystickController(object): - """ - Joystick client using access to local physical input - """ - - def __init__(self, poll_delay=0.0, - max_throttle=1.0, - steering_axis='x', - throttle_axis='rz', - steering_scale=1.0, - throttle_scale=-1.0, - dev_fn='/dev/input/js0', - auto_record_on_throttle=True): - - self.angle = 0.0 - self.throttle = 0.0 - self.mode = 'user' - self.poll_delay = poll_delay - self.running = True - self.max_throttle = max_throttle - self.steering_axis = steering_axis - self.throttle_axis = throttle_axis - self.steering_scale = steering_scale - self.throttle_scale = throttle_scale - self.recording = False - self.constant_throttle = False - self.auto_record_on_throttle = auto_record_on_throttle - self.dev_fn = dev_fn - self.js = None - - #We expect that the framework for parts will start a new - #thread for our update fn. We used to do that and it caused - #two threads to be polling for js events. - - def on_throttle_changes(self): - """ - turn on recording when non zero throttle in the user mode. - """ - if self.auto_record_on_throttle: - self.recording = (self.throttle != 0.0 and self.mode == 'user') - - def init_js(self): - """ - attempt to init joystick - """ - try: - self.js = Joystick(self.dev_fn) - self.js.init() - except FileNotFoundError: - print(self.dev_fn, "not found.") - self.js = None - return self.js is not None - - - def update(self): - """ - poll a joystick for input events - - button map name => PS3 button => function - * top2 = PS3 dpad up => increase throttle scale - * base = PS3 dpad down => decrease throttle scale - * base2 = PS3 dpad left => increase steering scale - * pinkie = PS3 dpad right => decrease steering scale - * trigger = PS3 select => switch modes - * top = PS3 start => toggle constant throttle - * base5 = PS3 left trigger 1 - * base3 = PS3 left trigger 2 - * base6 = PS3 right trigger 1 - * base4 = PS3 right trigger 2 - * thumb2 = PS3 right thumb - * thumb = PS3 left thumb - * circle = PS3 circrle => toggle recording - * triangle = PS3 triangle => increase max throttle - * cross = PS3 cross => decrease max throttle - """ - - #wait for joystick to be online - while self.running and not self.init_js(): - time.sleep(5) - - while self.running: - button, button_state, axis, axis_val = self.js.poll() - - if axis == self.steering_axis: - self.angle = self.steering_scale * axis_val - print("angle", self.angle) - - if axis == self.throttle_axis: - #this value is often reversed, with positive value when pulling down - self.throttle = (self.throttle_scale * axis_val * self.max_throttle) - print("throttle", self.throttle) - self.on_throttle_changes() - - if button == 'trigger' and button_state == 1: - """ - switch modes from: - user: human controlled steer and throttle - local_angle: ai steering, human throttle - local: ai steering, ai throttle - """ - if self.mode == 'user': - self.mode = 'local_angle' - elif self.mode == 'local_angle': - self.mode = 'local' - else: - self.mode = 'user' - print('new mode:', self.mode) - - if button == 'circle' and button_state == 1: - """ - toggle recording on/off - """ - if self.auto_record_on_throttle: - print('auto record on throttle is enabled.') - elif self.recording: - self.recording = False - else: - self.recording = True - - print('recording:', self.recording) - - if button == 'triangle' and button_state == 1: - """ - increase max throttle setting - """ - self.max_throttle = round(min(1.0, self.max_throttle + 0.01), 2) - if self.constant_throttle: - self.throttle = self.max_throttle - self.on_throttle_changes() - - print('max_throttle:', self.max_throttle) - - if button == 'cross' and button_state == 1: - """ - decrease max throttle setting - """ - self.max_throttle = round(max(0.0, self.max_throttle - 0.01), 2) - if self.constant_throttle: - self.throttle = self.max_throttle - self.on_throttle_changes() - - print('max_throttle:', self.max_throttle) - - if button == 'base' and button_state == 1: - """ - increase throttle scale - """ - self.throttle_scale = round(min(0.0, self.throttle_scale + 0.05), 2) - print('throttle_scale:', self.throttle_scale) - - if button == 'top2' and button_state == 1: - """ - decrease throttle scale - """ - self.throttle_scale = round(max(-1.0, self.throttle_scale - 0.05), 2) - print('throttle_scale:', self.throttle_scale) - - if button == 'base2' and button_state == 1: - """ - increase steering scale - """ - self.steering_scale = round(min(1.0, self.steering_scale + 0.05), 2) - print('steering_scale:', self.steering_scale) - - if button == 'pinkie' and button_state == 1: - """ - decrease steering scale - """ - self.steering_scale = round(max(0.0, self.steering_scale - 0.05), 2) - print('steering_scale:', self.steering_scale) - - if button == 'top' and button_state == 1: - """ - toggle constant throttle - """ - if self.constant_throttle: - self.constant_throttle = False - self.throttle = 0 - self.on_throttle_changes() - else: - self.constant_throttle = True - self.throttle = self.max_throttle - self.on_throttle_changes() - print('constant_throttle:', self.constant_throttle) - - time.sleep(self.poll_delay) - - def run_threaded(self, img_arr=None): - self.img_arr = img_arr - return self.angle, self.throttle, self.mode, self.recording - - def run(self, img_arr=None): - raise Exception("We expect for this part to be run with the threaded=True argument.") - return False - - def shutdown(self): - self.running = False - time.sleep(0.5) - diff --git a/donkeycar/parts/datastore.py b/donkeycar/parts/datastore.py index 5246e1063..23fa74810 100644 --- a/donkeycar/parts/datastore.py +++ b/donkeycar/parts/datastore.py @@ -108,7 +108,6 @@ def get_file_ix(file_name): return nums - @property def inputs(self): return list(self.meta['inputs']) @@ -142,7 +141,7 @@ def get_num_records(self): def make_record_paths_absolute(self, record_dict): d = {} for k, v in record_dict.items(): - if type(v) == str: #filename + if type(v) == str: # filename if '.' in v: v = os.path.join(self.path, v) d[k] = v @@ -162,7 +161,7 @@ def check(self, fix=False): self.get_record(ix) except: problems = True - if fix == False: + if fix is False: logger.warning('problems with record {} : {}'.format(ix, self.path)) else: logger.warning('problems with record {}, removing: {}'.format(ix, self.path)) @@ -194,13 +193,13 @@ def put_record(self, data): elif typ is 'image': name = self.make_file_name(key, ext='.jpg') val.save(os.path.join(self.path, name)) - json_data[key]=name + json_data[key] = name elif typ == 'image_array': img = Image.fromarray(np.uint8(val)) name = self.make_file_name(key, ext='.jpg') img.save(os.path.join(self.path, name)) - json_data[key]=name + json_data[key] = name else: msg = 'Tub does not know what to do with this type {}'.format(typ) @@ -211,8 +210,10 @@ def put_record(self, data): return self.current_ix def get_json_record_path(self, ix): - #return os.path.join(self.path, 'record_'+str(ix).zfill(6)+'.json') #fill zeros - return os.path.join(self.path, 'record_' + str(ix) + '.json') #don't fill zeros + # fill zeros + # return os.path.join(self.path, 'record_'+str(ix).zfill(6)+'.json') + # don't fill zeros + return os.path.join(self.path, 'record_' + str(ix) + '.json') def get_json_record(self, ix): path = self.get_json_record_path(ix) @@ -236,7 +237,7 @@ def get_record(self, ix): return data def read_record(self, record_dict): - data={} + data = {} for key, val in record_dict.items(): typ = self.get_input_type(key) @@ -249,7 +250,7 @@ def read_record(self, record_dict): return data def make_file_name(self, key, ext='.png'): - #name = '_'.join([str(self.current_ix).zfill(6), key, ext]) + # name = '_'.join([str(self.current_ix).zfill(6), key, ext]) name = '_'.join([str(self.current_ix), key, ext]) # don't fill zeros name = name = name.replace('/', '-') return name @@ -338,7 +339,10 @@ def get_batch_gen(self, keys=None, batch_size=128, record_transform=None, shuffl batch_arrays[k] = arr yield batch_arrays - def get_train_gen(self, X_keys, Y_keys, batch_size=128, record_transform=None, df=None): + def get_train_gen(self, X_keys, Y_keys, + batch_size=128, + record_transform=None, + df=None): """ Returns a training/validation set. @@ -656,4 +660,4 @@ def get_num_tubs(self): return len(self.tubs) def get_num_records(self): - return len(self.df) \ No newline at end of file + return len(self.df) diff --git a/donkeycar/parts/encoder.py b/donkeycar/parts/encoder.py deleted file mode 100644 index 041e89ab6..000000000 --- a/donkeycar/parts/encoder.py +++ /dev/null @@ -1,133 +0,0 @@ -""" -Rotary Encoder -""" - -from datetime import datetime -from donkeycar.parts.teensy import TeensyRCin -import re -import time - -class AStarSpeed: - def __init__(self): - self.speed = 0 - self.linaccel = None - - self.sensor = TeensyRCin(0); - - self.on = True - - def update(self): - encoder_pattern = re.compile('^E ([-0-9]+)( ([-0-9]+))?( ([-0-9]+))?$') - linaccel_pattern = re.compile('^L ([-.0-9]+) ([-.0-9]+) ([-.0-9]+) ([-0-9]+)$') - - while self.on: - start = datetime.now() - - l = self.sensor.astar_readline() - while l: - m = encoder_pattern.match(l.decode('utf-8')) - - if m: - value = int(m.group(1)) - # rospy.loginfo("%s: Receiver E got %d" % (self.node_name, value)) - # Speed - # 40 ticks/wheel rotation, - # circumfence 0.377m - # every 0.1 seconds - if len(m.group(3)) > 0: - period = 0.001 * int(m.group(3)) - else: - period = 0.1 - - self.speed = 0.377 * (float(value) / 40) / period # now in m/s - else: - m = linaccel_pattern.match(l.decode('utf-8')) - - if m: - la = { 'x': float(m.group(1)), 'y': float(m.group(2)), 'z': float(m.group(3)) } - - self.linaccel = la - print("mw linaccel= " + str(self.linaccel)) - - l = self.sensor.astar_readline() - - stop = datetime.now() - s = 0.1 - (stop - start).total_seconds() - if s > 0: - time.sleep(s) - - def run_threaded(self): - return self.speed # , self.linaccel - - def shutdown(self): - # indicate that the thread should be stopped - self.on = False - print('stopping AStarSpeed') - time.sleep(.5) - - -class RotaryEncoder(): - def __init__(self, mm_per_tick=0.306096, pin=27, poll_delay=0.0166, debug=False): - import RPi.GPIO as GPIO - GPIO.setmode(GPIO.BCM) - GPIO.setup(pin, GPIO.IN) - GPIO.add_event_detect(pin, GPIO.RISING, callback=self.isr) - - # initialize the odometer values - self.m_per_tick = mm_per_tick / 1000.0 - self.poll_delay = poll_delay - self.meters = 0 - self.last_time = time.time() - self.meters_per_second = 0 - self.counter = 0 - self.on = True - self.debug = debug - - def isr(self, channel): - self.counter += 1 - - def update(self): - # keep looping infinitely until the thread is stopped - while(self.on): - - #save the ticks and reset the counter - ticks = self.counter - self.counter = 0 - - #save off the last time interval and reset the timer - start_time = self.last_time - end_time = time.time() - self.last_time = end_time - - #calculate elapsed time and distance traveled - seconds = end_time - start_time - distance = ticks * self.m_per_tick - velocity = distance / seconds - - #update the odometer values - self.meters += distance - self.meters_per_second = velocity - - #console output for debugging - if(self.debug): - print('seconds:', seconds) - print('distance:', distance) - print('velocity:', velocity) - - print('distance (m):', round(self.meters, 4)) - print('velocity (m/s):', self.meters_per_second) - - time.sleep(self.poll_delay) - - def run_threaded(self): - return self.meters, self.meters_per_second - - def shutdown(self): - # indicate that the thread should be stopped - self.on = False - print('stopping Rotary Encoder') - print('top speed (m/s):', self.top_speed) - time.sleep(.5) - - import RPi.GPIO as GPIO - GPIO.cleanup() diff --git a/donkeycar/parts/imu.py b/donkeycar/parts/imu.py deleted file mode 100755 index 196afc52d..000000000 --- a/donkeycar/parts/imu.py +++ /dev/null @@ -1,53 +0,0 @@ -import time - -class Mpu6050: - """ - Installation: - sudo apt install python3-smbus - or - sudo apt-get install i2c-tools libi2c-dev python-dev python3-dev - git clone https://github.com/pimoroni/py-smbus.git - cd py-smbus/library - python setup.py build - sudo python setup.py install - - pip install mpu6050-raspberrypi - """ - - def __init__(self, addr=0x68, poll_delay=0.0166): - from mpu6050 import mpu6050 - self.sensor = mpu6050(addr) - self.accel = { 'x' : 0., 'y' : 0., 'z' : 0. } - self.gyro = { 'x' : 0., 'y' : 0., 'z' : 0. } - self.temp = 0. - self.poll_delay = poll_delay - self.on = True - - def update(self): - while self.on: - self.poll() - time.sleep(self.poll_delay) - - def poll(self): - self.accel, self.gyro, self.temp = self.sensor.get_all_data() - - def run_threaded(self): - return self.accel['x'], self.accel['y'], self.accel['z'], self.gyro['x'], self.gyro['y'], self.gyro['z'], self.temp - - def run(self): - self.poll() - return self.accel['x'], self.accel['y'], self.accel['z'], self.gyro['x'], self.gyro['y'], self.gyro['z'], self.temp - - def shutdown(self): - self.on = False - - -if __name__ == "__main__": - iter = 0 - p = Mpu6050() - while iter < 100: - data = p.run() - print(data) - time.sleep(0.1) - iter += 1 - diff --git a/donkeycar/parts/keras.py b/donkeycar/parts/keras.py index 80546ab2f..66b5fadb2 100644 --- a/donkeycar/parts/keras.py +++ b/donkeycar/parts/keras.py @@ -9,11 +9,9 @@ from tensorflow.python.keras.layers import Input from tensorflow.python.keras.models import Model, load_model from tensorflow.python.keras.layers import Convolution2D -from tensorflow.python.keras.layers import Dropout, Flatten, Dense, Cropping2D, Lambda +from tensorflow.python.keras.layers import Dropout, Flatten, Dense from tensorflow.python.keras.callbacks import ModelCheckpoint, EarlyStopping -from donkeycar import util - class KerasPilot: @@ -61,28 +59,13 @@ def train(self, train_gen, val_gen, return hist -class KerasCategorical(KerasPilot): - def __init__(self, model=None, *args, **kwargs): - super(KerasCategorical, self).__init__(*args, **kwargs) - if model: - self.model = model - else: - self.model = default_categorical() - - def run(self, img_arr): - img_arr = img_arr.reshape((1,) + img_arr.shape) - angle_binned, throttle = self.model.predict(img_arr) - angle_unbinned = util.data.linear_unbin(angle_binned[0]) - return angle_unbinned, throttle[0][0] - - class KerasLinear(KerasPilot): def __init__(self, model=None, num_outputs=None, *args, **kwargs): super(KerasLinear, self).__init__(*args, **kwargs) if model: self.model = model elif num_outputs is not None: - self.model = default_n_linear(num_outputs) + self.model = default_linear() else: self.model = default_linear() @@ -95,119 +78,27 @@ def run(self, img_arr): return steering[0][0], throttle[0][0] -def default_categorical(): - img_in = Input(shape=(120, 160, 3), - name='img_in') # First layer, input layer, Shape comes from camera.py resolution, RGB - x = img_in - x = Convolution2D(24, (5, 5), strides=(2, 2), activation='relu')( - x) # 24 features, 5 pixel x 5 pixel kernel (convolution, feauture) window, 2wx2h stride, relu activation - x = Convolution2D(32, (5, 5), strides=(2, 2), activation='relu')( - x) # 32 features, 5px5p kernel window, 2wx2h stride, relu activatiion - x = Convolution2D(64, (5, 5), strides=(2, 2), activation='relu')( - x) # 64 features, 5px5p kernal window, 2wx2h stride, relu - x = Convolution2D(64, (3, 3), strides=(2, 2), activation='relu')( - x) # 64 features, 3px3p kernal window, 2wx2h stride, relu - x = Convolution2D(64, (3, 3), strides=(1, 1), activation='relu')( - x) # 64 features, 3px3p kernal window, 1wx1h stride, relu - - # Possibly add MaxPooling (will make it less sensitive to position in image). Camera angle fixed, so may not to be needed - - x = Flatten(name='flattened')(x) # Flatten to 1D (Fully connected) - x = Dense(100, activation='relu')(x) # Classify the data into 100 features, make all negatives 0 - x = Dropout(.1)(x) # Randomly drop out (turn off) 10% of the neurons (Prevent overfitting) - x = Dense(50, activation='relu')(x) # Classify the data into 50 features, make all negatives 0 - x = Dropout(.1)(x) # Randomly drop out 10% of the neurons (Prevent overfitting) - # categorical output of the angle - angle_out = Dense(15, activation='softmax', name='angle_out')( - x) # Connect every input with every output and output 15 hidden units. Use Softmax to give percentage. 15 categories and find best one based off percentage 0.0-1.0 - - # continous output of throttle - throttle_out = Dense(1, activation='relu', name='throttle_out')(x) # Reduce to 1 number, Positive number only - - model = Model(inputs=[img_in], outputs=[angle_out, throttle_out]) - model.compile(optimizer='adam', - loss={'angle_out': 'categorical_crossentropy', - 'throttle_out': 'mean_absolute_error'}, - loss_weights={'angle_out': 0.9, 'throttle_out': .01}) - - return model - - -from tensorflow.python.keras import backend as K - - -def linear_unbin_layer(tnsr): - bin = K.constant((2 / 14), dtype='float32') - norm = K.constant(1, dtype='float32') - - b = K.cast(K.argmax(tnsr), dtype='float32') - a = b - norm - # print('linear_unbin_layer out: {}'.format(a)) - return a - - -def default_catlin(): - """ - Categorial Steering output before linear conversion. - :return: - """ - img_in = Input(shape=(120, 160, 3), - name='img_in') # First layer, input layer, Shape comes from camera.py resolution, RGB - x = img_in - x = Convolution2D(24, (5, 5), strides=(2, 2), activation='relu')( - x) # 24 features, 5 pixel x 5 pixel kernel (convolution, feauture) window, 2wx2h stride, relu activation - x = Convolution2D(32, (5, 5), strides=(2, 2), activation='relu')( - x) - x = Convolution2D(64, (5, 5), strides=(2, 2), activation='relu')( - x) # 64 features, 5px5p kernal window, 2wx2h stride, relu - x = Convolution2D(64, (3, 3), strides=(2, 2), activation='relu')( - x) # 64 features, 3px3p kernal window, 2wx2h stride, relu - x = Convolution2D(64, (3, 3), strides=(1, 1), activation='relu')( - x) # 64 features, 3px3p kernal window, 1wx1h stride, relu - - # Possibly add MaxPooling (will make it less sensitive to position in image). Camera angle fixed, so may not to be needed - - x = Flatten(name='flattened')(x) # Flatten to 1D (Fully connected) - x = Dense(100, activation='relu')(x) # Classify the data into 100 features, make all negatives 0 - x = Dropout(.1)(x) # Randomly drop out (turn off) 10% of the neurons (Prevent overfitting) - x = Dense(50, activation='relu')(x) # Classify the data into 50 features, make all negatives 0 - x = Dropout(.1)(x) # Randomly drop out 10% of the neurons (Prevent overfitting) - # categorical output of the angle - angle_cat_out = Dense(15, activation='softmax', name='angle_cat_out')(x) - angle_out = Dense(1, activation='sigmoid', name='angle_out')(angle_cat_out) - # angle_out = Lambda(linear_unbin_layer, output_shape=(1,1, ), name='angle_out')(angle_cat_out) - - # continuous output of throttle - throttle_out = Dense(1, activation='relu', name='throttle_out')(x) # Reduce to 1 number, Positive number only - - model = Model(inputs=[img_in], outputs=[angle_out, throttle_out]) - model.compile(optimizer='adam', - loss={'angle_out': 'mean_squared_error', - 'throttle_out': 'mean_absolute_error'}, - loss_weights={'angle_out': 0.9, 'throttle_out': .01}) - - return model - - def default_linear(): img_in = Input(shape=(120, 160, 3), name='img_in') x = img_in - x = Convolution2D(24, (5, 5), strides=(2, 2), activation='relu')(x) - x = Convolution2D(32, (5, 5), strides=(2, 2), activation='relu')(x) - x = Convolution2D(64, (5, 5), strides=(2, 2), activation='relu')(x) - x = Convolution2D(64, (3, 3), strides=(2, 2), activation='relu')(x) - x = Convolution2D(64, (3, 3), strides=(1, 1), activation='relu')(x) + + # Convolution2D class name is an alias for Conv2D + x = Convolution2D(filters=24, kernel_size=(5, 5), strides=(2, 2), activation='relu')(x) + x = Convolution2D(filters=32, kernel_size=(5, 5), strides=(2, 2), activation='relu')(x) + x = Convolution2D(filters=64, kernel_size=(5, 5), strides=(2, 2), activation='relu')(x) + x = Convolution2D(filters=64, kernel_size=(3, 3), strides=(2, 2), activation='relu')(x) + x = Convolution2D(filters=64, kernel_size=(3, 3), strides=(1, 1), activation='relu')(x) x = Flatten(name='flattened')(x) - x = Dense(100, activation='linear')(x) - x = Dropout(.1)(x) - x = Dense(50, activation='linear')(x) - x = Dropout(.1)(x) + x = Dense(units=100, activation='linear')(x) + x = Dropout(rate=.1)(x) + x = Dense(units=50, activation='linear')(x) + x = Dropout(rate=.1)(x) # categorical output of the angle - angle_out = Dense(1, activation='linear', name='angle_out')(x) + angle_out = Dense(units=1, activation='linear', name='angle_out')(x) # continous output of throttle - throttle_out = Dense(1, activation='linear', name='throttle_out')(x) + throttle_out = Dense(units=1, activation='linear', name='throttle_out')(x) model = Model(inputs=[img_in], outputs=[angle_out, throttle_out]) @@ -217,33 +108,3 @@ def default_linear(): loss_weights={'angle_out': 0.5, 'throttle_out': .5}) return model - - -def default_n_linear(num_outputs): - img_in = Input(shape=(120, 160, 3), name='img_in') - x = img_in - x = Cropping2D(cropping=((60, 0), (0, 0)))(x) # trim 60 pixels off top - x = Lambda(lambda x: x / 127.5 - 1.)(x) # normalize and re-center - x = Convolution2D(24, (5, 5), strides=(2, 2), activation='relu')(x) - x = Convolution2D(32, (5, 5), strides=(2, 2), activation='relu')(x) - x = Convolution2D(64, (5, 5), strides=(1, 1), activation='relu')(x) - x = Convolution2D(64, (3, 3), strides=(1, 1), activation='relu')(x) - x = Convolution2D(64, (3, 3), strides=(1, 1), activation='relu')(x) - - x = Flatten(name='flattened')(x) - x = Dense(100, activation='relu')(x) - x = Dropout(.1)(x) - x = Dense(50, activation='relu')(x) - x = Dropout(.1)(x) - - outputs = [] - - for i in range(num_outputs): - outputs.append(Dense(1, activation='linear', name='n_outputs' + str(i))(x)) - - model = Model(inputs=[img_in], outputs=outputs) - - model.compile(optimizer='adam', - loss='mse') - - return model diff --git a/donkeycar/parts/lidar.py b/donkeycar/parts/lidar.py deleted file mode 100644 index 9506339f1..000000000 --- a/donkeycar/parts/lidar.py +++ /dev/null @@ -1,29 +0,0 @@ -""" -Lidar -""" - -import time -import numpy as np - - -class RPLidar(): - def __init__(self, port='/dev/ttyUSB0'): - from rplidar import RPLidar - self.port = port - self.frame = np.zeros(shape=365) - self.lidar = RPLidar(self.port) - self.lidar.clear_input() - time.sleep(1) - self.on = True - - - def update(self): - self.measurements = self.lidar.iter_measurments(500) - for new_scan, quality, angle, distance in self.measurements: - angle = int(angle) - self.frame[angle] = 2*distance/3 + self.frame[angle]/3 - if not self.on: - break - - def run_threaded(self): - return self.frame diff --git a/donkeycar/parts/simulation.py b/donkeycar/parts/simulation.py index 54d085dcc..94e9c0a84 100644 --- a/donkeycar/parts/simulation.py +++ b/donkeycar/parts/simulation.py @@ -1,147 +1,11 @@ #!/usr/bin/env python3 # -*- coding: utf-8 -*- """ -Created on Sun Jun 25 17:30:28 2017 - -@author: wroscoe +Parts to try donkeycar without a physical car. """ - - - -import base64 import random import numpy as np -import socketio -import eventlet -import eventlet.wsgi -from PIL import Image -from flask import Flask -from io import BytesIO -import time - - -class FPSTimer(object): - def __init__(self): - self.t = time.time() - self.iter = 0 - - def reset(self): - self.t = time.time() - self.iter = 0 - - def on_frame(self): - self.iter += 1 - if self.iter == 100: - e = time.time() - print('fps', 100.0 / (e - self.t)) - self.t = time.time() - self.iter = 0 - - -class SteeringServer(object): - """ - A SocketIO based Websocket server designed to integrate with - the Donkey Sim Unity project. Check the donkey branch of - https://github.com/tawnkramer/sdsandbox for source of simulator. - Prebuilt simulators available: - Windows: https://drive.google.com/file/d/0BxSsaxmEV-5YRC1ZWHZ4Y1dZTkE/view?usp=sharing - """ - def __init__(self, _sio, kpart, top_speed=4.0, image_part=None, steering_scale=1.0): - self.model = None - self.timer = FPSTimer() - self.sio = _sio - # TODO: convert this flask app to a tornado app to minimize dependencies. - self.app = Flask(__name__) - self.kpart = kpart - self.image_part = image_part - self.steering_scale = steering_scale - self.top_speed = top_speed - - def throttle_control(self, last_steering, last_throttle, speed, nn_throttle): - """ - super basic throttle control, derive from this Server and override as needed - """ - if speed < self.top_speed: - return 0.3 - - return 0.0 - - def telemetry(self, sid, data): - """ - Callback when we get new data from Unity simulator. - We use it to process the image, do a forward inference, - then send controls back to client. - Takes sid (?) and data, a dictionary of json elements. - """ - if data: - # The current steering angle of the car - last_steering = float(data["steering_angle"]) - - # The current throttle of the car - last_throttle = float(data["throttle"]) - - # The current speed of the car - speed = float(data["speed"]) - - # The current image from the center camera of the car - imgString = data["image"] - - # decode string based data into bytes, then to Image - image = Image.open(BytesIO(base64.b64decode(imgString))) - - # then as numpy array - image_array = np.asarray(image) - - # optional change to pre-preocess image before NN sees it - if self.image_part is not None: - image_array = self.image_part.run(image_array) - - # forward pass - inference - steering, throttle = self.kpart.run(image_array) - - # filter throttle here, as our NN doesn't always do a greate job - throttle = self.throttle_control(last_steering, last_throttle, speed, throttle) - - # simulator will scale our steering based on it's angle based input. - # but we have an opportunity for more adjustment here. - steering *= self.steering_scale - - # send command back to Unity simulator - self.send_control(steering, throttle) - - else: - # NOTE: DON'T EDIT THIS. - self.sio.emit('manual', data={}, skip_sid=True) - - self.timer.on_frame() - - def connect(self, sid, environ): - print("connect ", sid) - self.timer.reset() - self.send_control(0, 0) - - def send_control(self, steering_angle, throttle): - self.sio.emit( - "steer", - data={ - 'steering_angle': steering_angle.__str__(), - 'throttle': throttle.__str__() - }, - skip_sid=True) - - def go(self, address): - - # wrap Flask application with engineio's middleware - self.app = socketio.Middleware(self.sio, self.app) - - # deploy as an eventlet WSGI server - try: - eventlet.wsgi.server(eventlet.listen(address), self.app) - - except KeyboardInterrupt: - # unless some hits Ctrl+C and then we get this interrupt - print('stopping') class MovingSquareTelemetry: @@ -149,8 +13,8 @@ class MovingSquareTelemetry: Generator of cordinates of a bouncing moving square for simulations. """ def __init__(self, max_velocity=29, - x_min = 10, x_max=150, - y_min = 10, y_max=110): + x_min=10, x_max=150, + y_min=10, y_max=110): self.velocity = random.random() * max_velocity @@ -166,11 +30,11 @@ def __init__(self, max_velocity=29, self.tel = self.x, self.y def run(self): - #move + # move self.x += self.x_direction * self.velocity self.y += self.y_direction * self.velocity - #make square bounce off walls + # make square bounce off walls if self.y < self.y_min or self.y > self.y_max: self.y_direction *= -1 if self.x < self.x_min or self.x > self.x_max: @@ -192,13 +56,12 @@ class SquareBoxCamera: This can be used to test if a learning algorithm can learn. """ - def __init__(self, resolution=(120,160), box_size=4, color=(255, 0, 0)): + def __init__(self, resolution=(120, 160), box_size=4, color=(255, 0, 0)): self.resolution = resolution self.box_size = box_size self.color = color - - def run(self, x,y, box_size=None, color=None): + def run(self, x, y, box_size=None, color=None): """ Create an image of a square box at a given coordinates. """ @@ -206,7 +69,5 @@ def run(self, x,y, box_size=None, color=None): color = color or self.color frame = np.zeros(shape=self.resolution + (3,)) frame[y - radius: y + radius, - x - radius: x + radius, :] = color + x - radius: x + radius, :] = color return frame - - diff --git a/donkeycar/parts/teensy.py b/donkeycar/parts/teensy.py deleted file mode 100644 index 5fe668a3f..000000000 --- a/donkeycar/parts/teensy.py +++ /dev/null @@ -1,85 +0,0 @@ -from datetime import datetime -import donkeycar as dk -import re -import time - -class TeensyRCin: - def __init__(self): - self.inSteering = 0.0 - self.inThrottle = 0.0 - - self.sensor = dk.parts.Teensy(0); - - TeensyRCin.LEFT_ANGLE = -1.0 - TeensyRCin.RIGHT_ANGLE = 1.0 - TeensyRCin.MIN_THROTTLE = -1.0 - TeensyRCin.MAX_THROTTLE = 1.0 - - TeensyRCin.LEFT_PULSE = 496.0 - TeensyRCin.RIGHT_PULSE = 242.0 - TeensyRCin.MAX_PULSE = 496.0 - TeensyRCin.MIN_PULSE = 242.0 - - - self.on = True - - def map_range(self, x, X_min, X_max, Y_min, Y_max): - """ - Linear mapping between two ranges of values - """ - X_range = X_max - X_min - Y_range = Y_max - Y_min - XY_ratio = X_range/Y_range - - return ((x-X_min) / XY_ratio + Y_min) - - def update(self): - rcin_pattern = re.compile('^I +([.0-9]+) +([.0-9]+).*$') - - while self.on: - start = datetime.now() - - l = self.sensor.teensy_readline() - - while l: - # print("mw TeensyRCin line= " + l.decode('utf-8')) - m = rcin_pattern.match(l.decode('utf-8')) - - if m: - i = float(m.group(1)) - if i == 0.0: - self.inSteering = 0.0 - else: - i = i / (1000.0 * 1000.0) # in seconds - i *= self.sensor.frequency * 4096.0 - self.inSteering = self.map_range(i, - TeensyRCin.LEFT_PULSE, TeensyRCin.RIGHT_PULSE, - TeensyRCin.LEFT_ANGLE, TeensyRCin.RIGHT_ANGLE) - - k = float(m.group(2)) - if k == 0.0: - self.inThrottle = 0.0 - else: - k = k / (1000.0 * 1000.0) # in seconds - k *= self.sensor.frequency * 4096.0 - self.inThrottle = self.map_range(k, - TeensyRCin.MIN_PULSE, TeensyRCin.MAX_PULSE, - TeensyRCin.MIN_THROTTLE, TeensyRCin.MAX_THROTTLE) - - # print("matched %.1f %.1f %.1f %.1f" % (i, self.inSteering, k, self.inThrottle)) - l = self.sensor.teensy_readline() - - stop = datetime.now() - s = 0.01 - (stop - start).total_seconds() - if s > 0: - time.sleep(s) - - def run_threaded(self): - return self.inSteering, self.inThrottle - - def shutdown(self): - # indicate that the thread should be stopped - self.on = False - print('stopping TeensyRCin') - time.sleep(.5) - diff --git a/donkeycar/parts/transform.py b/donkeycar/parts/transform.py index 225d0dcb9..fae951a98 100644 --- a/donkeycar/parts/transform.py +++ b/donkeycar/parts/transform.py @@ -2,6 +2,7 @@ import time + class Lambda: """ Wraps a function into a donkey part. @@ -19,11 +20,10 @@ def shutdown(self): return - - class PIDController: """ Performs a PID computation and returns a control value. - This is based on the elapsed time (dt) and the current value of the process variable + This is based on the elapsed time (dt) and the current value + of the process variable (i.e. the thing we're measuring and trying to change). https://github.com/chrisspen/pid_controller/blob/master/pid_controller/pid.py """ diff --git a/donkeycar/parts/web_controller/__init__.py b/donkeycar/parts/web_controller/__init__.py index e69de29bb..a8763ec5d 100644 --- a/donkeycar/parts/web_controller/__init__.py +++ b/donkeycar/parts/web_controller/__init__.py @@ -0,0 +1 @@ +from .web import LocalWebController \ No newline at end of file diff --git a/donkeycar/parts/web_controller/web.py b/donkeycar/parts/web_controller/web.py index cac7d6127..f16c1eb2b 100644 --- a/donkeycar/parts/web_controller/web.py +++ b/donkeycar/parts/web_controller/web.py @@ -26,6 +26,7 @@ class LocalWebController(tornado.web.Application): port = 8887 + def __init__(self, use_chaos=False): """ Create and publish variables needed on many of @@ -45,7 +46,7 @@ def __init__(self, use_chaos=False): self.chaos_on = False self.chaos_counter = 0 - self.chaos_frequency = 1000 #frames + self.chaos_frequency = 1000 # frames self.chaos_duration = 10 if use_chaos: diff --git a/donkeycar/templates/donkey2.py b/donkeycar/templates/donkey2.py index e776921d9..1f97e99f0 100644 --- a/donkeycar/templates/donkey2.py +++ b/donkeycar/templates/donkey2.py @@ -16,14 +16,12 @@ from docopt import docopt import donkeycar as dk - -#import parts from donkeycar.parts.camera import PiCamera from donkeycar.parts.transform import Lambda -from donkeycar.parts.keras import KerasCategorical +from donkeycar.parts.keras import KerasLinear from donkeycar.parts.actuator import PCA9685, PWMSteering, PWMThrottle from donkeycar.parts.datastore import TubGroup, TubWriter -from donkeycar.parts.controller import LocalWebController, JoystickController +from donkeycar.parts.web_controller import LocalWebController from donkeycar.parts.clock import Timestamp @@ -41,7 +39,7 @@ def drive(cfg, model_path=None, use_joystick=False, use_chaos=False): V = dk.vehicle.Vehicle() clock = Timestamp() - V.add(clock, outputs='timestamp') + V.add(clock, outputs=['timestamp']) cam = PiCamera(resolution=cfg.CAMERA_RESOLUTION) V.add(cam, outputs=['cam/image_array'], threaded=True) @@ -69,17 +67,19 @@ def pilot_condition(mode): return True pilot_condition_part = Lambda(pilot_condition) - V.add(pilot_condition_part, inputs=['user/mode'], - outputs=['run_pilot']) + V.add(pilot_condition_part, + inputs=['user/mode'], + outputs=['run_pilot']) # Run the pilot if the mode is not user. - kl = KerasCategorical() + kl = KerasLinear() if model_path: kl.load(model_path) - V.add(kl, inputs=['cam/image_array'], - outputs=['pilot/angle', 'pilot/throttle'], - run_condition='run_pilot') + V.add(kl, + inputs=['cam/image_array'], + outputs=['pilot/angle', 'pilot/throttle'], + run_condition='run_pilot') # Choose what inputs should change the car. def drive_mode(mode, @@ -103,7 +103,7 @@ def drive_mode(mode, steering_controller = PCA9685(cfg.STEERING_CHANNEL) steering = PWMSteering(controller=steering_controller, left_pulse=cfg.STEERING_LEFT_PWM, - right_pulse=cfg.STEERING_RIGHT_PWM) + right_pulse=cfg.STEERING_RIGHT_PWM) throttle_controller = PCA9685(cfg.THROTTLE_CHANNEL) throttle = PWMThrottle(controller=throttle_controller, @@ -118,9 +118,9 @@ def drive_mode(mode, inputs = ['cam/image_array', 'user/angle', 'user/throttle', 'user/mode', 'timestamp'] types = ['image_array', 'float', 'float', 'str', 'str'] - #multiple tubs - #th = TubHandler(path=cfg.DATA_PATH) - #tub = th.new_tub_writer(inputs=inputs, types=types) + # multiple tubs + # th = TubHandler(path=cfg.DATA_PATH) + # tub = th.new_tub_writer(inputs=inputs, types=types) # single tub tub = TubWriter(path=cfg.TUB_PATH, inputs=inputs, types=types) @@ -131,29 +131,17 @@ def drive_mode(mode, max_loop_count=cfg.MAX_LOOPS) - - -def train(cfg, tub_names, new_model_path, base_model_path=None ): +def train(cfg, tub_names, new_model_path, base_model_path=None): """ use the specified data in tub_names to train an artifical neural network saves the output trained model as model_name """ X_keys = ['cam/image_array'] y_keys = ['user/angle', 'user/throttle'] - def train_record_transform(record): - """ convert categorical steering to linear and apply image augmentations """ - record['user/angle'] = dk.util.data.linear_bin(record['user/angle']) - # TODO add augmentation that doesn't use opencv - return record - - def val_record_transform(record): - """ convert categorical steering to linear """ - record['user/angle'] = dk.util.data.linear_bin(record['user/angle']) - return record new_model_path = os.path.expanduser(new_model_path) - kl = KerasCategorical() + kl = KerasLinear() if base_model_path is not None: base_model_path = os.path.expanduser(base_model_path) kl.load(base_model_path) @@ -163,8 +151,6 @@ def val_record_transform(record): tub_names = os.path.join(cfg.DATA_PATH, '*') tubgroup = TubGroup(tub_names) train_gen, val_gen = tubgroup.get_train_val_gen(X_keys, y_keys, - train_record_transform=train_record_transform, - val_record_transform=val_record_transform, batch_size=cfg.BATCH_SIZE, train_frac=cfg.TRAIN_TEST_SPLIT) @@ -187,7 +173,7 @@ def val_record_transform(record): cfg = dk.load_config() if args['drive']: - drive(cfg, model_path = args['--model'], use_joystick=args['--js'], use_chaos=args['--chaos']) + drive(cfg, model_path=args['--model'], use_joystick=args['--js'], use_chaos=args['--chaos']) elif args['train']: tub = args['--tub'] diff --git a/donkeycar/templates/square.py b/donkeycar/templates/square.py index 1f95d13a6..874f495f4 100644 --- a/donkeycar/templates/square.py +++ b/donkeycar/templates/square.py @@ -21,8 +21,8 @@ from donkeycar.parts.datastore import TubGroup, TubWriter from donkeycar.parts.transform import Lambda from donkeycar.parts.simulation import SquareBoxCamera -from donkeycar.parts.controller import LocalWebController -from donkeycar.parts.keras import KerasCategorical +from donkeycar.parts.web_controller import LocalWebController +from donkeycar.parts.keras import KerasLinear from donkeycar.parts.clock import Timestamp log_path = os.path.join(os.path.dirname(os.path.abspath(__file__)), 'sq.log') @@ -62,7 +62,7 @@ def pilot_condition(mode): V.add(pilot_condition_part, inputs=['user/mode'], outputs=['run_pilot']) # Run the pilot if the mode is not user. - kl = KerasCategorical() + kl = KerasLinear() if model_path: kl.load(model_path) diff --git a/donkeycar/templates/tk1.py b/donkeycar/templates/tk1.py deleted file mode 100644 index 5d7fa4d4a..000000000 --- a/donkeycar/templates/tk1.py +++ /dev/null @@ -1,46 +0,0 @@ -# -*- coding: utf-8 -*- - -""" -Script to drive a donkey car using a webserver hosted on the vehicle. - -""" -from datetime import datetime -import donkeycar as dk - -V = dk.vehicle.Vehicle() - -cam = dk.parts.Webcam() -V.add(cam, outputs = [ 'cam/image_array' ], threaded = True) - -rcin_controller = dk.parts.TeensyRCin() -V.add(rcin_controller, outputs = [ 'rcin/angle', 'rcin/throttle' ], threaded = True) - -speed_controller = dk.parts.AStarSpeed() -V.add(speed_controller, outputs = [ 'odo/speed' ], threaded = True) - -ctr = dk.parts.LocalWebController() -V.add(ctr, - inputs = [ 'cam/image_array', 'rcin/angle', 'rcin/throttle' ], - outputs = [ 'user/angle', 'user/throttle', 'user/mode', 'user/recording' ], - threaded = True) - -steering_controller = dk.parts.Teensy('S') -steering = dk.parts.PWMSteering(controller = steering_controller, - left_pulse = 496, right_pulse = 242) - -throttle_controller = dk.parts.Teensy('T') -throttle = dk.parts.PWMThrottle(controller = throttle_controller, - max_pulse = 496, zero_pulse = 369, min_pulse = 242) - -V.add(steering, inputs = [ 'user/angle', 'user/mode' ]) -V.add(throttle, inputs = [ 'user/throttle', 'user/mode' ]) - -#add tub to save data -path = '~/mydonkey/sessions/' + datetime.now().strftime('%Y_%m_%d__%H_%M_%S') -inputs = [ 'user/angle', 'user/throttle', 'cam/image_array', 'user/mode', 'odo/speed', 'user/recording' ] -types = [ 'float', 'float', 'image_array', 'str', 'float', 'boolean' ] -tub = dk.parts.OriginalWriter(path, inputs = inputs, types = types) -V.add(tub, inputs = inputs) - -#run the vehicle for 20 seconds -V.start(rate_hz = 20) # , max_loop_count = 1000) diff --git a/donkeycar/tests/test_keras.py b/donkeycar/tests/test_keras.py index 110e8c63a..e7bd9d674 100644 --- a/donkeycar/tests/test_keras.py +++ b/donkeycar/tests/test_keras.py @@ -1,28 +1,15 @@ # -*- coding: utf-8 -*- import pytest -from donkeycar.parts.keras import KerasPilot, KerasCategorical -from donkeycar.parts.keras import default_categorical, default_n_linear -# content of ./test_smtpsimple.py +from donkeycar.parts.keras import KerasPilot, KerasLinear +from donkeycar.parts.keras import default_linear -@pytest.fixture -def pilot(): - kp = KerasPilot() - return kp -def test_pilot_types(pilot): - assert 1 == 1 +def test_linear(): + kl = KerasLinear() + assert kl.model is not None - -def test_categorical(): - kc = KerasCategorical() - assert kc.model is not None - -def test_categorical_with_model(): - kc = KerasCategorical(default_categorical()) +def test_linear_with_model(): + kc = KerasLinear(default_linear()) assert kc.model is not None -def test_def_n_linear_model(): - model = default_n_linear(10) - assert model is not None - diff --git a/donkeycar/tests/test_sim.py b/donkeycar/tests/test_sim.py deleted file mode 100644 index a7c3f96e8..000000000 --- a/donkeycar/tests/test_sim.py +++ /dev/null @@ -1,34 +0,0 @@ -#!/usr/bin/env python3 -# -*- coding: utf-8 -*- -""" -Created on Thu Oct 12 2017 - -@author: tawnkramer -""" - - -import unittest -from donkeycar.parts.simulation import SteeringServer, FPSTimer -from donkeycar.parts.keras import KerasCategorical - -class TestSimServer(unittest.TestCase): - - def test_create_sim_server(self): - import socketio - kc = KerasCategorical() - sio = socketio.Server() - assert sio is not None - ss = SteeringServer(_sio=sio, kpart=kc) - assert ss is not None - - def test_timer(self): - tm = FPSTimer() - assert tm is not None - tm.reset() - tm.on_frame() - tm.on_frame() - assert tm.iter == 2 - tm.iter = 100 - tm.on_frame() - - diff --git a/donkeycar/util/web.py b/donkeycar/util/web.py index f9d94ed1d..5ef654104 100644 --- a/donkeycar/util/web.py +++ b/donkeycar/util/web.py @@ -1,7 +1,10 @@ import socket def get_ip_address(): - ip = ([l for l in ([ip for ip in socket.gethostbyname_ex(socket.gethostname())[2] if not ip.startswith("127.")][:1], - [[(s.connect(('8.8.8.8', 53)), s.getsockname()[0], s.close()) for s in - [socket.socket(socket.AF_INET, socket.SOCK_DGRAM)]][0][1]]) if l][0][0]) - return ip + try: + ip = ([l for l in ([ip for ip in socket.gethostbyname_ex(socket.gethostname())[2] if not ip.startswith("127.")][:1], + [[(s.connect(('8.8.8.8', 53)), s.getsockname()[0], s.close()) for s in + [socket.socket(socket.AF_INET, socket.SOCK_DGRAM)]][0][1]]) if l][0][0]) + return ip + except OSError: #occurs when cannot connect to '8.8.8.8' + return "127.0.0.1" #loopback \ No newline at end of file diff --git a/install/pi/install.sh b/install/pi/install.sh index 84474f4c2..1e009e10f 100644 --- a/install/pi/install.sh +++ b/install/pi/install.sh @@ -1,21 +1,5 @@ # Script to install everything needed for donkeycar except the donkeycar library - -# Get witch Pi version -echo "Enter the Pi number (3 or 0)" -read pi_num -if [ $pi_num == 3 ]; then - echo "installing for Pi 3." - tf_file=tensorflow-1.8.0-cp35-none-linux_armv7l.whl -elif [ $pi_num == 0 ]; then - echo "installing for Pi Zero." - tf_file=tensorflow-1.8.0-cp35-none-linux_armv6l.whl -else - echo "Only Pi 3 and Pi Zero are supported." - exit 1 -fi - - #standard updates (5 min) sudo apt update -y sudo apt upgrade -y @@ -45,9 +29,6 @@ sudo apt-get autoremove -y #install redis-server (1 min) sudo apt install redis-server -y -sudo bash make_virtual_env.sh - - #create a python virtualenv (2 min) sudo apt install virtualenv -y virtualenv ~/env --system-site-packages --python python3 @@ -63,8 +44,4 @@ source ~/env/bin/activate pip install pandas #also installs numpy -#install tensorflow (5 min) -echo "Installing Tensorflow" -wget https://github.com/lhelontra/tensorflow-on-arm/releases/download/v1.8.0/${tf_file} -pip install ${tf_file} -rm ${tf_file} \ No newline at end of file +pip install tensorflow==1.9 \ No newline at end of file diff --git a/setup.py b/setup.py index f8ed8b230..86e9caad9 100644 --- a/setup.py +++ b/setup.py @@ -2,13 +2,12 @@ import os - with open("README.md", "r") as fh: long_description = fh.read() setup(name='donkeycar', - version='2.5.1', + version='2.5.2', description='Self driving library for python.', long_description=long_description, long_description_content_type="text/markdown", @@ -36,8 +35,8 @@ ], extras_require={ - 'tf': ['tensorflow>=1.7.0'], - 'tf_gpu': ['tensorflow-gpu>=1.7.0'], + 'tf': ['tensorflow>=1.9.0'], + 'tf_gpu': ['tensorflow-gpu>=1.9.0'], 'pi': [ 'picamera', 'Adafruit_PCA9685', @@ -69,7 +68,6 @@ # 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.4', 'Programming Language :: Python :: 3.5', 'Programming Language :: Python :: 3.6', ],