├── IMG_0615.JPG ├── IMG_0616.JPG ├── IMG_0617.JPG ├── IMG_0618.JPG ├── Jietu20171113-162749.jpg ├── README.md ├── car_control.py ├── collect.py ├── drive.py ├── process_img_to_npz.py ├── train_model.py ├── 使用教程.md └── 电路板的输出电路图.jpg /IMG_0615.JPG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/HadXu/auto-drive/4d0c22235c1f4bcb5d7cce865a9f94c00e0facf8/IMG_0615.JPG -------------------------------------------------------------------------------- /IMG_0616.JPG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/HadXu/auto-drive/4d0c22235c1f4bcb5d7cce865a9f94c00e0facf8/IMG_0616.JPG -------------------------------------------------------------------------------- /IMG_0617.JPG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/HadXu/auto-drive/4d0c22235c1f4bcb5d7cce865a9f94c00e0facf8/IMG_0617.JPG -------------------------------------------------------------------------------- /IMG_0618.JPG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/HadXu/auto-drive/4d0c22235c1f4bcb5d7cce865a9f94c00e0facf8/IMG_0618.JPG -------------------------------------------------------------------------------- /Jietu20171113-162749.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/HadXu/auto-drive/4d0c22235c1f4bcb5d7cce865a9f94c00e0facf8/Jietu20171113-162749.jpg -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # auto-drive 2 | 树莓派自动驾驶小车项目 3 | 4 | 5 | 6 | ![](电路板的输出电路图.jpg) 7 | 8 | ![](IMG_0615.JPG) 9 | 10 | ![](IMG_0616.JPG) 11 | 12 | ![](IMG_0617.JPG) 13 | 14 | ![](IMG_0617.JPG) 15 | -------------------------------------------------------------------------------- /car_control.py: -------------------------------------------------------------------------------- 1 | import RPi.GPIO as GPIO 2 | import time 3 | 4 | 5 | backInput1 = 7 6 | backInput2 = 11 7 | 8 | frontInput1 = 13 9 | frontInput2 = 15 10 | 11 | change = 12 12 | 13 | change2 = 16 14 | 15 | speed = 15 16 | 17 | GPIO.setmode(GPIO.BOARD) 18 | 19 | GPIO.setup(backInput1,GPIO.OUT) 20 | GPIO.setup(backInput2,GPIO.OUT) 21 | GPIO.setup(change,GPIO.OUT) 22 | GPIO.setup(change2,GPIO.OUT) 23 | 24 | 25 | GPIO.setup(frontInput1,GPIO.OUT) 26 | GPIO.setup(frontInput2,GPIO.OUT) 27 | 28 | backMotorPwm = GPIO.PWM(change,100) 29 | backMotorPwm.start(0) 30 | 31 | def carStop(): 32 | GPIO.output(backInput1,GPIO.LOW) 33 | GPIO.output(backInput2,GPIO.LOW) 34 | 35 | def carMoveForward(): 36 | carStraight() 37 | GPIO.output(backInput1,GPIO.LOW) 38 | GPIO.output(backInput2,GPIO.HIGH) 39 | 40 | backMotorPwm.ChangeDutyCycle(speed) 41 | 42 | def carMoveBack(): 43 | GPIO.output(backInput1,GPIO.HIGH) 44 | GPIO.output(backInput2,GPIO.LOW) 45 | backMotorPwm.ChangeDutyCycle(speed) 46 | 47 | 48 | def carStraight(): 49 | GPIO.output(change2,GPIO.LOW) 50 | 51 | def carRight(): 52 | GPIO.output(change2,GPIO.HIGH) 53 | GPIO.output(frontInput1,GPIO.LOW) 54 | GPIO.output(frontInput2,GPIO.HIGH) 55 | 56 | def carLeft(): 57 | GPIO.output(change2,GPIO.HIGH) 58 | GPIO.output(frontInput1,GPIO.HIGH) 59 | GPIO.output(frontInput2,GPIO.LOW) 60 | 61 | 62 | def clean(): 63 | GPIO.cleanup() 64 | backMotorPwm.stop() 65 | 66 | if __name__ == '__main__': 67 | carMoveForward() 68 | 69 | time.sleep(2) 70 | 71 | carStop() 72 | 73 | carStraight() 74 | carLeft() 75 | time.sleep(2) 76 | carStraight() 77 | 78 | clean() 79 | -------------------------------------------------------------------------------- /collect.py: -------------------------------------------------------------------------------- 1 | import io 2 | import car_control 3 | import os 4 | os.environ['SDL_VIDEODRIVER'] = 'x11' 5 | 6 | import pygame 7 | from time import ctime,sleep,time 8 | 9 | import threading 10 | import numpy as np 11 | import picamera 12 | import picamera.array 13 | 14 | global train_labels, train_img, is_capture_running, key 15 | 16 | 17 | class SplitFrames(object): 18 | def __init__(self): 19 | self.frame_num = 0 20 | self.output = None 21 | 22 | def write(self, buf): 23 | global key 24 | if buf.startswith(b'\xff\xd8'): 25 | # Start of new frame; close the old one (if any) and 26 | # open a new output 27 | if self.output: 28 | self.output.close() 29 | self.frame_num += 1 30 | self.output = io.open('images/%s_image%s.jpg'%(key,time()), 'wb') 31 | self.output.write(buf) 32 | 33 | 34 | def pi_capture(): 35 | global train_img,train_labels,is_capture_running,key 36 | 37 | print('start capture') 38 | 39 | is_capture_running = True 40 | 41 | with picamera.PiCamera(resolution=(160,120), framerate=30) as camera: 42 | camera.start_preview() 43 | # Give the camera some warm-up time 44 | sleep(2) 45 | output = SplitFrames() 46 | start = time() 47 | camera.start_recording(output, format='mjpeg') 48 | camera.wait_recording(5) 49 | camera.stop_recording() 50 | finish = time() 51 | print('Captured %d frames at %.2ffps' % ( 52 | output.frame_num, 53 | output.frame_num / (finish - start))) 54 | 55 | print('quit pi camera') 56 | is_capture_running = False 57 | 58 | def my_car_control(): 59 | global is_capture_running,key 60 | 61 | key = 4 62 | 63 | pygame.init() 64 | pygame.display.set_mode((1,1)) 65 | car_control.carStraight() 66 | car_control.carStop() 67 | 68 | sleep(0.1) 69 | print('start control') 70 | 71 | while is_capture_running: 72 | events = pygame.event.get() 73 | for event in events: 74 | if event.type == pygame.KEYDOWN: 75 | key_input = pygame.key.get_pressed() 76 | print(key_input[pygame.K_w],key_input[pygame.K_a],key_input[pygame.K_d]) 77 | 78 | if key_input[pygame.K_w] and not key_input[pygame.K_a] and not key_input[pygame.K_d]: 79 | print('forward') 80 | key = 2 81 | car_control.carMoveForward() 82 | elif key_input[pygame.K_a]: 83 | print('left') 84 | car_control.carLeft() 85 | sleep(0.1) 86 | key = 0 87 | elif key_input[pygame.K_d]: 88 | print('right') 89 | car_control.carRight() 90 | sleep(0.1) 91 | key=1 92 | elif key_input[pygame.K_s]: 93 | print('back') 94 | car_control.carMoveBack() 95 | key = 3 96 | 97 | 98 | 99 | car_control.clean() 100 | 101 | if __name__ == '__main__': 102 | 103 | global train_labels,train_img,key 104 | print('start') 105 | 106 | print('*'*50) 107 | 108 | capture_thread= threading.Thread(target=pi_capture, args=()) 109 | capture_thread.setDaemon(True) 110 | capture_thread.start() 111 | 112 | my_car_control() 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | -------------------------------------------------------------------------------- /drive.py: -------------------------------------------------------------------------------- 1 | import os 2 | import io 3 | import glob 4 | import time 5 | import threading 6 | import picamera 7 | import picamera.array 8 | from PIL import Image 9 | import numpy as np 10 | 11 | import car_control 12 | from keras.models import load_model 13 | import tensorflow as tf 14 | 15 | def get_max_prob_num(predictions_array): 16 | """to get the integer of predition, instead of digit number""" 17 | 18 | prediction_edit = np.zeros([1,5]) 19 | for i in range(0,5): 20 | if predictions_array[0][i] == predictions_array.max(): 21 | prediction_edit[0][i] = 1 22 | return i 23 | return 2 24 | 25 | def control_car(action_num): 26 | """out put the char and call car_control(we used before)""" 27 | 28 | if action_num == 0: 29 | print("Left") 30 | car_control.car_turn_left() 31 | time.sleep(0.25) 32 | elif action_num== 1: 33 | print("Right") 34 | car_control.car_turn_right() 35 | time.sleep(0.25) 36 | elif action_num == 2: 37 | car_control.car_move_forward() 38 | print('Forward') 39 | elif action_num == 3: 40 | car_control.car_move_backward() 41 | print('Backward') 42 | else: 43 | car_control.car_stop() 44 | print('Stop') 45 | 46 | 47 | class ImageProcessor(threading.Thread): 48 | def __init__(self, owner): 49 | super(ImageProcessor, self).__init__() 50 | self.stream = io.BytesIO() 51 | self.event = threading.Event() 52 | self.terminated = False 53 | self.owner = owner 54 | self.start() 55 | 56 | def run(self): 57 | global latest_time, model, graph 58 | # This method runs in a separate thread 59 | while not self.terminated: 60 | # Wait for an image to be written to the stream 61 | if self.event.wait(1): 62 | try: 63 | self.stream.seek(0) 64 | # Read the image and do some processing on it 65 | image = Image.open(self.stream) 66 | image_np = np.array(image) 67 | camera_data_array = np.expand_dims(image_np,axis = 0) 68 | current_time = time.time() 69 | if current_time>latest_time: 70 | if current_time-latest_time>1: 71 | print("*" * 30) 72 | print(current_time-latest_time) 73 | print("*" * 30) 74 | latest_time = current_time 75 | with graph.as_default(): 76 | predictions_array = model.predict(camera_data_array, batch_size=20, verbose=1) 77 | print(predictions_array) 78 | action_num = get_max_prob_num(predictions_array) 79 | control_car(action_num) 80 | # Uncomment this line if you want to save images with prediction as name 81 | # Warning: This will cause latency sometimes. 82 | # image.save('%s_image%s.jpg' % (action_num,time.time())) 83 | finally: 84 | # Reset the stream and event 85 | self.stream.seek(0) 86 | self.stream.truncate() 87 | self.event.clear() 88 | # Return ourselves to the available pool 89 | with self.owner.lock: 90 | self.owner.pool.append(self) 91 | 92 | class ProcessOutput(object): 93 | def __init__(self): 94 | self.done = False 95 | # Construct a pool of 4 image processors along with a lock 96 | # to control access between threads 97 | self.lock = threading.Lock() 98 | self.pool = [ImageProcessor(self) for i in range(4)] 99 | self.processor = None 100 | 101 | def write(self, buf): 102 | if buf.startswith(b'\xff\xd8'): 103 | # New frame; set the current processor going and grab 104 | # a spare one 105 | if self.processor: 106 | self.processor.event.set() 107 | with self.lock: 108 | if self.pool: 109 | self.processor = self.pool.pop() 110 | else: 111 | # No processor's available, we'll have to skip 112 | # this frame; you may want to print a warning 113 | # here to see whether you hit this case 114 | self.processor = None 115 | if self.processor: 116 | self.processor.stream.write(buf) 117 | 118 | def flush(self): 119 | # When told to flush (this indicates end of recording), shut 120 | # down in an orderly fashion. First, add the current processor 121 | # back to the pool 122 | if self.processor: 123 | with self.lock: 124 | self.pool.append(self.processor) 125 | self.processor = None 126 | # Now, empty the pool, joining each thread as we go 127 | while True: 128 | with self.lock: 129 | try: 130 | proc = self.pool.pop() 131 | except IndexError: 132 | pass # pool is empty 133 | proc.terminated = True 134 | proc.join() 135 | 136 | 137 | def main(): 138 | """get data, then predict the data, edited data, then control the car""" 139 | global model, graph 140 | 141 | model_loaded = glob.glob('model/*.h5') 142 | for single_mod in model_loaded: 143 | model = load_model(single_mod) 144 | graph = tf.get_default_graph() 145 | 146 | try: 147 | with picamera.PiCamera(resolution=(160,120)) as camera: 148 | # uncomment this line and the camera images will be upside down 149 | # camera.vflip = True 150 | time.sleep(2) 151 | output = ProcessOutput() 152 | camera.start_recording(output, format='mjpeg') 153 | while not output.done: 154 | camera.wait_recording(1) 155 | camera.stop_recording() 156 | finally: 157 | car_control.cleanGPIO() 158 | 159 | if __name__ == '__main__': 160 | global latest_time 161 | latest_time = time.time() 162 | main() 163 | -------------------------------------------------------------------------------- /process_img_to_npz.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # @Author: biying 3 | # @Date: 2017-06-30 10:20:35 4 | # @Last Modified by: biying 5 | # @Last Modified time: 2017-12-17 18:34:18 6 | 7 | import os 8 | os.environ['SDL_VIDEODRIVE'] = 'x11' 9 | import numpy as np 10 | import matplotlib.image as mpimg 11 | from time import time 12 | import math 13 | 14 | def process_img(img_path, key): 15 | global train_imgs, train_labels, image_array, label_array 16 | print(img_path, key) 17 | 18 | # output = PIL.open(img_path) 19 | # temp_array = output.array 20 | # temp_array = np.expand_dims(temp_array,axis = 0) 21 | 22 | temp_array = mpimg.imread(img_path) 23 | temp_array = np.expand_dims(temp_array,axis = 0) 24 | print(temp_array.shape) 25 | print(image_array.shape) 26 | 27 | #stack the array 28 | image_array = np.vstack((image_array,temp_array)) 29 | 30 | if key == 2: 31 | label_array = np.vstack((label_array,[ 0., 0., 1., 0., 0.])) 32 | key = 4 33 | elif key ==3: 34 | label_array = np.vstack((label_array,[ 0., 0., 0., 1., 0.])) 35 | key = 4 36 | elif key == 0: 37 | label_array = np.vstack((label_array,[ 1., 0., 0., 0., 0.])) 38 | key = 4 39 | elif key == 1: 40 | label_array = np.vstack((label_array,[ 0., 1., 0., 0., 0.])) 41 | key = 4 42 | elif key == 4: 43 | label_array = np.vstack((label_array,[ 0., 0., 0., 0., 1.])) 44 | 45 | # 去掉第0位的全零图像数组,全零图像数组是image_array = np.zeros([1,120,160,3])初始化生成的 46 | train_imgs = image_array[1:, :] 47 | train_labels = label_array[1:, :] 48 | 49 | if __name__ == '__main__': 50 | global train_imgs, train_labels, image_array, label_array 51 | 52 | path = "training_data" 53 | files= os.listdir(path) 54 | turns = int(math.ceil(len(files) / 500)) 55 | print("number of files: %d", len(files)) 56 | print("turns: %d", turns) 57 | 58 | for turn in range(0, turns): 59 | label_array = np.zeros((1,5),'float') 60 | image_array = np.zeros([1,120,160,3]) 61 | 62 | trunc_files = files[turn*500: (turn+1)*500] 63 | print("number of trunc files: %d", len(trunc_files)) 64 | for file in trunc_files: 65 | if not os.path.isdir(file) and file[len(file)-3:len(file)] == 'jpg': 66 | try: 67 | key = int(file[0]) 68 | process_img(path+"/"+file, key); 69 | except: 70 | print('prcess error') 71 | 72 | file_name = str(int(time())) 73 | directory = "training_data_npz" 74 | 75 | if not os.path.exists(directory): 76 | os.makedirs(directory) 77 | try: 78 | np.savez(directory + '/' + file_name + '.npz', train_imgs=train_imgs, train_labels=train_labels) 79 | except IOError as e: 80 | print(e) 81 | -------------------------------------------------------------------------------- /train_model.py: -------------------------------------------------------------------------------- 1 | import pandas as pd # data analysis toolkit - create, read, update, delete datasets 2 | import numpy as np #matrix math 3 | from sklearn.model_selection import train_test_split #to split out training and testing data 4 | #keras is a high level wrapper on top of tensorflow (machine learning library) 5 | #The Sequential container is a linear stack of layers 6 | import tensorflow 7 | from keras.models import Sequential 8 | #popular optimization strategy that uses gradient descent 9 | from keras.optimizers import Adam,SGD 10 | #to save our model periodically as checkpoints for loading later 11 | from keras.callbacks import ModelCheckpoint 12 | from keras.callbacks import EarlyStopping 13 | from keras.callbacks import TensorBoard 14 | #what types of layers do we want our model to have? 15 | from keras.layers import Lambda, Conv2D, MaxPooling2D, Dropout, Dense, Flatten 16 | from keras.models import Model, Input 17 | from keras.models import load_model 18 | import glob 19 | import os 20 | import glob 21 | import h5py 22 | import sys 23 | import keras 24 | #for debugging, allows for reproducible (deterministic) results 25 | np.random.seed(0) 26 | 27 | IMAGE_HEIGHT, IMAGE_WIDTH, IMAGE_CHANNELS = 120, 160, 3 28 | INPUT_SHAPE = (IMAGE_HEIGHT, IMAGE_WIDTH, IMAGE_CHANNELS) 29 | 30 | def load_data(): 31 | """ 32 | Load training data and split it into training and validation set 33 | """ 34 | 35 | # load training data 36 | image_array = np.zeros((1,120,160,3)) 37 | label_array = np.zeros((1, 5), 'float') 38 | training_data = glob.glob('training_data_npz/*.npz') 39 | 40 | # if no data, exit 41 | if not training_data: 42 | print ("No training data in directory, exit") 43 | sys.exit() 44 | 45 | for single_npz in training_data: 46 | with np.load(single_npz) as data: 47 | print(data.keys()) 48 | train_temp = data['train_imgs'] 49 | train_labels_temp = data['train_labels'] 50 | image_array = np.vstack((image_array, train_temp)) 51 | label_array = np.vstack((label_array, train_labels_temp)) 52 | 53 | X = image_array[1:, :] 54 | y = label_array[1:, :] 55 | print ('Image array shape: '+ str(X.shape)) 56 | print ('Label array shape: '+ str(y.shape)) 57 | print(np.mean(X)) 58 | print(np.var(X)) 59 | 60 | #now we can split the data into a training (80), testing(20), and validation set 61 | #thanks scikit learn 62 | X_train, X_valid, y_train, y_valid = train_test_split(X, y, test_size=0.2, random_state=0) 63 | 64 | return X_train, X_valid, y_train, y_valid 65 | 66 | 67 | def build_model(keep_prob): 68 | """ 69 | NVIDIA model used 70 | Image normalization to avoid saturation and make gradients work better. 71 | Convolution: 5x5, filter: 24, strides: 2x2, activation: ELU 72 | Convolution: 5x5, filter: 36, strides: 2x2, activation: ELU 73 | Convolution: 5x5, filter: 48, strides: 2x2, activation: ELU 74 | Convolution: 3x3, filter: 64, strides: 1x1, activation: ELU 75 | Convolution: 3x3, filter: 64, strides: 1x1, activation: ELU 76 | Drop out (0.5) 77 | Fully connected: neurons: 100, activation: ELU 78 | Fully connected: neurons: 50, activation: ELU 79 | Fully connected: neurons: 10, activation: ELU 80 | Fully connected: neurons: 1 (output) 81 | 82 | # the convolution layers are meant to handle feature engineering 83 | the fully connected layer for predicting the steering angle. 84 | dropout avoids overfitting 85 | ELU(Exponential linear unit) function takes care of the Vanishing gradient problem. 86 | """ 87 | # IMAGE_HEIGHT, IMAGE_WIDTH, IMAGE_CHANNELS = 240, 240, 3 88 | # INPUT_SHAPE = (IMAGE_HEIGHT, IMAGE_WIDTH, IMAGE_CHANNELS) 89 | 90 | model = Sequential() 91 | model.add(Lambda(lambda x: (x/102.83-1), input_shape=INPUT_SHAPE))#/85-5139 92 | model.add(Conv2D(24, (5, 5), activation='elu', strides=(2, 2))) 93 | model.add(Conv2D(36, (5, 5), activation='elu', strides=(2, 2))) 94 | model.add(Conv2D(48, (5, 5), activation='elu', strides=(2, 2))) 95 | 96 | #model.add(Dropout(0.5)) 97 | model.add(Conv2D(64, (3, 3), activation='elu')) 98 | #model.add(Dropout(0.3)) 99 | model.add(Conv2D(64, (3, 3), activation='elu')) 100 | model.add(Dropout(keep_prob)) 101 | model.add(Flatten()) 102 | model.add(Dense(500, activation='elu')) 103 | #model.add(Dropout(0.1)) 104 | model.add(Dense(250, activation='elu')) 105 | #model.add(Dropout(0.1)) 106 | model.add(Dense(50, activation='elu')) 107 | #model.add(Dropout(0.1)) 108 | model.add(Dense(5)) 109 | model.summary() 110 | 111 | return model 112 | 113 | 114 | def train_model(model,learning_rate,nb_epoch,samples_per_epoch, batch_size,X_train, X_valid, y_train, y_valid): 115 | """ 116 | Train the model 117 | """ 118 | #Saves the model after every epoch. 119 | #quantity to monitor, verbosity i.e logging mode (0 or 1), 120 | #if save_best_only is true the latest best model according to the quantity monitored will not be overwritten. 121 | #mode: one of {auto, min, max}. If save_best_only=True, the decision to overwrite the current save file is 122 | # made based on either the maximization or the minimization of the monitored quantity. For val_acc, 123 | #this should be max, for val_loss this should be min, etc. In auto mode, the direction is automatically 124 | # inferred from the name of the monitored quantity. 125 | checkpoint = ModelCheckpoint('model-{epoch:03d}.h5', 126 | monitor='val_loss', 127 | verbose=0, 128 | save_best_only=True, 129 | mode='min') 130 | 131 | # EarlyStopping patience:当early 132 | # stop被激活(如发现loss相比上一个epoch训练没有下降),则经过patience个epoch后停止训练。 133 | # mode:‘auto’,‘min’,‘max’之一,在min模式下,如果检测值停止下降则中止训练。在max模式下,当检测值不再上升则停止训练。 134 | early_stop = EarlyStopping(monitor='val_loss', min_delta=.0005, patience=4, 135 | verbose=1, mode='min') 136 | tensorboard = TensorBoard(log_dir='./logs', histogram_freq=0, batch_size=20, write_graph=True, write_grads=True, write_images=True, embeddings_freq=0, embeddings_layer_names=None, embeddings_metadata=None) 137 | #calculate the difference between expected steering angle and actual steering angle 138 | #square the difference 139 | #add up all those differences for as many data points as we have 140 | #divide by the number of them 141 | #that value is our mean squared error! this is what we want to minimize via 142 | #gradient descent 143 | #opt = SGD(lr=0.0001) 144 | model.compile(loss='mean_squared_error', optimizer=Adam(lr=learning_rate),metrics=['accuracy'])# 145 | 146 | #Fits the model on data generated batch-by-batch by a Python generator. 147 | 148 | #The generator is run in parallel to the model, for efficiency. 149 | #For instance, this allows you to do real-time data augmentation on images on CPU in 150 | #parallel to training your model on GPU. 151 | #so we reshape our data into their appropriate batches and train our model simulatenously 152 | 153 | model.fit_generator(batch_generator(X_train, y_train,batch_size), 154 | steps_per_epoch=samples_per_epoch/batch_size, 155 | epochs=nb_epoch, 156 | max_queue_size=1, 157 | validation_data=batch_generator(X_valid, y_valid, batch_size), 158 | validation_steps=len(X_valid)/batch_size, 159 | callbacks=[tensorboard, checkpoint, early_stop], 160 | verbose=2) 161 | 162 | ## model.fit(X_train,y_train,samples_per_epoch,nb_epoch,max_q_size=1,X_valid,y_valid,\ 163 | ## nb_val_samples=len(X_valid),callbacks=[checkpoint],verbose=1) 164 | 165 | def batch_generator(X, y, batch_size): 166 | """ 167 | Generate training image give image paths and associated steering angles 168 | """ 169 | images = np.empty([batch_size, IMAGE_HEIGHT, IMAGE_WIDTH, IMAGE_CHANNELS]) 170 | steers = np.empty([batch_size,5]) 171 | while True: 172 | i = 0 173 | for index in np.random.permutation(X.shape[0]): 174 | images[i] = X[index] 175 | steers[i] = y[index] 176 | i += 1 177 | if i == batch_size: 178 | break 179 | yield (images, steers) 180 | 181 | def main(): 182 | #print parameters 183 | print('-' * 30) 184 | print('Parameters') 185 | print('-' * 30) 186 | 187 | keep_prob = 0.5 188 | learning_rate = 0.0001 189 | nb_epoch = 100 190 | samples_per_epoch = 3000 191 | batch_size = 40 192 | 193 | print('keep_prob = %f', keep_prob) 194 | print('learning_rate = %f', learning_rate) 195 | print('nb_epoch = %d', nb_epoch) 196 | print('samples_per_epoch = %d', samples_per_epoch) 197 | print('batch_size = %d', batch_size) 198 | print('-' * 30) 199 | 200 | #load data 201 | data = load_data() 202 | #build model 203 | model = build_model(keep_prob) 204 | #train model on data, it saves as model.h5 205 | train_model(model,learning_rate,nb_epoch,samples_per_epoch, batch_size, *data) 206 | 207 | 208 | if __name__ == '__main__': 209 | main() 210 | -------------------------------------------------------------------------------- /使用教程.md: -------------------------------------------------------------------------------- 1 | # 树莓派自动驾驶模型搭建指南 2 | *** 3 | 4 | ## 树莓派介绍 5 | 6 | 1. 简称`raspberry` 7 | 2. 当我们拿到树莓派第一件事就是烧系统,使用`etcher` 8 | 3. 在sd卡的主文件夹下新建ssh文件,因为新版系统默认不支持ssh 9 | 4. 得到ip地址 通过 `arp -a`或者`ping raspberrypi.local` 10 | 5. 连接树莓派通过 `ssh pi@ip` 密码 `raspberry` 11 | 6. 进行配置`sudo raspi-config` 12 | 13 | * 设置camera为Yes,VNC为YES 14 | * 通过vnc连接 软件为`vnc viewer` 15 | 16 | 软件安装 17 | 18 | 各项命令 19 | 20 | 1. 安装tensorflow: `sudo pip3 install –v tensorflow-1.1.0-cp35-cp35m-linux_armv71.whl` 21 | 22 | 2. 安装Keras: 23 | 24 | - sudo pip3 install –v numpy 25 | 26 | - sudo apt-get install python3-scipy 27 | 28 | - sudo pip3 install –v scikit-learn 29 | 30 | - sudo pip3 install –v pillow 31 | 32 | - sudo apt-get install python3-h5py 33 | 34 | - sudo pip3 install –v keras 35 | 36 | 3. 使用软件将树莓派备份`ApplePi-Baker` 37 | 38 | 39 | 4. 树莓派的摄像头的使用 40 | 41 | - 使用picamera库[picamera](http://picamera.readthedocs.io/en/release-1.13/recipes1.html) 42 | 43 | - 如果拍照片 使用'raspistill -t 30000 -tl 2000 -o image%04d.jpg' 44 | 45 | - 如果是拍视频 使用'raspivid -o video.h264 -t 60000' 46 | 47 | - 更多的用法请参考[树莓派的使用方法](http://picamera.readthedocs.io/en/release-1.13/recipes2.html#rapid-capture-and-processing) 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | -------------------------------------------------------------------------------- /电路板的输出电路图.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/HadXu/auto-drive/4d0c22235c1f4bcb5d7cce865a9f94c00e0facf8/电路板的输出电路图.jpg --------------------------------------------------------------------------------