Self-Driving Car Engineer Nanodegree

Project: Finding Lane Lines on the Road


In this project, you will use the tools you learned about in the lesson to identify lane lines on the road. You can develop your pipeline on a series of individual images, and later apply the result to a video stream (really just a series of images). Check out the video clip "raw-lines-example.mp4" (also contained in this repository) to see what the output should look like after using the helper functions below.

Once you have a result that looks roughly like "raw-lines-example.mp4", you'll need to get creative and try to average and/or extrapolate the line segments you've detected to map out the full extent of the lane lines. You can see an example of the result you're going for in the video "P1_example.mp4". Ultimately, you would like to draw just one line for the left side of the lane, and one for the right.

In addition to implementing code, there is a brief writeup to complete. The writeup should be completed in a separate file, which can be either a markdown file or a pdf document. There is a write up template that can be used to guide the writing process. Completing both the code in the Ipython notebook and the writeup template will cover all of the rubric points for this project.


Let's have a look at our first image called 'test_images/solidWhiteRight.jpg'. Run the 2 cells below (hit Shift-Enter or the "play" button above) to display the image.

Note: If, at any point, you encounter frozen display windows or other confounding issues, you can always start again with a clean slate by going to the "Kernel" menu above and selecting "Restart & Clear Output".


The tools you have are color selection, region of interest selection, grayscaling, Gaussian smoothing, Canny Edge Detection and Hough Tranform line detection. You are also free to explore and try other techniques that were not presented in the lesson. Your goal is piece together a pipeline to detect the line segments in the image, then average/extrapolate them and draw them onto the image for display (as below). Once you have a working pipeline, try it out on the video stream below.


Your output should look something like this (above) after detecting line segments using the helper functions below

Your goal is to connect/average/extrapolate line segments to get output like this

Run the cell below to import some packages. If you get an import error for a package you've already installed, try changing your kernel (select the Kernel menu above --> Change Kernel). Still have problems? Try relaunching Jupyter Notebook from the terminal prompt. Also, see this forum post for more troubleshooting tips.


In [1]:
%qtconsole

Import Packages


In [2]:
#importing some useful packages
import matplotlib.pyplot as plt
import matplotlib.image as mpimg
import matplotlib.mlab as mlab
import numpy as np
import cv2
import os

# Import everything needed to edit/save/watch video clips
from moviepy.editor import VideoFileClip
from IPython.display import HTML

%matplotlib inline

Read in an Image


In [3]:
#reading in an image
image = mpimg.imread('test_images/solidWhiteRight.jpg')

#printing out some stats and plotting
print('This image is:', type(image), 'with dimesions:', image.shape)
plt.imshow(image)  # if you wanted to show a single color channel image called 'gray', for example, call as plt.imshow(gray, cmap='gray')


This image is: <class 'numpy.ndarray'> with dimesions: (540, 960, 3)
Out[3]:
<matplotlib.image.AxesImage at 0x1164cd400>

List of Test Images and Videos

Pre-load only the names of the test images and videos


In [4]:
## Test Images
test_dir = "test_images"
test_files = [os.path.abspath(os.path.join(test_dir, f)) for f in os.listdir(test_dir)]                       

all_test_img = range(len(test_files))
sub_test_rng = [0, 1, 2, 3, 4, 5]

## Test Videos
white     = {'input': "solidWhiteRight.mp4", 'output': "white.mp4" }
yellow    = {'input': "solidYellowLeft.mp4", 'output': "yellow.mp4"}
challenge = {'input': "challenge.mp4"      , 'output': "result.mp4"}

all_vid_files = [white, yellow, challenge]

Helper Functions

Below are some helper functions from the project


In [5]:
import math

def grayscale(img):
    """Applies the Grayscale transform
    This will return an image with only one color channel
    but NOTE: to see the returned image as grayscale
    (assuming your grayscaled image is called 'gray')
    you should call plt.imshow(gray, cmap='gray')"""
    return cv2.cvtColor(img, cv2.COLOR_RGB2GRAY)
    # Or use BGR2GRAY if you read an image with cv2.imread()
    # return cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)
    
def canny(img, low_threshold, high_threshold):
    """Applies the Canny transform"""
    return cv2.Canny(img, low_threshold, high_threshold)

def gaussian_blur(img, kernel_size):
    """Applies a Gaussian Noise kernel"""
    return cv2.GaussianBlur(img, (kernel_size, kernel_size), 0)

def region_of_interest(img, vertices):
    """
    Applies an image mask.
    
    Only keeps the region of the image defined by the polygon
    formed from `vertices`. The rest of the image is set to black.
    """
    #defining a blank mask to start with
    mask = np.zeros_like(img)   
    
    #defining a 3 channel or 1 channel color to fill the mask with depending on the input image
    if len(img.shape) > 2:
        channel_count = img.shape[2]  # i.e. 3 or 4 depending on your image
        ignore_mask_color = (255,) * channel_count
    else:
        ignore_mask_color = 255
        
    #filling pixels inside the polygon defined by "vertices" with the fill color    
    cv2.fillPoly(mask, vertices, ignore_mask_color)
    
    #returning the image only where mask pixels are nonzero
    masked_image = cv2.bitwise_and(img, mask)
    return masked_image


def draw_lines(img, lines, color=[255, 0, 0], thickness=2):
    """
    NOTE: this is the function you might want to use as a starting point once you want to 
    average/extrapolate the line segments you detect to map out the full
    extent of the lane (going from the result shown in raw-lines-example.mp4
    to that shown in P1_example.mp4).  
    
    Think about things like separating line segments by their 
    slope ((y2-y1)/(x2-x1)) to decide which segments are part of the left
    line vs. the right line.  Then, you can average the position of each of 
    the lines and extrapolate to the top and bottom of the lane.
    
    This function draws `lines` with `color` and `thickness`.    
    Lines are drawn on the image inplace (mutates the image).
    If you want to make the lines semi-transparent, think about combining
    this function with the weighted_img() function below
    """
    for line in lines:
        for x1,y1,x2,y2 in line:
            cv2.line(img, (x1, y1), (x2, y2), color, thickness)
    return img

def hough_lines(img, rho, theta, threshold, min_line_len, max_line_gap):
    """
    `img` should be the output of a Canny transform.
        
    Returns an image with hough lines drawn.
    """
    lines = cv2.HoughLinesP(img, rho, theta, threshold, np.array([]), minLineLength=min_line_len, maxLineGap=max_line_gap)
    line_img = np.zeros((img.shape[0], img.shape[1], 3), dtype=np.uint8)
    draw_lines(line_img, lines)
    return line_img

# Python 3 has support for cool math symbols.

def weighted_img(img, initial_img, α=0.8, β=1., λ=0.):
    """
    `img` is the output of the hough_lines(), An image with lines drawn on it.
    Should be a blank image (all black) with lines drawn on it.
    
    `initial_img` should be the image before any processing.
    
    The result image is computed as follows:
    
    initial_img * α + img * β + λ
    NOTE: initial_img and img must be the same shape!
    """
    return cv2.addWeighted(initial_img, α, img, β, λ)

Pipeline Functions

The block below contains the pipeline functions and most of the helper functions used in the project.


In [6]:
COLOR_SWATCH = [ 
	[255, 64,  0  ], [255, 128, 0  ], [255, 191,   0], 
	[255, 255, 0  ], [191, 255, 0  ], [128, 255,   0], [64, 255, 0],
	[0,   255, 0  ], [0,   255, 64 ], [  0, 255, 128], 
	[0,   255, 191], [0,   255, 255], [  0, 191, 255], 
	[0,   128, 255], [0,   64,  255], [  0,   0, 255], 
	[64,  0,   255], [128, 0,   255], [191,   0, 255], 
	[255, 0,   255], [255, 0,   191], [255,   0, 128], 
	[255, 0,   64 ], [255, 0,   0  ] 
]


def getColor(counter=0):
    """ Returns a color based on an index. Ideally this method should
        be used in a loop, when drawing lines to get a different color
        for different line.
    """
    return COLOR_SWATCH[(counter*5) % len(COLOR_SWATCH)]


def image_size(img):
    """ Returns only the [Height, Width] regardless of the number of channels 
        the image has.
    """
    return (img.shape[0], img.shape[1])


def edge_detect(gray, kernel_size=5, low_threshold=50, high_threshold=150):
    """ Define a kernel size and apply Gaussian smoothing 
        Defaults:
          - kernel_size = 5
          - low_threshold = 50
          - high_threshold = 150
    """ 
    kernel_size = 5
    blur_gray = cv2.GaussianBlur(gray,(kernel_size, kernel_size),0)
    
    # Define our parameters for Canny and apply
    low_threshold = 50
    high_threshold = 150
    edges = cv2.Canny(blur_gray, low_threshold, high_threshold)
    return edges, blur_gray


def create_region_mask(imshape, vertices, ignore_mask_color = 255):
    """ Returns a mask given the image's shape, vertices [array].
        Defaults:
        ignore_mask_color = 255
    """
    mask = np.zeros((imshape[0], imshape[1]), dtype=np.uint8)        
    cv2.fillPoly(mask, vertices, ignore_mask_color)
    return mask


def create_quad_region_mask(imshape, top_width=0.1, btm_width=1.0, top_height=0.55, ignore_mask_color=255):
    """ Returns a quadrilateral mask given the image's shape and some quadrilateral specs.

        Params:
        * top_width -  [0.0 - 1.0] value indicating the percentage difference between the botton
                       width vs the image width. Bottom line will be centered around the center 
                       of the image
        * top_heigth - [0.0 - 1.0] value indicating the percentage difference between the top
                       width vs the image width. Top line will be centered around the center 
                       of the image
        Defaults:
        * ignore_mask_color = 255
    """
    # This time we are defining a four sided polygon to mask
    h = imshape[0]
    w = imshape[1]
    
    w_top_min = ((1.0 - top_width)/2) * w
    w_top_max = ((1.0 + top_width)/2) * w
    w_btm_min = ((1.0 - btm_width)/2) * w
    w_btm_max = ((1.0 + btm_width)/2) * w
    h_min = (h * top_height)

    vertices = np.array([[(w_btm_min, h),     (w_top_min, h_min), 
                          (w_top_max, h_min), (w_btm_max, h)]], dtype=np.int32)
    return vertices, create_region_mask(imshape, vertices)


def apply_mask(img, mask):
    """ Applies a mask to an image regardless of the image's number of channel. 
        However, the image [height, width] and mask [height, width] must match
    """
    a = image_size(img)
    b = image_size(mask)
    
    assert(a == b), "image(" + str(a) + ") and mask(" + str(b) + ") size mismatch"
    
    #defining a 3 channel or 1 channel color to fill the mask with depending on the input image
    if len(img.shape) > 2:
        channel_count = img.shape[2]  # i.e. 3 or 4 depending on your image
        masked_image = np.zeros_like(img)
        
        for i in range(channel_count):
            masked_image[:,:,i] = cv2.bitwise_and(img[:, :,i], mask)
        return masked_image
    else:
        return cv2.bitwise_and(img, mask)

    
def hough_lines_P(img, rho, theta, threshold, min_line_len, max_line_gap):
    """ `img` should be the output of a Canny transform.
        Returns an array of hough line segments
    """
    lines = cv2.HoughLinesP(img, rho, theta, threshold, np.array([]), minLineLength=min_line_len, maxLineGap=max_line_gap)
    return lines

Pipeline Functions Continued


In [7]:
# TODO: Build your pipeline that will draw lane lines on the test_images
# then save them to the test_images directory.

## Edge Detect Params
ED_kernel_size    = 5 
ED_low_threshold  = 50 
ED_high_threshold = 150

## Region Mask Params
REG_top_width  = 0.1 
REG_btm_width  = 0.9
REG_top_height = 0.6

# Define the Hough transform parameters
rho = 2               # distance resolution in pixels of the Hough grid
theta = np.pi/180 * 1 # angular resolution in radians of the Hough grid
threshold = 60        # minimum number of votes (intersections in Hough grid cell)
min_line_length = 75  # minimum number of pixels making up a line
max_line_gap = 50     # maximum gap in pixels between connectable line segments

# Gradient Filter Thresholds
(Left_Std, Right_Std) = (5.0, 5.0)

def print_params(dirname):
    f = open(os.path.join(dirname, 'params.txt'), 'w')
    f.write("## Edge Detect Params\n")
    f.write("* ED_kernel_size    = " + str(ED_kernel_size   ) + "\n")
    f.write("* ED_low_threshold  = " + str(ED_low_threshold ) + "\n")
    f.write("* ED_high_threshold = " + str(ED_high_threshold) + "\n")
    f.write("\n")
    f.write("## Region Mask Params\n")
    f.write("* REG_top_width  = " + str(REG_top_width ) + "\n") 
    f.write("* REG_btm_width  = " + str(REG_btm_width ) + "\n")
    f.write("* REG_top_height = " + str(REG_top_height) + "\n")
    f.write("\n")
    f.write("## Hough transform parameters\n")
    f.write("* rho             = " + str(rho            ) + "\n")
    f.write("* theta           = " + str(theta          ) + "\n")
    f.write("* threshold       = " + str(threshold      ) + "\n")
    f.write("* min_line_length = " + str(min_line_length) + "\n")
    f.write("* max_line_gap    = " + str(max_line_gap   ) + "\n")
    f.close()

    
def print_images(dirname, org_img=None, res_img=None, cny_img=None, num_line=''):
    if (org_img is not None): mpimg.imsave(os.path.join(dirname, num_line + "org_img.png"), arr=org_img)
    if (res_img is not None): mpimg.imsave(os.path.join(dirname, num_line + "res_img.png"), arr=res_img)        
    if (cny_img is not None): mpimg.imsave(os.path.join(dirname, num_line + "cny_img.png"), arr=cny_img)            

def inRange(a, b, c, inclusive=True):
    if (inclusive):
        return (a >= b and a <= c)
    else:
        return (a > b and a < c)        
            
left_grad_mean = 0
left_grad_std  = 0
right_grad_mean = 0
right_grad_std  = 0

def reset_grad_filter_params():
    global left_grad_mean, left_grad_std, right_grad_mean, right_grad_std
    left_grad_mean = 0
    left_grad_std  = 0
    right_grad_mean = 0
    right_grad_std  = 0

    
lines_list  = []
def filter_by_angle(lines):
    global lines_list

    for l in lines:
        lines_list.append(l)

    ms = []
    cs = []
    filtered_cs   = []
    filtered_ms   = []
    filtered_lines = []

    for l in lines:
        for (x1, y1, x2, y2) in l:
            m = (y2 - y1) / (x2 - x1)
            c = y2 - m*x2
            ms.append(m)
            cs.append(c)
            if ((left_grad_mean + left_grad_std + right_grad_mean + right_grad_std) != 0):
                l_min = left_grad_mean  - Left_Std*left_grad_std 
                l_max = left_grad_mean  + Left_Std*left_grad_std
                r_min = right_grad_mean - Right_Std*right_grad_std
                r_max = right_grad_mean + Right_Std*right_grad_std
                if (inRange(m, l_min, l_max) or inRange(m, r_min, r_max)): 
                    filtered_lines.append(l)
                    filtered_ms.append(m)
                    filtered_cs.append(c)
    
    if (len(filtered_lines) > 0):
        return np.array(filtered_lines), filtered_ms, filtered_cs
    else:
        return lines, ms, cs
    

def split_left_right(lines, m, c):
    """splits things into left and right lanes"""    
    _l = np.array(lines)
    _m = np.array(m)
    _c = np.array(c)
    l_idx = _m > 0
    r_idx = _m < 0
    a = (_l[l_idx], _l[r_idx])
    b = (_m[l_idx], _m[r_idx])
    c = (_c[r_idx], _c[l_idx])    
    return a,b,c
    
    
def find_best_fit(x, y, show_plot=False):
    pt = np.array([x, y]).transpose()
    vx, vy, x1, y1 = cv2.fitLine(pt, 2, 0, 0.01, 0.01)

    mm = vy/vx
    c = (y1 - mm*x1)
    y2 = mm*x + c

    if (show_plot):        
        plt.plot(x, y, 'r.')
        plt.plot(x, y2, 'b-')
        plt.grid(True);
        plt.show()
    return vx[0], vy[0], x1[0], y1[0], mm[0], c[0]


def create_lane_lines(lines, m, c, verts):
    assert len(lines) == len(m) == len(c), 'lines, m, c, size mismatch'

    lr_l, lr_m, lr_c = split_left_right(lines, m, c)

    x_rng = range(verts[0,:,0].min(), verts[0,:,0].max())    
    y_rng = range(verts[0,:,1].min(), verts[0,:,1].max())
    
    lanes = []

    # find left lane line
    for i in [0, 1]:        
        xs = np.concatenate((lr_l[i][:,:,0],  lr_l[i][:,:,2]))
        ys = np.concatenate((lr_l[i][:,:,1],  lr_l[i][:,:,3]))        
        (vx, vy, x1, y1, mm, cc) = find_best_fit(xs, ys)

        a = [vx, vy, x1, y1, mm, cc]
        if (np.isnan(a).any() or np.isinf(a).any()): 
            print('NANs found')
            print(a)
            continue
            
        y1 = y_rng.start;  y2 = y_rng.stop
        x1 = (y1 - cc)/mm; x2 = (y2 - cc)/mm
        if (mm == 0.0):
            print("xy = " + str((x1, y1, x2, y2)) + " m,c = " + str((mm, cc)))
            print("lines = " + str(lines))
            print("m = " + str(m))
            print("c = " + str(c))
            continue

        pt = np.array([[x1, y1, x2, y2]], dtype=np.int32)
        lanes.append(pt)
        
    return np.array(lanes)


def process_image(image):
    
    org_image = np.copy(image)
    gray = cv2.cvtColor(image, cv2.COLOR_RGB2GRAY)
    
    ## Detect Edges
    [edges, blur_gray] = edge_detect(gray, ED_kernel_size, ED_low_threshold, ED_high_threshold)    
    
    ## Create Region Mask
    verts, mask = create_quad_region_mask(gray.shape, top_width =REG_top_width, 
                                                      btm_width =REG_btm_width, 
                                                      top_height=REG_top_height)
    # Overlay the mask on the edge image
    masked_edges = apply_mask(edges, mask)

    # Run HoughLine algorithm
    lines = hough_lines_P(masked_edges, rho, theta, threshold, min_line_length, max_line_gap)
    
    # Filter Lines
    lines, ms, cs = filter_by_angle(lines)
    
    # Create single line
    lines = create_lane_lines(lines, ms, cs, verts)

    # Draw Lines 
    dark_line  = draw_lines(np.zeros_like(image),  lines, color=[0, 255, 0], thickness=6)
    comp_image = weighted_img(initial_img=dark_line, α=1.0,  img=org_image, β=0.6)
    
    return comp_image


def process_test_image(image_name, res_dir=None, render=False):
    # Read image
    image = mpimg.imread(image_name)    

    # Results Directory
    im_res_dir = None
    if (res_dir is not None):
        file_name = os.path.splitext(os.path.basename(image_name))[0]
        im_res_dir = os.path.join(res_dir, file_name)
        if (False == os.path.exists(im_res_dir)): os.makedirs(im_res_dir)
        # save test param3
        print_params(dirname=res_dir)

    # process image
    process_image(image, save_results_dir=im_res_dir, render_images=render)

    
def process_video(filename):
    clip1 = VideoFileClip(filename)
    clip = clip1.fl_image(process_image) #NOTE: this function expects color images!!
    return clip    

def save_video(clip, filename):
    clip.write_videofile(filename, audio=False)

Build the pipeline and run your solution on all test_images. Make copies into the test_images directory, and you can use the images in your writeup report.

Try tuning the various parameters, especially the low and high Canny thresholds as well as the Hough lines parameters.

Determine - Left/Right gradient and Y-intercept value


In [8]:
def plot_normpdf(hdl, bins, mu, sigma, clr='r--'):
    """Plots a normal probability distribution"""
    # add a 'best fit' line
    y = mlab.normpdf( bins, mu, sigma)
    l = hdl.plot(bins, y, 'r--', linewidth=1)

    
def plot_hist(lines_list):
    """Does more than just plot histograms"""
    lines = (np.array(lines_list))
    if (len(lines.shape) == 3):
        lines = lines[:,0,:]
        lines.shape
        
    x1 = lines[:,0];
    y1 = lines[:,1];
    x2 = lines[:,2];
    y2 = lines[:,3];

    m = (y2 - y1)/(x2 - x1)
    c = y2 - (m * x2)

    sp_l, sp_m, sp_c = split_left_right(lines, m, c)
    
    m_plt = plt.figure().add_subplot(111)
    c_plt = plt.figure().add_subplot(111)
    
    # the histogram of the gradients
    n, bins, patches = m_plt.hist(m, 50, normed=1, facecolor='green', alpha=0.75)
    plot_normpdf(m_plt, bins[bins>0], sp_m[0].mean(), sp_m[0].std())
    plot_normpdf(m_plt, bins[bins<0], sp_m[1].mean(), sp_m[1].std())    
    m_plt.set_xlabel('gradients')
    m_plt.set_ylabel('Probability')
    m_plt.set_title('l_mu = '    + str(sp_m[0].mean()) + 
                    ' | l_sg = ' + str(sp_m[0].std())  +
                    ' | r_mu = ' + str(sp_m[1].mean()) + 
                    ' | r_sg = ' + str(sp_m[1].std()))
    m_plt.grid(True)

    # the histogram of the intercepts
    _, cbins, _ = c_plt.hist(c, 50, normed=1, facecolor='blue', alpha=0.75)
    x = cbins[-1]/2
    plot_normpdf(c_plt, cbins[cbins>x], sp_c[0].mean(), sp_c[0].std())
    plot_normpdf(c_plt, cbins[cbins<x], sp_c[1].mean(), sp_c[1].std())    
    c_plt.set_xlabel('intercepts')
    c_plt.set_ylabel('Probability')
    c_plt.set_title('l_mu = '    + str(sp_c[0].mean()) + 
                    ' | l_sg = ' + str(sp_c[0].std())  +
                    ' | r_mu = ' + str(sp_c[1].mean()) + 
                    ' | r_sg = ' + str(sp_c[1].std()))
    c_plt.grid(True)

    plt.show()
    return lines, m, c, bins, n


def predict_lane_gradients():
    
    ### lines list is a hacky way of collecting the list of all the line generated by our first
    ### pass. During first pass, it attempts to predict the left and right lane gradient means 
    ### and std-devs. zero the lines_list for now
    global lines_list
    
    # Run through the first video
    lines_list = []
    process_video(white['input'])
    WH_lines, WH_m, WH_c, WH_bins, WH_n = plot_hist(lines_list)

    # Run through the Second video
    lines_list = []
    process_video(yellow['input'])
    YL_lines, YL_m, YL_c, YL_bins, YL_n = plot_hist(lines_list)
        
    # combine the two data sets
    WY_lines = np.concatenate((np.array(YL_lines), np.array(WH_lines)), axis=0)
    WY_l, WY_m, WY_c, WY_bins, WY_n = plot_hist(WY_lines)

    l, m, c = split_left_right(WY_l, WY_m, WY_c)
    
    left_m_std   = m[0].std()
    left_m_mean  = m[0].mean()
    right_m_std  = m[1].std()
    right_m_mean = m[1].mean()
    left_c_std   = c[0].std()
    left_c_mean  = c[0].mean()
    right_c_std  = c[1].std()
    right_c_mean = c[1].mean()
    print("Left  mean(m) = " + str(left_m_mean)  + " std(m) = " + str(left_m_std))
    print("Left  mean(c) = " + str(left_c_mean)  + " std(c) = " + str(left_c_std))
    print("")
    print("Right mean(m) = " + str(right_m_mean) + " std(m) = " + str(right_m_std))
    print("Right mean(c) = " + str(right_c_mean) + " std(c) = " + str(right_c_std))

    # run the prediction 
    global left_grad_mean, left_grad_std, right_grad_mean, right_grad_std
    left_grad_mean  = left_m_mean
    left_grad_std   = left_m_std
    right_grad_mean = right_m_mean
    right_grad_std  = right_m_std

    return l, m, c
    
_ = predict_lane_gradients()


Left  mean(m) = 0.64637109746 std(m) = 0.0273221417728
Left  mean(c) = 632.861437446 std(c) = 23.217346736

Right mean(m) = -0.675439254607 std(m) = 0.0563541724597
Right mean(c) = -7.53295304049 std(c) = 13.6366325964

Test on Videos

You know what's cooler than drawing lanes over images? Drawing lanes over video!

We can test our solution on two provided videos:

solidWhiteRight.mp4

solidYellowLeft.mp4

Note: if you get an import error when you run the next cell, try changing your kernel (select the Kernel menu above --> Change Kernel). Still have problems? Try relaunching Jupyter Notebook from the terminal prompt. Also, check out this forum post for more troubleshooting tips.

If you get an error that looks like this:

NeedDownloadError: Need ffmpeg exe. 
You can download it by calling: 
imageio.plugins.ffmpeg.download()

Follow the instructions in the error message and check out this forum post for more troubleshooting tips across operating systems.

Test Video: solidWhiteRight.mp4


In [9]:
clip = process_video(white['input'])
%time save_video(clip, white['output'])


HTML("""
<video width="960" height="540" controls>
  <source src="{0}">
</video>
""".format(white['output']))


[MoviePy] >>>> Building video white.mp4
[MoviePy] Writing video white.mp4
100%|█████████▉| 221/222 [00:39<00:00,  5.69it/s]
[MoviePy] Done.
[MoviePy] >>>> Video ready: white.mp4 

CPU times: user 37.7 s, sys: 1.9 s, total: 39.6 s
Wall time: 39.7 s
Out[9]:

Test Video: solidYellowLeft.mp4


In [10]:
save_image_number = -1

clip = process_video(yellow['input'])
%time save_video(clip, yellow['output'])

HTML("""
<video width="960" height="540" controls>
  <source src="{0}">
</video>
""".format(yellow['output']))


[MoviePy] >>>> Building video yellow.mp4
[MoviePy] Writing video yellow.mp4
100%|█████████▉| 681/682 [01:59<00:00,  5.77it/s]
[MoviePy] Done.
[MoviePy] >>>> Video ready: yellow.mp4 

CPU times: user 1min 56s, sys: 4.13 s, total: 2min
Wall time: 2min
Out[10]:

In [ ]: