Rename our allwpilib (which is now 2020) to not have 2019 in the name

Change-Id: I3c07f85ed32ab8b97db765a9b43f2a6ce7da964a
diff --git a/cscore/.styleguide b/cscore/.styleguide
new file mode 100644
index 0000000..f38c850
--- /dev/null
+++ b/cscore/.styleguide
@@ -0,0 +1,37 @@
+cHeaderFileInclude {
+  _c\.h$
+}
+
+cppHeaderFileInclude {
+  (?<!_c)\.h$
+  \.hpp$
+  \.inc$
+}
+
+cppSrcFileInclude {
+  \.cpp$
+}
+
+licenseUpdateExclude {
+  src/main/native/cpp/default_init_allocator\.h$
+}
+
+includeGuardRoots {
+  cscore/src/main/native/cpp/
+  cscore/src/main/native/include/
+  cscore/src/main/native/linux/
+  cscore/src/main/native/osx/
+  cscore/src/main/native/windows/
+  cscore/src/main/test/native/cpp/
+}
+
+repoRootNameOverride {
+  cscore
+}
+
+includeOtherLibs {
+  ^opencv2/
+  ^support/
+  ^tcpsockets/
+  ^wpi/
+}
diff --git a/cscore/CMakeLists.txt b/cscore/CMakeLists.txt
new file mode 100644
index 0000000..a87ab7d
--- /dev/null
+++ b/cscore/CMakeLists.txt
@@ -0,0 +1,134 @@
+project(cscore)
+
+include(SubDirList)
+include(CompileWarnings)
+include(AddTest)
+
+find_package( OpenCV REQUIRED )
+
+file(GLOB
+    cscore_native_src src/main/native/cpp/*.cpp)
+file(GLOB cscore_linux_src src/main/native/linux/*.cpp)
+file(GLOB cscore_osx_src src/main/native/osx/*.cpp)
+file(GLOB cscore_windows_src src/main/native/windows/*.cpp)
+
+add_library(cscore ${cscore_native_src})
+set_target_properties(cscore PROPERTIES DEBUG_POSTFIX "d")
+
+if(NOT MSVC)
+    if (APPLE)
+        target_sources(cscore PRIVATE ${cscore_osx_src})
+    else()
+        target_sources(cscore PRIVATE ${cscore_linux_src})
+    endif()
+else()
+    target_sources(cscore PRIVATE ${cscore_windows_src})
+    target_compile_definitions(cscore PUBLIC -DNOMINMAX)
+    target_compile_definitions(cscore PRIVATE -D_CRT_SECURE_NO_WARNINGS)
+endif()
+
+target_include_directories(cscore PUBLIC
+                $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
+                            $<INSTALL_INTERFACE:${include_dest}/cscore>)
+target_include_directories(cscore PRIVATE src/main/native/cpp)
+wpilib_target_warnings(cscore)
+target_link_libraries(cscore PUBLIC wpiutil ${OpenCV_LIBS})
+
+set_property(TARGET cscore PROPERTY FOLDER "libraries")
+
+install(TARGETS cscore EXPORT cscore DESTINATION "${main_lib_dest}")
+install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/cscore")
+
+if (MSVC OR FLAT_INSTALL_WPILIB)
+    set (cscore_config_dir ${wpilib_dest})
+else()
+    set (cscore_config_dir share/cscore)
+endif()
+
+configure_file(cscore-config.cmake.in ${CMAKE_BINARY_DIR}/cscore-config.cmake )
+install(FILES ${CMAKE_BINARY_DIR}/cscore-config.cmake DESTINATION ${cscore_config_dir})
+install(EXPORT cscore DESTINATION ${cscore_config_dir})
+
+SUBDIR_LIST(cscore_examples "${CMAKE_CURRENT_SOURCE_DIR}/examples")
+foreach(example ${cscore_examples})
+    file(GLOB cscore_example_src examples/${example}/*.cpp)
+    if(cscore_example_src)
+        add_executable(cscore_${example} ${cscore_example_src})
+        wpilib_target_warnings(cscore_${example})
+        target_link_libraries(cscore_${example} cscore)
+        set_property(TARGET cscore_${example} PROPERTY FOLDER "examples")
+    endif()
+endforeach()
+
+# Java bindings
+if (NOT WITHOUT_JAVA)
+    find_package(Java REQUIRED)
+    find_package(JNI REQUIRED)
+    include(UseJava)
+    set(CMAKE_JAVA_COMPILE_FLAGS "-Xlint:unchecked")
+
+    #find java files, copy them locally
+
+    set(OPENCV_JAVA_INSTALL_DIR ${OpenCV_INSTALL_PATH}/share/OpenCV/java/)
+
+    find_file(OPENCV_JAR_FILE NAMES opencv-${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.jar PATHS ${OPENCV_JAVA_INSTALL_DIR} ${OpenCV_INSTALL_PATH}/bin NO_DEFAULT_PATH)
+    find_file(OPENCV_JNI_FILE NAMES libopencv_java${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.so
+                                    libopencv_java${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.dylib
+                                    opencv_java${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.dll
+                                    PATHS ${OPENCV_JAVA_INSTALL_DIR} ${OpenCV_INSTALL_PATH}/bin ${OpenCV_INSTALL_PATH}/bin/Release ${OpenCV_INSTALL_PATH}/bin/Debug ${OpenCV_INSTALL_PATH}/lib NO_DEFAULT_PATH)
+
+    file(GLOB
+        cscore_jni_src src/main/native/cpp/jni/CameraServerJNI.cpp)
+
+    file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java)
+    set(CMAKE_JNI_TARGET true)
+
+    if(${CMAKE_VERSION} VERSION_LESS "3.11.0")
+        set(CMAKE_JAVA_COMPILE_FLAGS "-h" "${CMAKE_CURRENT_BINARY_DIR}/jniheaders")
+        add_jar(cscore_jar ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar ${OPENCV_JAR_FILE} OUTPUT_NAME cscore)
+    else()
+        add_jar(cscore_jar ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar ${OPENCV_JAR_FILE} OUTPUT_NAME cscore GENERATE_NATIVE_HEADERS cscore_jni_headers)
+    endif()
+
+    get_property(CSCORE_JAR_FILE TARGET cscore_jar PROPERTY JAR_FILE)
+    install(FILES ${CSCORE_JAR_FILE} DESTINATION "${java_lib_dest}")
+    install(FILES ${OPENCV_JAR_FILE} DESTINATION "${java_lib_dest}")
+
+    if (MSVC)
+        install(FILES ${OPENCV_JNI_FILE} DESTINATION "${jni_lib_dest}")
+
+        foreach(cvFile ${OpenCV_LIBS})
+            find_file(${cvFile}Loc NAMES ${cvFile}${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.dll
+                              PATHS ${OPENCV_JAVA_INSTALL_DIR} ${OpenCV_INSTALL_PATH}/bin ${OpenCV_INSTALL_PATH}/bin/Release ${OpenCV_INSTALL_PATH}/bin/Debug ${OpenCV_INSTALL_PATH}/lib NO_DEFAULT_PATH)
+            install(FILES ${${cvFile}Loc} DESTINATION "${jni_lib_dest}")
+        endforeach()
+    endif()
+
+    set_property(TARGET cscore_jar PROPERTY FOLDER "java")
+
+    add_library(cscorejni ${cscore_jni_src})
+    wpilib_target_warnings(cscorejni)
+    target_link_libraries(cscorejni PUBLIC cscore wpiutil ${OpenCV_LIBS})
+
+    set_property(TARGET cscorejni PROPERTY FOLDER "libraries")
+
+    if(${CMAKE_VERSION} VERSION_LESS "3.11.0")
+        target_include_directories(cscorejni PRIVATE ${JNI_INCLUDE_DIRS})
+        target_include_directories(cscorejni PRIVATE "${CMAKE_CURRENT_BINARY_DIR}/jniheaders")
+    else()
+        target_link_libraries(cscorejni PRIVATE cscore_jni_headers)
+    endif()
+    add_dependencies(cscorejni cscore_jar)
+
+    if (MSVC)
+        install(TARGETS cscorejni RUNTIME DESTINATION "${jni_lib_dest}" COMPONENT Runtime)
+    endif()
+
+    install(TARGETS cscorejni EXPORT cscorejni DESTINATION "${main_lib_dest}")
+
+endif()
+
+if (WITH_TESTS)
+    wpilib_add_test(cscore src/test/native/cpp)
+    target_link_libraries(cscore_test cscore gmock)
+endif()
diff --git a/cscore/build.gradle b/cscore/build.gradle
new file mode 100644
index 0000000..9b84031
--- /dev/null
+++ b/cscore/build.gradle
@@ -0,0 +1,137 @@
+import org.gradle.internal.os.OperatingSystem
+
+ext {
+    nativeName = 'cscore'
+    devMain = 'edu.wpi.cscore.DevMain'
+}
+
+// Removed because having the objective-cpp plugin added breaks
+// embedded tools and its toolchain check. It causes an obj-cpp
+// source set to be added to all binaries, even cross binaries
+// with no support.
+// if (OperatingSystem.current().isMacOsX()) {
+//     apply plugin: 'objective-cpp'
+// }
+
+apply from: "${rootDir}/shared/jni/setupBuild.gradle"
+
+ext {
+    sharedCvConfigs = [cscore    : [],
+                       cscoreBase: [],
+                       cscoreDev : [],
+                       cscoreTest: [],
+                       cscoreJNIShared: []]
+    staticCvConfigs = [cscoreJNI: []]
+    useJava = true
+    useCpp = true
+    splitSetup = {
+        if (it.targetPlatform.operatingSystem.isMacOsX()) {
+            it.sources {
+                // macObjCpp(ObjectiveCppSourceSet) {
+                //     source {
+                //         srcDirs = ['src/main/native/objcpp']
+                //         include '**/*.mm'
+                //     }
+                //     exportedHeaders {
+                //         srcDirs 'src/main/native/include'
+                //         include '**/*.h'
+                //     }
+                // }
+                cscoreMacCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/osx'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp'
+                        include '**/*.h'
+                    }
+                }
+            }
+        } else if (it.targetPlatform.operatingSystem.isLinux()) {
+            it.sources {
+                cscoreLinuxCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/linux'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp'
+                        include '**/*.h'
+                    }
+                }
+            }
+        } else if (it.targetPlatform.operatingSystem.isWindows()) {
+            it.sources {
+                cscoreWindowsCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/windows'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp'
+                        include '**/*.h'
+                    }
+                }
+            }
+        }
+    }
+}
+
+def examplesMap = [:];
+
+File examplesTree = file("$projectDir/examples")
+examplesTree.list(new FilenameFilter() {
+    @Override
+    public boolean accept(File current, String name) {
+        return new File(current, name).isDirectory();
+    }
+}).each {
+    sharedCvConfigs.put(it, [])
+    examplesMap.put(it, [])
+}
+
+apply from: "${rootDir}/shared/opencv.gradle"
+
+nativeUtils.exportsConfigs {
+    cscore {
+        x86ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                            '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                            '_TI5?AVfailure', '_CT??_R0?AVout_of_range', '_CTA3?AVout_of_range',
+                            '_TI3?AVout_of_range', '_CT??_R0?AVbad_cast']
+        x64ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                            '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                            '_TI5?AVfailure', '_CT??_R0?AVout_of_range', '_CTA3?AVout_of_range',
+                            '_TI3?AVout_of_range', '_CT??_R0?AVbad_cast']
+    }
+    cscoreJNI {
+        x86SymbolFilter = { symbols ->
+            symbols.removeIf({ !it.startsWith('CS_') })
+        }
+        x64SymbolFilter = { symbols ->
+            symbols.removeIf({ !it.startsWith('CS_') })
+        }
+    }
+}
+
+model {
+    components {
+        examplesMap.each { key, value ->
+            "${key}"(NativeExecutableSpec) {
+                targetBuildTypes 'debug'
+                binaries.all {
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    lib library: 'cscore', linkage: 'shared'
+                }
+                sources {
+                    cpp {
+                        source {
+                            srcDirs 'examples/' + "${key}"
+                            include '**/*.cpp'
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
diff --git a/cscore/cscore-config.cmake.in b/cscore/cscore-config.cmake.in
new file mode 100644
index 0000000..da85e8b
--- /dev/null
+++ b/cscore/cscore-config.cmake.in
@@ -0,0 +1,6 @@
+include(CMakeFindDependencyMacro)
+@FILENAME_DEP_REPLACE@
+@WPIUTIL_DEP_REPLACE@
+find_dependency(OpenCV)
+
+include(${SELF_DIR}/cscore.cmake)
diff --git a/cscore/examples/enum_usb/enum_usb.cpp b/cscore/examples/enum_usb/enum_usb.cpp
new file mode 100644
index 0000000..866e2f1
--- /dev/null
+++ b/cscore/examples/enum_usb/enum_usb.cpp
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "cscore.h"
+
+int main() {
+  CS_Status status = 0;
+  wpi::SmallString<64> buf;
+
+  for (const auto& caminfo : cs::EnumerateUsbCameras(&status)) {
+    wpi::outs() << caminfo.dev << ": " << caminfo.path << " (" << caminfo.name
+                << ")\n";
+    if (!caminfo.otherPaths.empty()) {
+      wpi::outs() << "Other device paths:\n";
+      for (auto&& path : caminfo.otherPaths)
+        wpi::outs() << "  " << path << '\n';
+    }
+
+    cs::UsbCamera camera{"usbcam", caminfo.dev};
+
+    wpi::outs() << "Properties:\n";
+    for (const auto& prop : camera.EnumerateProperties()) {
+      wpi::outs() << "  " << prop.GetName();
+      switch (prop.GetKind()) {
+        case cs::VideoProperty::kBoolean:
+          wpi::outs() << " (bool): "
+                      << "value=" << prop.Get()
+                      << " default=" << prop.GetDefault();
+          break;
+        case cs::VideoProperty::kInteger:
+          wpi::outs() << " (int): "
+                      << "value=" << prop.Get() << " min=" << prop.GetMin()
+                      << " max=" << prop.GetMax() << " step=" << prop.GetStep()
+                      << " default=" << prop.GetDefault();
+          break;
+        case cs::VideoProperty::kString:
+          wpi::outs() << " (string): " << prop.GetString(buf);
+          break;
+        case cs::VideoProperty::kEnum: {
+          wpi::outs() << " (enum): "
+                      << "value=" << prop.Get();
+          auto choices = prop.GetChoices();
+          for (size_t i = 0; i < choices.size(); ++i) {
+            if (choices[i].empty()) continue;
+            wpi::outs() << "\n    " << i << ": " << choices[i];
+          }
+          break;
+        }
+        default:
+          break;
+      }
+      wpi::outs() << '\n';
+    }
+
+    wpi::outs() << "Video Modes:\n";
+    for (const auto& mode : camera.EnumerateVideoModes()) {
+      wpi::outs() << "  PixelFormat:";
+      switch (mode.pixelFormat) {
+        case cs::VideoMode::kMJPEG:
+          wpi::outs() << "MJPEG";
+          break;
+        case cs::VideoMode::kYUYV:
+          wpi::outs() << "YUYV";
+          break;
+        case cs::VideoMode::kRGB565:
+          wpi::outs() << "RGB565";
+          break;
+        default:
+          wpi::outs() << "Unknown";
+          break;
+      }
+      wpi::outs() << " Width:" << mode.width;
+      wpi::outs() << " Height:" << mode.height;
+      wpi::outs() << " FPS:" << mode.fps << '\n';
+    }
+  }
+}
diff --git a/cscore/examples/httpcvstream/httpcvstream.cpp b/cscore/examples/httpcvstream/httpcvstream.cpp
new file mode 100644
index 0000000..90d61d5
--- /dev/null
+++ b/cscore/examples/httpcvstream/httpcvstream.cpp
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <cstdio>
+#include <iostream>
+
+#include <opencv2/core/core.hpp>
+
+#include "cscore.h"
+#include "cscore_cv.h"
+
+int main() {
+  cs::HttpCamera camera{"httpcam", "http://localhost:8081/?action=stream"};
+  camera.SetVideoMode(cs::VideoMode::kMJPEG, 320, 240, 30);
+  cs::CvSink cvsink{"cvsink"};
+  cvsink.SetSource(camera);
+  cs::CvSource cvsource{"cvsource", cs::VideoMode::kMJPEG, 320, 240, 30};
+  cs::MjpegServer cvMjpegServer{"cvhttpserver", 8083};
+  cvMjpegServer.SetSource(cvsource);
+
+  cv::Mat test;
+  cv::Mat flip;
+  for (;;) {
+    uint64_t time = cvsink.GrabFrame(test);
+    if (time == 0) {
+      std::cout << "error: " << cvsink.GetError() << std::endl;
+      continue;
+    }
+    std::cout << "got frame at time " << time << " size " << test.size()
+              << std::endl;
+    cv::flip(test, flip, 0);
+    cvsource.PutFrame(flip);
+  }
+}
diff --git a/cscore/examples/settings/settings.cpp b/cscore/examples/settings/settings.cpp
new file mode 100644
index 0000000..5aa919f
--- /dev/null
+++ b/cscore/examples/settings/settings.cpp
@@ -0,0 +1,104 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <chrono>
+#include <thread>
+
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "cscore.h"
+
+int main(int argc, char** argv) {
+  if (argc < 2) {
+    wpi::errs() << "Usage: settings camera [prop val] ... -- [prop val]...\n";
+    wpi::errs() << "  Example: settings 1 brightness 30 raw_contrast 10\n";
+    return 1;
+  }
+
+  int id;
+  if (wpi::StringRef{argv[1]}.getAsInteger(10, id)) {
+    wpi::errs() << "Expected number for camera\n";
+    return 2;
+  }
+
+  cs::UsbCamera camera{"usbcam", id};
+
+  // Set prior to connect
+  int arg = 2;
+  wpi::StringRef propName;
+  for (; arg < argc && wpi::StringRef{argv[arg]} != "--"; ++arg) {
+    if (propName.empty()) {
+      propName = argv[arg];
+    } else {
+      wpi::StringRef propVal{argv[arg]};
+      int intVal;
+      if (propVal.getAsInteger(10, intVal))
+        camera.GetProperty(propName).SetString(propVal);
+      else
+        camera.GetProperty(propName).Set(intVal);
+      propName = wpi::StringRef{};
+    }
+  }
+  if (arg < argc && wpi::StringRef{argv[arg]} == "--") ++arg;
+
+  // Wait to connect
+  while (!camera.IsConnected())
+    std::this_thread::sleep_for(std::chrono::milliseconds(10));
+
+  // Set rest
+  propName = wpi::StringRef{};
+  for (; arg < argc; ++arg) {
+    if (propName.empty()) {
+      propName = argv[arg];
+    } else {
+      wpi::StringRef propVal{argv[arg]};
+      int intVal;
+      if (propVal.getAsInteger(10, intVal))
+        camera.GetProperty(propName).SetString(propVal);
+      else
+        camera.GetProperty(propName).Set(intVal);
+      propName = wpi::StringRef{};
+    }
+  }
+
+  // Print settings
+  wpi::SmallString<64> buf;
+  wpi::outs() << "Properties:\n";
+  for (const auto& prop : camera.EnumerateProperties()) {
+    wpi::outs() << "  " << prop.GetName();
+    switch (prop.GetKind()) {
+      case cs::VideoProperty::kBoolean:
+        wpi::outs() << " (bool): "
+                    << "value=" << prop.Get()
+                    << " default=" << prop.GetDefault();
+        break;
+      case cs::VideoProperty::kInteger:
+        wpi::outs() << " (int): "
+                    << "value=" << prop.Get() << " min=" << prop.GetMin()
+                    << " max=" << prop.GetMax() << " step=" << prop.GetStep()
+                    << " default=" << prop.GetDefault();
+        break;
+      case cs::VideoProperty::kString:
+        wpi::outs() << " (string): " << prop.GetString(buf);
+        break;
+      case cs::VideoProperty::kEnum: {
+        wpi::outs() << " (enum): "
+                    << "value=" << prop.Get();
+        auto choices = prop.GetChoices();
+        for (size_t i = 0; i < choices.size(); ++i) {
+          if (choices[i].empty()) continue;
+          wpi::outs() << "\n    " << i << ": " << choices[i];
+        }
+        break;
+      }
+      default:
+        break;
+    }
+    wpi::outs() << '\n';
+  }
+}
diff --git a/cscore/examples/usbcvstream/usbcvstream.cpp b/cscore/examples/usbcvstream/usbcvstream.cpp
new file mode 100644
index 0000000..9a4ab06
--- /dev/null
+++ b/cscore/examples/usbcvstream/usbcvstream.cpp
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <cstdio>
+#include <iostream>
+
+#include <opencv2/core/core.hpp>
+
+#include "cscore.h"
+#include "cscore_cv.h"
+
+int main() {
+  cs::UsbCamera camera{"usbcam", 0};
+  camera.SetVideoMode(cs::VideoMode::kMJPEG, 320, 240, 30);
+  cs::MjpegServer mjpegServer{"httpserver", 8081};
+  mjpegServer.SetSource(camera);
+  cs::CvSink cvsink{"cvsink"};
+  cvsink.SetSource(camera);
+  cs::CvSource cvsource{"cvsource", cs::VideoMode::kMJPEG, 320, 240, 30};
+  cs::MjpegServer cvMjpegServer{"cvhttpserver", 8082};
+  cvMjpegServer.SetSource(cvsource);
+
+  cv::Mat test;
+  cv::Mat flip;
+  for (;;) {
+    uint64_t time = cvsink.GrabFrame(test);
+    if (time == 0) {
+      std::cout << "error: " << cvsink.GetError() << std::endl;
+      continue;
+    }
+    std::cout << "got frame at time " << time << " size " << test.size()
+              << std::endl;
+    cv::flip(test, flip, 0);
+    cvsource.PutFrame(flip);
+  }
+}
diff --git a/cscore/examples/usbstream/usbstream.cpp b/cscore/examples/usbstream/usbstream.cpp
new file mode 100644
index 0000000..2f23151
--- /dev/null
+++ b/cscore/examples/usbstream/usbstream.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <cstdio>
+
+#include <wpi/raw_ostream.h>
+
+#include "cscore.h"
+
+int main() {
+  wpi::outs() << "hostname: " << cs::GetHostname() << '\n';
+  wpi::outs() << "IPv4 network addresses:\n";
+  for (const auto& addr : cs::GetNetworkInterfaces())
+    wpi::outs() << "  " << addr << '\n';
+  cs::UsbCamera camera{"usbcam", 0};
+  camera.SetVideoMode(cs::VideoMode::kMJPEG, 320, 240, 30);
+  cs::MjpegServer mjpegServer{"httpserver", 8081};
+  mjpegServer.SetSource(camera);
+
+  CS_Status status = 0;
+  cs::AddListener(
+      [&](const cs::RawEvent& event) {
+        wpi::outs() << "FPS=" << camera.GetActualFPS()
+                    << " MBPS=" << (camera.GetActualDataRate() / 1000000.0)
+                    << '\n';
+      },
+      cs::RawEvent::kTelemetryUpdated, false, &status);
+  cs::SetTelemetryPeriod(1.0);
+
+  std::getchar();
+}
diff --git a/cscore/java-examples/RawCVMatSink.java b/cscore/java-examples/RawCVMatSink.java
new file mode 100644
index 0000000..d9557f7
--- /dev/null
+++ b/cscore/java-examples/RawCVMatSink.java
@@ -0,0 +1,96 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import java.nio.ByteBuffer;
+
+import org.opencv.core.CvType;
+import org.opencv.core.Mat;
+
+import edu.wpi.cscore.VideoMode.PixelFormat;
+import edu.wpi.cscore.raw.RawFrame;
+
+public class RawCVMatSink extends ImageSink {
+  RawFrame frame = new RawFrame();
+  Mat tmpMat;
+  ByteBuffer origByteBuffer;
+  int width;
+  int height;
+  int pixelFormat;
+  int bgrValue = PixelFormat.kBGR.getValue();
+
+  private int getCVFormat(PixelFormat pixelFormat) {
+    int type = 0;
+    switch (pixelFormat) {
+    case kYUYV:
+    case kRGB565:
+      type = CvType.CV_8UC2;
+      break;
+    case kBGR:
+      type = CvType.CV_8UC3;
+      break;
+    case kGray:
+    case kMJPEG:
+    default:
+      type = CvType.CV_8UC1;
+      break;
+    }
+    return type;
+  }
+
+  /**
+   * Create a sink for accepting OpenCV images.
+   * WaitForFrame() must be called on the created sink to get each new
+   * image.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   */
+  public RawCVMatSink(String name) {
+    super(CameraServerJNI.createRawSink(name));
+  }
+
+  /**
+   * Wait for the next frame and get the image.
+   * Times out (returning 0) after 0.225 seconds.
+   * The provided image will have three 3-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message)
+   */
+  public long grabFrame(Mat image) {
+    return grabFrame(image, 0.225);
+  }
+
+  /**
+   * Wait for the next frame and get the image.
+   * Times out (returning 0) after timeout seconds.
+   * The provided image will have three 3-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in 1 us increments.
+   */
+  public long grabFrame(Mat image, double timeout) {
+    frame.setWidth(0);
+    frame.setHeight(0);
+    frame.setPixelFormat(bgrValue);
+    long rv = CameraServerJNI.grabSinkFrameTimeout(m_handle, frame, timeout);
+    if (rv <= 0) {
+      return rv;
+    }
+
+    if (frame.getDataByteBuffer() != origByteBuffer || width != frame.getWidth() || height != frame.getHeight() || pixelFormat != frame.getPixelFormat()) {
+      origByteBuffer = frame.getDataByteBuffer();
+      height = frame.getHeight();
+      width = frame.getWidth();
+      pixelFormat = frame.getPixelFormat();
+      tmpMat = new Mat(frame.getHeight(), frame.getWidth(), getCVFormat(VideoMode.getPixelFormatFromInt(pixelFormat)), origByteBuffer);
+    }
+    tmpMat.copyTo(image);
+    return rv;
+  }
+}
diff --git a/cscore/java-examples/RawCVMatSource.java b/cscore/java-examples/RawCVMatSource.java
new file mode 100644
index 0000000..65bd7d2
--- /dev/null
+++ b/cscore/java-examples/RawCVMatSource.java
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import org.opencv.core.Mat;
+
+import edu.wpi.cscore.VideoMode.PixelFormat;
+
+public class RawCVMatSource extends ImageSource {
+  /**
+   * Create an OpenCV source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param mode Video mode being generated
+   */
+  public RawCVMatSource(String name, VideoMode mode) {
+    super(CameraServerJNI.createRawSource(name,
+        mode.pixelFormat.getValue(),
+        mode.width,
+        mode.height,
+        mode.fps));
+  }
+
+  /**
+   * Create an OpenCV source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param pixelFormat Pixel format
+   * @param width width
+   * @param height height
+   * @param fps fps
+   */
+  public RawCVMatSource(String name, VideoMode.PixelFormat pixelFormat, int width, int height, int fps) {
+    super(CameraServerJNI.createRawSource(name, pixelFormat.getValue(), width, height, fps));
+  }
+
+  /**
+   * Put an OpenCV image and notify sinks.
+   *
+   * <p>Only 8-bit single-channel or 3-channel (with BGR channel order) images
+   * are supported. If the format, depth or channel order is different, use
+   * Mat.convertTo() and/or cvtColor() to convert it first.
+   *
+   * @param image OpenCV image
+   */
+  public void putFrame(Mat image) {
+    int channels = image.channels();
+    if (channels != 1 && channels != 3) {
+      throw new VideoException("Unsupported Image Type");
+    }
+    int imgType = channels == 1 ? PixelFormat.kGray.getValue() : PixelFormat.kBGR.getValue();
+    CameraServerJNI.putRawSourceFrame(m_handle, image.dataAddr(), image.width(), image.height(), imgType, (int)image.total() * channels);
+  }
+}
diff --git a/cscore/src/dev/java/edu/wpi/cscore/DevMain.java b/cscore/src/dev/java/edu/wpi/cscore/DevMain.java
new file mode 100644
index 0000000..51bfd26
--- /dev/null
+++ b/cscore/src/dev/java/edu/wpi/cscore/DevMain.java
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import edu.wpi.first.wpiutil.RuntimeDetector;
+
+public final class DevMain {
+  /**
+   * Main method.
+   */
+  public static void main(String[] args) {
+    System.out.println("Hello World!");
+    System.out.println(RuntimeDetector.getPlatformPath());
+    System.out.println(CameraServerJNI.getHostname());
+  }
+
+  private DevMain() {
+  }
+}
diff --git a/cscore/src/dev/native/cpp/main.cpp b/cscore/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..f27f61f
--- /dev/null
+++ b/cscore/src/dev/native/cpp/main.cpp
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <iostream>
+
+#include "cscore.h"
+
+int main() { std::cout << cs::GetHostname() << std::endl; }
diff --git a/cscore/src/main/java/edu/wpi/cscore/AxisCamera.java b/cscore/src/main/java/edu/wpi/cscore/AxisCamera.java
new file mode 100644
index 0000000..8eef0b3
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/AxisCamera.java
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source that represents an Axis IP camera.
+ */
+public class AxisCamera extends HttpCamera {
+  private static String hostToUrl(String host) {
+    return "http://" + host + "/mjpg/video.mjpg";
+  }
+
+  private static String[] hostToUrl(String[] hosts) {
+    String[] urls = new String[hosts.length];
+    for (int i = 0; i < hosts.length; i++) {
+      urls[i] = hostToUrl(hosts[i]);
+    }
+    return urls;
+  }
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  public AxisCamera(String name, String host) {
+    super(name, hostToUrl(host), HttpCameraKind.kAxis);
+  }
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  public AxisCamera(String name, String[] hosts) {
+    super(name, hostToUrl(hosts), HttpCameraKind.kAxis);
+  }
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/CameraServerCvJNI.java b/cscore/src/main/java/edu/wpi/cscore/CameraServerCvJNI.java
new file mode 100644
index 0000000..78b4ff8
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/CameraServerCvJNI.java
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import java.io.IOException;
+import java.util.concurrent.atomic.AtomicBoolean;
+
+import org.opencv.core.Core;
+
+import edu.wpi.first.wpiutil.RuntimeLoader;
+
+public class CameraServerCvJNI {
+  static boolean libraryLoaded = false;
+
+  static RuntimeLoader<Core> loader = null;
+
+  public static class Helper {
+    private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
+
+    public static boolean getExtractOnStaticLoad() {
+      return extractOnStaticLoad.get();
+    }
+
+    public static void setExtractOnStaticLoad(boolean load) {
+      extractOnStaticLoad.set(load);
+    }
+  }
+
+  static {
+    String opencvName = Core.NATIVE_LIBRARY_NAME;
+    if (Helper.getExtractOnStaticLoad()) {
+      try {
+        CameraServerJNI.forceLoad();
+        loader = new RuntimeLoader<>(opencvName, RuntimeLoader.getDefaultExtractionRoot(), Core.class);
+        loader.loadLibraryHashed();
+      } catch (IOException ex) {
+        ex.printStackTrace();
+        System.exit(1);
+      }
+      libraryLoaded = true;
+    }
+  }
+
+  /**
+   * Force load the library.
+   */
+  public static synchronized void forceLoad() throws IOException {
+    if (libraryLoaded) {
+      return;
+    }
+    CameraServerJNI.forceLoad();
+    loader = new RuntimeLoader<>(Core.NATIVE_LIBRARY_NAME, RuntimeLoader.getDefaultExtractionRoot(), Core.class);
+    loader.loadLibrary();
+    libraryLoaded = true;
+  }
+
+  public static native int createCvSource(String name, int pixelFormat, int width, int height, int fps);
+
+  public static native void putSourceFrame(int source, long imageNativeObj);
+
+  public static native int createCvSink(String name);
+  //public static native int createCvSinkCallback(String name,
+  //                            void (*processFrame)(long time));
+
+  public static native long grabSinkFrame(int sink, long imageNativeObj);
+  public static native long grabSinkFrameTimeout(int sink, long imageNativeObj, double timeout);
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/CameraServerJNI.java b/cscore/src/main/java/edu/wpi/cscore/CameraServerJNI.java
new file mode 100644
index 0000000..ac18408
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/CameraServerJNI.java
@@ -0,0 +1,255 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import java.io.IOException;
+import java.nio.ByteBuffer;
+import java.util.concurrent.atomic.AtomicBoolean;
+import java.util.function.Consumer;
+
+import edu.wpi.cscore.raw.RawFrame;
+import edu.wpi.first.wpiutil.RuntimeLoader;
+
+public class CameraServerJNI {
+  static boolean libraryLoaded = false;
+
+  static RuntimeLoader<CameraServerJNI> loader = null;
+
+  public static class Helper {
+    private static AtomicBoolean extractOnStaticLoad = new AtomicBoolean(true);
+
+    public static boolean getExtractOnStaticLoad() {
+      return extractOnStaticLoad.get();
+    }
+
+    public static void setExtractOnStaticLoad(boolean load) {
+      extractOnStaticLoad.set(load);
+    }
+  }
+
+  static {
+    if (Helper.getExtractOnStaticLoad()) {
+      try {
+        loader = new RuntimeLoader<>("cscorejni", RuntimeLoader.getDefaultExtractionRoot(), CameraServerJNI.class);
+        loader.loadLibrary();
+      } catch (IOException ex) {
+        ex.printStackTrace();
+        System.exit(1);
+      }
+      libraryLoaded = true;
+    }
+  }
+
+  /**
+   * Force load the library.
+   */
+  public static synchronized void forceLoad() throws IOException {
+    if (libraryLoaded) {
+      return;
+    }
+    loader = new RuntimeLoader<>("cscorejni", RuntimeLoader.getDefaultExtractionRoot(), CameraServerJNI.class);
+    loader.loadLibrary();
+    libraryLoaded = true;
+  }
+
+  //
+  // Property Functions
+  //
+  public static native int getPropertyKind(int property);
+  public static native String getPropertyName(int property);
+  public static native int getProperty(int property);
+  public static native void setProperty(int property, int value);
+  public static native int getPropertyMin(int property);
+  public static native int getPropertyMax(int property);
+  public static native int getPropertyStep(int property);
+  public static native int getPropertyDefault(int property);
+  public static native String getStringProperty(int property);
+  public static native void setStringProperty(int property, String value);
+  public static native String[] getEnumPropertyChoices(int property);
+
+  //
+  // Source Creation Functions
+  //
+  public static native int createUsbCameraDev(String name, int dev);
+  public static native int createUsbCameraPath(String name, String path);
+  public static native int createHttpCamera(String name, String url, int kind);
+  public static native int createHttpCameraMulti(String name, String[] urls, int kind);
+  public static native int createRawSource(String name, int pixelFormat, int width, int height, int fps);
+
+  //
+  // Source Functions
+  //
+  public static native int getSourceKind(int source);
+  public static native String getSourceName(int source);
+  public static native String getSourceDescription(int source);
+  public static native long getSourceLastFrameTime(int source);
+  public static native void setSourceConnectionStrategy(int source, int strategy);
+  public static native boolean isSourceConnected(int source);
+  public static native boolean isSourceEnabled(int source);
+  public static native int getSourceProperty(int source, String name);
+  public static native int[] enumerateSourceProperties(int source);
+  public static native VideoMode getSourceVideoMode(int source);
+  public static native boolean setSourceVideoMode(int source, int pixelFormat, int width, int height, int fps);
+  public static native boolean setSourcePixelFormat(int source, int pixelFormat);
+  public static native boolean setSourceResolution(int source, int width, int height);
+  public static native boolean setSourceFPS(int source, int fps);
+  public static native boolean setSourceConfigJson(int source, String config);
+  public static native String getSourceConfigJson(int source);
+  public static native VideoMode[] enumerateSourceVideoModes(int source);
+  public static native int[] enumerateSourceSinks(int source);
+  public static native int copySource(int source);
+  public static native void releaseSource(int source);
+
+  //
+  // Camera Source Common Property Fuctions
+  //
+  public static native void setCameraBrightness(int source, int brightness);
+  public static native int getCameraBrightness(int source);
+  public static native void setCameraWhiteBalanceAuto(int source);
+  public static native void setCameraWhiteBalanceHoldCurrent(int source);
+  public static native void setCameraWhiteBalanceManual(int source, int value);
+  public static native void setCameraExposureAuto(int source);
+  public static native void setCameraExposureHoldCurrent(int source);
+  public static native void setCameraExposureManual(int source, int value);
+
+  //
+  // UsbCamera Source Functions
+  //
+  public static native String getUsbCameraPath(int source);
+  public static native UsbCameraInfo getUsbCameraInfo(int source);
+
+  //
+  // HttpCamera Source Functions
+  //
+  public static native int getHttpCameraKind(int source);
+  public static native void setHttpCameraUrls(int source, String[] urls);
+  public static native String[] getHttpCameraUrls(int source);
+
+  //
+  // Image Source Functions
+  //
+  public static native void putRawSourceFrameBB(int source, ByteBuffer data, int width, int height, int pixelFormat, int totalData);
+  public static native void putRawSourceFrame(int source, long data, int width, int height, int pixelFormat, int totalData);
+  public static void putRawSourceFrame(int source, RawFrame raw) {
+    putRawSourceFrame(source, raw.getDataPtr(), raw.getWidth(), raw.getHeight(), raw.getPixelFormat(), raw.getTotalData());
+  }
+  public static native void notifySourceError(int source, String msg);
+  public static native void setSourceConnected(int source, boolean connected);
+  public static native void setSourceDescription(int source, String description);
+  public static native int createSourceProperty(int source, String name, int kind, int minimum, int maximum, int step, int defaultValue, int value);
+  public static native void setSourceEnumPropertyChoices(int source, int property, String[] choices);
+
+  //
+  // Sink Creation Functions
+  //
+  public static native int createMjpegServer(String name, String listenAddress, int port);
+
+  public static native int createRawSink(String name);
+
+  //
+  // Sink Functions
+  //
+  public static native int getSinkKind(int sink);
+  public static native String getSinkName(int sink);
+  public static native String getSinkDescription(int sink);
+  public static native int getSinkProperty(int sink, String name);
+  public static native int[] enumerateSinkProperties(int sink);
+  public static native boolean setSinkConfigJson(int sink, String config);
+  public static native String getSinkConfigJson(int sink);
+  public static native void setSinkSource(int sink, int source);
+  public static native int getSinkSourceProperty(int sink, String name);
+  public static native int getSinkSource(int sink);
+  public static native int copySink(int sink);
+  public static native void releaseSink(int sink);
+
+  //
+  // MjpegServer Sink Functions
+  //
+  public static native String getMjpegServerListenAddress(int sink);
+  public static native int getMjpegServerPort(int sink);
+
+  //
+  // Image Sink Functions
+  //
+  public static native void setSinkDescription(int sink, String description);
+
+  private static native long grabRawSinkFrameImpl(int sink, RawFrame rawFrame, long rawFramePtr, ByteBuffer byteBuffer, int width, int height, int pixelFormat);
+  private static native long grabRawSinkFrameTimeoutImpl(int sink, RawFrame rawFrame, long rawFramePtr, ByteBuffer byteBuffer, int width, int height, int pixelFormat, double timeout);
+
+  public static long grabSinkFrame(int sink, RawFrame rawFrame) {
+    return grabRawSinkFrameImpl(sink, rawFrame, rawFrame.getFramePtr(), rawFrame.getDataByteBuffer(), rawFrame.getWidth(), rawFrame.getHeight(), rawFrame.getPixelFormat());
+  }
+  public static long grabSinkFrameTimeout(int sink, RawFrame rawFrame, double timeout) {
+    return grabRawSinkFrameTimeoutImpl(sink, rawFrame, rawFrame.getFramePtr(), rawFrame.getDataByteBuffer(), rawFrame.getWidth(), rawFrame.getHeight(), rawFrame.getPixelFormat(), timeout);
+  }
+  public static native String getSinkError(int sink);
+  public static native void setSinkEnabled(int sink, boolean enabled);
+
+  //
+  // Listener Functions
+  //
+  public static native int addListener(Consumer<VideoEvent> listener,
+                                       int eventMask, boolean immediateNotify);
+
+  public static native void removeListener(int handle);
+
+  //
+  // Telemetry Functions
+  //
+  public enum TelemetryKind {
+    kSourceBytesReceived(1),
+    kSourceFramesReceived(2);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    TelemetryKind(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+  public static native void setTelemetryPeriod(double seconds);
+  public static native double getTelemetryElapsedTime();
+  public static native long getTelemetryValue(int handle, int kind);
+  public static long getTelemetryValue(int handle, TelemetryKind kind) {
+    return getTelemetryValue(handle, kind.getValue());
+  }
+  public static native double getTelemetryAverageValue(int handle, int kind);
+  public static double getTelemetryAverageValue(int handle, TelemetryKind kind) {
+    return getTelemetryAverageValue(handle, kind.getValue());
+  }
+
+  //
+  // Logging Functions
+  //
+  @FunctionalInterface
+  public interface LoggerFunction {
+    void apply(int level, String file, int line, String msg);
+  }
+  public static native void setLogger(LoggerFunction func, int minLevel);
+
+  //
+  // Utility Functions
+  //
+  public static native UsbCameraInfo[] enumerateUsbCameras();
+
+  public static native int[] enumerateSources();
+
+  public static native int[] enumerateSinks();
+
+  public static native String getHostname();
+
+  public static native String[] getNetworkInterfaces();
+
+  public static native long allocateRawFrame();
+
+  public static native void freeRawFrame(long frame);
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/CvSink.java b/cscore/src/main/java/edu/wpi/cscore/CvSink.java
new file mode 100644
index 0000000..f12dcc7
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/CvSink.java
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import org.opencv.core.Mat;
+
+/**
+ * A sink for user code to accept video frames as OpenCV images.
+ * These sinks require the WPILib OpenCV builds.
+ * For an alternate OpenCV, see the documentation how to build your own
+ * with RawSink.
+ */
+public class CvSink extends ImageSink {
+  /**
+   * Create a sink for accepting OpenCV images.
+   * WaitForFrame() must be called on the created sink to get each new
+   * image.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   */
+  public CvSink(String name) {
+    super(CameraServerCvJNI.createCvSink(name));
+  }
+
+  /// Create a sink for accepting OpenCV images in a separate thread.
+  /// A thread will be created that calls WaitForFrame() and calls the
+  /// processFrame() callback each time a new frame arrives.
+  /// @param name Source name (arbitrary unique identifier)
+  /// @param processFrame Frame processing function; will be called with a
+  ///        time=0 if an error occurred.  processFrame should call GetImage()
+  ///        or GetError() as needed, but should not call (except in very
+  ///        unusual circumstances) WaitForImage().
+  //public CvSink(wpi::StringRef name,
+  //       std::function<void(uint64_t time)> processFrame) {
+  //  super(CameraServerJNI.createCvSinkCallback(name, processFrame));
+  //}
+
+  /**
+   * Wait for the next frame and get the image.
+   * Times out (returning 0) after 0.225 seconds.
+   * The provided image will have three 3-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message)
+   */
+  public long grabFrame(Mat image) {
+    return grabFrame(image, 0.225);
+  }
+
+  /**
+   * Wait for the next frame and get the image.
+   * Times out (returning 0) after timeout seconds.
+   * The provided image will have three 3-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in 1 us increments.
+   */
+  public long grabFrame(Mat image, double timeout) {
+    return CameraServerCvJNI.grabSinkFrameTimeout(m_handle, image.nativeObj, timeout);
+  }
+
+  /**
+   * Wait for the next frame and get the image.  May block forever.
+   * The provided image will have three 3-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in 1 us increments.
+   */
+  public long grabFrameNoTimeout(Mat image) {
+    return CameraServerCvJNI.grabSinkFrame(m_handle, image.nativeObj);
+  }
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/CvSource.java b/cscore/src/main/java/edu/wpi/cscore/CvSource.java
new file mode 100644
index 0000000..c04d197
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/CvSource.java
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import org.opencv.core.Mat;
+
+/**
+ * A source that represents a video camera.
+ * These sources require the WPILib OpenCV builds.
+ * For an alternate OpenCV, see the documentation how to build your own
+ * with RawSource.
+ */
+public class CvSource extends ImageSource {
+  /**
+   * Create an OpenCV source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param mode Video mode being generated
+   */
+  public CvSource(String name, VideoMode mode) {
+    super(CameraServerCvJNI.createCvSource(name,
+        mode.pixelFormat.getValue(),
+        mode.width,
+        mode.height,
+        mode.fps));
+  }
+
+  /**
+   * Create an OpenCV source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param pixelFormat Pixel format
+   * @param width width
+   * @param height height
+   * @param fps fps
+   */
+  public CvSource(String name, VideoMode.PixelFormat pixelFormat, int width, int height, int fps) {
+    super(CameraServerCvJNI.createCvSource(name, pixelFormat.getValue(), width, height, fps));
+  }
+
+  /**
+   * Put an OpenCV image and notify sinks.
+   *
+   * <p>Only 8-bit single-channel or 3-channel (with BGR channel order) images
+   * are supported. If the format, depth or channel order is different, use
+   * Mat.convertTo() and/or cvtColor() to convert it first.
+   *
+   * @param image OpenCV image
+   */
+  public void putFrame(Mat image) {
+    CameraServerCvJNI.putSourceFrame(m_handle, image.nativeObj);
+  }
+
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/HttpCamera.java b/cscore/src/main/java/edu/wpi/cscore/HttpCamera.java
new file mode 100644
index 0000000..533d00f
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/HttpCamera.java
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source that represents a MJPEG-over-HTTP (IP) camera.
+ */
+public class HttpCamera extends VideoCamera {
+  public enum HttpCameraKind {
+    kUnknown(0), kMJPGStreamer(1), kCSCore(2), kAxis(3);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    HttpCameraKind(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /**
+   * Convert from the numerical representation of kind to an enum type.
+   *
+   * @param kind The numerical representation of kind
+   * @return The kind
+   */
+  public static HttpCameraKind getHttpCameraKindFromInt(int kind) {
+    switch (kind) {
+      case 1: return HttpCameraKind.kMJPGStreamer;
+      case 2: return HttpCameraKind.kCSCore;
+      case 3: return HttpCameraKind.kAxis;
+      default: return HttpCameraKind.kUnknown;
+    }
+  }
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param url Camera URL (e.g. "http://10.x.y.11/video/stream.mjpg")
+   */
+  public HttpCamera(String name, String url) {
+    super(CameraServerJNI.createHttpCamera(name, url, HttpCameraKind.kUnknown.getValue()));
+  }
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param url Camera URL (e.g. "http://10.x.y.11/video/stream.mjpg")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  public HttpCamera(String name, String url, HttpCameraKind kind) {
+    super(CameraServerJNI.createHttpCamera(name, url, kind.getValue()));
+  }
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param urls Array of Camera URLs
+   */
+  public HttpCamera(String name, String[] urls) {
+    super(CameraServerJNI.createHttpCameraMulti(name, urls, HttpCameraKind.kUnknown.getValue()));
+  }
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param urls Array of Camera URLs
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  public HttpCamera(String name, String[] urls, HttpCameraKind kind) {
+    super(CameraServerJNI.createHttpCameraMulti(name, urls, kind.getValue()));
+  }
+
+  /**
+   * Get the kind of HTTP camera.
+   *
+   * <p>Autodetection can result in returning a different value than the camera
+   * was created with.
+   */
+  public HttpCameraKind getHttpCameraKind() {
+    return getHttpCameraKindFromInt(CameraServerJNI.getHttpCameraKind(m_handle));
+  }
+
+  /**
+   * Change the URLs used to connect to the camera.
+   */
+  public void setUrls(String[] urls) {
+    CameraServerJNI.setHttpCameraUrls(m_handle, urls);
+  }
+
+  /**
+   * Get the URLs used to connect to the camera.
+   */
+  public String[] getUrls() {
+    return CameraServerJNI.getHttpCameraUrls(m_handle);
+  }
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/ImageSink.java b/cscore/src/main/java/edu/wpi/cscore/ImageSink.java
new file mode 100644
index 0000000..f755fb6
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/ImageSink.java
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+public abstract class ImageSink extends VideoSink {
+  protected ImageSink(int handle) {
+    super(handle);
+  }
+
+  /**
+   * Set sink description.
+   *
+   * @param description Description
+   */
+  public void setDescription(String description) {
+    CameraServerJNI.setSinkDescription(m_handle, description);
+  }
+
+  /**
+   * Get error string.  Call this if WaitForFrame() returns 0 to determine
+   * what the error is.
+   */
+  public String getError() {
+    return CameraServerJNI.getSinkError(m_handle);
+  }
+
+  /**
+   * Enable or disable getting new frames.
+   * Disabling will cause processFrame (for callback-based CvSinks) to not
+   * be called and WaitForFrame() to not return.  This can be used to save
+   * processor resources when frames are not needed.
+   */
+  public void setEnabled(boolean enabled) {
+    CameraServerJNI.setSinkEnabled(m_handle, enabled);
+  }
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/ImageSource.java b/cscore/src/main/java/edu/wpi/cscore/ImageSource.java
new file mode 100644
index 0000000..3787516
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/ImageSource.java
@@ -0,0 +1,162 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+public abstract class ImageSource extends VideoSource {
+  protected ImageSource(int handle) {
+    super(handle);
+  }
+
+  /**
+   * Signal sinks that an error has occurred.  This should be called instead
+   * of NotifyFrame when an error occurs.
+   */
+  public void notifyError(String msg) {
+    CameraServerJNI.notifySourceError(m_handle, msg);
+  }
+
+  /**
+   * Set source connection status.  Defaults to true.
+   *
+   * @param connected True for connected, false for disconnected
+   */
+  public void setConnected(boolean connected) {
+    CameraServerJNI.setSourceConnected(m_handle, connected);
+  }
+
+  /**
+   * Set source description.
+   *
+   * @param description Description
+   */
+  public void setDescription(String description) {
+    CameraServerJNI.setSourceDescription(m_handle, description);
+  }
+
+  /**
+   * Create a property.
+   *
+   * @param name Property name
+   * @param kind Property kind
+   * @param minimum Minimum value
+   * @param maximum Maximum value
+   * @param step Step value
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  public VideoProperty createProperty(String name,
+                                      VideoProperty.Kind kind,
+                                      int minimum,
+                                      int maximum,
+                                      int step,
+                                      int defaultValue,
+                                      int value) {
+    return new VideoProperty(
+        CameraServerJNI.createSourceProperty(m_handle,
+            name,
+            kind.getValue(),
+            minimum,
+            maximum,
+            step,
+            defaultValue,
+            value));
+  }
+
+  /**
+   * Create an integer property.
+   *
+   * @param name Property name
+   * @param minimum Minimum value
+   * @param maximum Maximum value
+   * @param step Step value
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  public VideoProperty createIntegerProperty(String name,
+                                             int minimum,
+                                             int maximum,
+                                             int step,
+                                             int defaultValue,
+                                             int value) {
+    return new VideoProperty(
+        CameraServerJNI.createSourceProperty(m_handle,
+            name,
+            VideoProperty.Kind.kInteger.getValue(),
+            minimum,
+            maximum,
+            step,
+            defaultValue,
+            value));
+  }
+
+  /**
+   * Create a boolean property.
+   *
+   * @param name Property name
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  public VideoProperty createBooleanProperty(String name, boolean defaultValue, boolean value) {
+    return new VideoProperty(
+        CameraServerJNI.createSourceProperty(m_handle,
+            name,
+            VideoProperty.Kind.kBoolean.getValue(),
+            0,
+            1,
+            1,
+            defaultValue ? 1 : 0,
+            value ? 1 : 0));
+  }
+
+  /**
+   * Create a string property.
+   *
+   * @param name Property name
+   * @param value Current value
+   * @return Property
+   */
+  public VideoProperty createStringProperty(String name, String value) {
+    VideoProperty prop = new VideoProperty(
+        CameraServerJNI.createSourceProperty(m_handle,
+            name,
+            VideoProperty.Kind.kString.getValue(),
+            0,
+            0,
+            0,
+            0,
+            0));
+    prop.setString(value);
+    return prop;
+  }
+
+  /**
+   * Configure enum property choices.
+   *
+   * @param property Property
+   * @param choices Choices
+   */
+  public void setEnumPropertyChoices(VideoProperty property, String[] choices) {
+    CameraServerJNI.setSourceEnumPropertyChoices(m_handle, property.m_handle, choices);
+  }
+
+  /**
+   * Configure enum property choices.
+   *
+   * @param property Property
+   * @param choices Choices
+   * @deprecated Use {@code setEnumPropertyChoices} instead.
+   */
+  @Deprecated
+  @SuppressWarnings("MethodName")
+  public void SetEnumPropertyChoices(VideoProperty property, String[] choices) {
+    setEnumPropertyChoices(property, choices);
+  }
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/MjpegServer.java b/cscore/src/main/java/edu/wpi/cscore/MjpegServer.java
new file mode 100644
index 0000000..4c00aed
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/MjpegServer.java
@@ -0,0 +1,104 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A sink that acts as a MJPEG-over-HTTP network server.
+ */
+public class MjpegServer extends VideoSink {
+  /**
+   * Create a MJPEG-over-HTTP server sink.
+   *
+   * @param name Sink name (arbitrary unique identifier)
+   * @param listenAddress TCP listen address (empty string for all addresses)
+   * @param port TCP port number
+   */
+  public MjpegServer(String name, String listenAddress, int port) {
+    super(CameraServerJNI.createMjpegServer(name, listenAddress, port));
+  }
+
+  /**
+   * Create a MJPEG-over-HTTP server sink.
+   *
+   * @param name Sink name (arbitrary unique identifier)
+   * @param port TCP port number
+   */
+  public MjpegServer(String name, int port) {
+    this(name, "", port);
+  }
+
+  /**
+   * Get the listen address of the server.
+   */
+  public String getListenAddress() {
+    return CameraServerJNI.getMjpegServerListenAddress(m_handle);
+  }
+
+  /**
+   * Get the port number of the server.
+   */
+  public int getPort() {
+    return CameraServerJNI.getMjpegServerPort(m_handle);
+  }
+
+  /**
+   * Set the stream resolution for clients that don't specify it.
+   *
+   * <p>It is not necessary to set this if it is the same as the source
+   * resolution.
+   *
+   * <p>Setting this different than the source resolution will result in
+   * increased CPU usage, particularly for MJPEG source cameras, as it will
+   * decompress, resize, and recompress the image, instead of using the
+   * camera's MJPEG image directly.
+   *
+   * @param width width, 0 for unspecified
+   * @param height height, 0 for unspecified
+   */
+  public void setResolution(int width, int height) {
+    CameraServerJNI.setProperty(CameraServerJNI.getSinkProperty(m_handle, "width"), width);
+    CameraServerJNI.setProperty(CameraServerJNI.getSinkProperty(m_handle, "height"), height);
+  }
+
+  /**
+   * Set the stream frames per second (FPS) for clients that don't specify it.
+   *
+   * <p>It is not necessary to set this if it is the same as the source FPS.
+   *
+   * @param fps FPS, 0 for unspecified
+   */
+  public void setFPS(int fps) {
+    CameraServerJNI.setProperty(CameraServerJNI.getSinkProperty(m_handle, "fps"), fps);
+  }
+
+  /**
+   * Set the compression for clients that don't specify it.
+   *
+   * <p>Setting this will result in increased CPU usage for MJPEG source cameras
+   * as it will decompress and recompress the image instead of using the
+   * camera's MJPEG image directly.
+   *
+   * @param quality JPEG compression quality (0-100), -1 for unspecified
+   */
+  public void setCompression(int quality) {
+    CameraServerJNI.setProperty(CameraServerJNI.getSinkProperty(m_handle, "compression"),
+                                quality);
+  }
+
+  /**
+   * Set the default compression used for non-MJPEG sources.  If not set,
+   * 80 is used.  This function has no effect on MJPEG source cameras; use
+   * SetCompression() instead to force recompression of MJPEG source images.
+   *
+   * @param quality JPEG compression quality (0-100)
+   */
+  public void setDefaultCompression(int quality) {
+    CameraServerJNI.setProperty(CameraServerJNI.getSinkProperty(m_handle, "default_compression"),
+                                quality);
+  }
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/UsbCamera.java b/cscore/src/main/java/edu/wpi/cscore/UsbCamera.java
new file mode 100644
index 0000000..fc80047
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/UsbCamera.java
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source that represents a USB camera.
+ */
+public class UsbCamera extends VideoCamera {
+  /**
+   * Create a source for a USB camera based on device number.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param dev Device number (e.g. 0 for /dev/video0)
+   */
+  public UsbCamera(String name, int dev) {
+    super(CameraServerJNI.createUsbCameraDev(name, dev));
+  }
+
+  /**
+   * Create a source for a USB camera based on device path.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param path Path to device (e.g. "/dev/video0" on Linux)
+   */
+  public UsbCamera(String name, String path) {
+    super(CameraServerJNI.createUsbCameraPath(name, path));
+  }
+
+  /**
+   * Enumerate USB cameras on the local system.
+   *
+   * @return Vector of USB camera information (one for each camera)
+   */
+  public static UsbCameraInfo[] enumerateUsbCameras() {
+    return CameraServerJNI.enumerateUsbCameras();
+  }
+
+  /**
+   * Get the path to the device.
+   */
+  public String getPath() {
+    return CameraServerJNI.getUsbCameraPath(m_handle);
+  }
+
+  /**
+   * Get the full camera information for the device.
+   */
+  public UsbCameraInfo getInfo() {
+    return CameraServerJNI.getUsbCameraInfo(m_handle);
+  }
+
+  /**
+   * Set how verbose the camera connection messages are.
+   *
+   * @param level 0=don't display Connecting message, 1=do display message
+   */
+  public void setConnectVerbose(int level) {
+    CameraServerJNI.setProperty(CameraServerJNI.getSourceProperty(m_handle, "connect_verbose"),
+                                level);
+  }
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/UsbCameraInfo.java b/cscore/src/main/java/edu/wpi/cscore/UsbCameraInfo.java
new file mode 100644
index 0000000..c3a8309
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/UsbCameraInfo.java
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * USB camera information.
+ */
+public class UsbCameraInfo {
+  /**
+   * Create a new set of UsbCameraInfo.
+   *
+   * @param dev Device number (e.g. N in '/dev/videoN' on Linux)
+   * @param path Path to device if available (e.g. '/dev/video0' on Linux)
+   * @param name Vendor/model name of the camera as provided by the USB driver
+   * @param otherPaths Other path aliases to device
+   * @param vendorId USB vendor id
+   * @param productId USB product id
+   */
+  @SuppressWarnings("PMD.ArrayIsStoredDirectly")
+  public UsbCameraInfo(int dev, String path, String name, String[] otherPaths, int vendorId,
+      int productId) {
+    this.dev = dev;
+    this.path = path;
+    this.name = name;
+    this.otherPaths = otherPaths;
+    this.vendorId = vendorId;
+    this.productId = productId;
+  }
+
+  /**
+   * Device number (e.g. N in '/dev/videoN' on Linux).
+   */
+  @SuppressWarnings("MemberName")
+  public int dev;
+
+  /**
+   * Path to device if available (e.g. '/dev/video0' on Linux).
+   */
+  @SuppressWarnings("MemberName")
+  public String path;
+
+  /**
+   * Vendor/model name of the camera as provided by the USB driver.
+   */
+  @SuppressWarnings("MemberName")
+  public String name;
+
+  /**
+   * Other path aliases to device (e.g. '/dev/v4l/by-id/...' etc on Linux).
+   */
+  @SuppressWarnings("MemberName")
+  public String[] otherPaths;
+
+  /**
+   * USB vendor id.
+   */
+  @SuppressWarnings("MemberName")
+  public int vendorId;
+
+  /**
+   * USB product id.
+   */
+  @SuppressWarnings("MemberName")
+  public int productId;
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/VideoCamera.java b/cscore/src/main/java/edu/wpi/cscore/VideoCamera.java
new file mode 100644
index 0000000..0ab95f1
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/VideoCamera.java
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source that represents a video camera.
+ */
+public class VideoCamera extends VideoSource {
+  public static class WhiteBalance {
+    public static final int kFixedIndoor = 3000;
+    public static final int kFixedOutdoor1 = 4000;
+    public static final int kFixedOutdoor2 = 5000;
+    public static final int kFixedFluorescent1 = 5100;
+    public static final int kFixedFlourescent2 = 5200;
+  }
+
+  protected VideoCamera(int handle) {
+    super(handle);
+  }
+
+  /**
+   * Set the brightness, as a percentage (0-100).
+   */
+  public synchronized void setBrightness(int brightness) {
+    CameraServerJNI.setCameraBrightness(m_handle, brightness);
+  }
+
+  /**
+   * Get the brightness, as a percentage (0-100).
+   */
+  public synchronized int getBrightness() {
+    return CameraServerJNI.getCameraBrightness(m_handle);
+  }
+
+  /**
+   * Set the white balance to auto.
+   */
+  public synchronized void setWhiteBalanceAuto() {
+    CameraServerJNI.setCameraWhiteBalanceAuto(m_handle);
+  }
+
+  /**
+   * Set the white balance to hold current.
+   */
+  public synchronized void setWhiteBalanceHoldCurrent() {
+    CameraServerJNI.setCameraWhiteBalanceHoldCurrent(m_handle);
+  }
+
+  /**
+   * Set the white balance to manual, with specified color temperature.
+   */
+  public synchronized void setWhiteBalanceManual(int value) {
+    CameraServerJNI.setCameraWhiteBalanceManual(m_handle, value);
+  }
+
+  /**
+   * Set the exposure to auto aperture.
+   */
+  public synchronized void setExposureAuto() {
+    CameraServerJNI.setCameraExposureAuto(m_handle);
+  }
+
+  /**
+   * Set the exposure to hold current.
+   */
+  public synchronized void setExposureHoldCurrent() {
+    CameraServerJNI.setCameraExposureHoldCurrent(m_handle);
+  }
+
+  /**
+   * Set the exposure to manual, as a percentage (0-100).
+   */
+  public synchronized void setExposureManual(int value) {
+    CameraServerJNI.setCameraExposureManual(m_handle, value);
+  }
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/VideoEvent.java b/cscore/src/main/java/edu/wpi/cscore/VideoEvent.java
new file mode 100644
index 0000000..7f4599d
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/VideoEvent.java
@@ -0,0 +1,133 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * Video event.
+ */
+public class VideoEvent {
+  public enum Kind {
+    kUnknown(0x0000),
+    kSourceCreated(0x0001),
+    kSourceDestroyed(0x0002),
+    kSourceConnected(0x0004),
+    kSourceDisconnected(0x0008),
+    kSourceVideoModesUpdated(0x0010),
+    kSourceVideoModeChanged(0x0020),
+    kSourcePropertyCreated(0x0040),
+    kSourcePropertyValueUpdated(0x0080),
+    kSourcePropertyChoicesUpdated(0x0100),
+    kSinkSourceChanged(0x0200),
+    kSinkCreated(0x0400),
+    kSinkDestroyed(0x0800),
+    kSinkEnabled(0x1000),
+    kSinkDisabled(0x2000),
+    kNetworkInterfacesChanged(0x4000),
+    kTelemetryUpdated(0x8000),
+    kSinkPropertyCreated(0x10000),
+    kSinkPropertyValueUpdated(0x20000),
+    kSinkPropertyChoicesUpdated(0x40000);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    Kind(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /**
+   * Convert from the numerical representation of kind to an enum type.
+   *
+   * @param kind The numerical representation of kind
+   * @return The kind
+   */
+  @SuppressWarnings("PMD.CyclomaticComplexity")
+  public static Kind getKindFromInt(int kind) {
+    switch (kind) {
+      case 0x0001: return Kind.kSourceCreated;
+      case 0x0002: return Kind.kSourceDestroyed;
+      case 0x0004: return Kind.kSourceConnected;
+      case 0x0008: return Kind.kSourceDisconnected;
+      case 0x0010: return Kind.kSourceVideoModesUpdated;
+      case 0x0020: return Kind.kSourceVideoModeChanged;
+      case 0x0040: return Kind.kSourcePropertyCreated;
+      case 0x0080: return Kind.kSourcePropertyValueUpdated;
+      case 0x0100: return Kind.kSourcePropertyChoicesUpdated;
+      case 0x0200: return Kind.kSinkSourceChanged;
+      case 0x0400: return Kind.kSinkCreated;
+      case 0x0800: return Kind.kSinkDestroyed;
+      case 0x1000: return Kind.kSinkEnabled;
+      case 0x2000: return Kind.kSinkDisabled;
+      case 0x4000: return Kind.kNetworkInterfacesChanged;
+      case 0x10000: return Kind.kSinkPropertyCreated;
+      case 0x20000: return Kind.kSinkPropertyValueUpdated;
+      case 0x40000: return Kind.kSinkPropertyChoicesUpdated;
+      default: return Kind.kUnknown;
+    }
+  }
+
+  @SuppressWarnings("PMD.ExcessiveParameterList")
+  VideoEvent(int kind, int source, int sink, String name, int pixelFormat,
+             int width, int height, int fps, int property, int propertyKind,
+             int value, String valueStr) {
+    this.kind = getKindFromInt(kind);
+    this.sourceHandle = source;
+    this.sinkHandle = sink;
+    this.name = name;
+    this.mode = new VideoMode(pixelFormat, width, height, fps);
+    this.propertyHandle = property;
+    this.propertyKind = VideoProperty.getKindFromInt(propertyKind);
+    this.value = value;
+    this.valueStr = valueStr;
+  }
+
+  @SuppressWarnings("MemberName")
+  public Kind kind;
+
+  // Valid for kSource* and kSink* respectively
+  @SuppressWarnings("MemberName")
+  public int sourceHandle;
+  @SuppressWarnings("MemberName")
+  public int sinkHandle;
+
+  // Source/sink/property name
+  @SuppressWarnings("MemberName")
+  public String name;
+
+  // Fields for kSourceVideoModeChanged event
+  @SuppressWarnings("MemberName")
+  public VideoMode mode;
+
+  // Fields for kSourceProperty* events
+  @SuppressWarnings("MemberName")
+  public int propertyHandle;
+  @SuppressWarnings("MemberName")
+  public VideoProperty.Kind propertyKind;
+  @SuppressWarnings("MemberName")
+  public int value;
+  @SuppressWarnings("MemberName")
+  public String valueStr;
+
+  public VideoSource getSource() {
+    return new VideoSource(CameraServerJNI.copySource(sourceHandle));
+  }
+
+  public VideoSink getSink() {
+    return new VideoSink(CameraServerJNI.copySink(sinkHandle));
+  }
+
+  public VideoProperty getProperty() {
+    return new VideoProperty(propertyHandle, propertyKind);
+  }
+
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/VideoException.java b/cscore/src/main/java/edu/wpi/cscore/VideoException.java
new file mode 100644
index 0000000..8c35517
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/VideoException.java
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * An exception raised by the camera server.
+ */
+public class VideoException extends RuntimeException {
+  private static final long serialVersionUID = -9155939328084105145L;
+
+  public VideoException(String msg) {
+    super(msg);
+  }
+
+  @Override
+  public String toString() {
+    return "VideoException [" + super.toString() + "]";
+  }
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/VideoListener.java b/cscore/src/main/java/edu/wpi/cscore/VideoListener.java
new file mode 100644
index 0000000..2a35505
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/VideoListener.java
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import java.util.function.Consumer;
+
+/**
+ * An event listener.  This calls back to a desigated callback function when
+ * an event matching the specified mask is generated by the library.
+ */
+public class VideoListener implements AutoCloseable {
+  /**
+   * Create an event listener.
+   *
+   * @param listener Listener function
+   * @param eventMask Bitmask of VideoEvent.Type values
+   * @param immediateNotify Whether callback should be immediately called with
+   *        a representative set of events for the current library state.
+   */
+  public VideoListener(Consumer<VideoEvent> listener, int eventMask,
+                       boolean immediateNotify) {
+    m_handle = CameraServerJNI.addListener(listener, eventMask, immediateNotify);
+  }
+
+  @Override
+  public synchronized void close() {
+    if (m_handle != 0) {
+      CameraServerJNI.removeListener(m_handle);
+    }
+    m_handle = 0;
+  }
+
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  private int m_handle;
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/VideoMode.java b/cscore/src/main/java/edu/wpi/cscore/VideoMode.java
new file mode 100644
index 0000000..dec4686
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/VideoMode.java
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * Video mode.
+ */
+public class VideoMode {
+  public enum PixelFormat {
+    kUnknown(0), kMJPEG(1), kYUYV(2), kRGB565(3), kBGR(4), kGray(5);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    PixelFormat(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  private static final PixelFormat[] m_pixelFormatValues = PixelFormat.values();
+
+  public static PixelFormat getPixelFormatFromInt(int pixelFormat) {
+    return m_pixelFormatValues[pixelFormat];
+  }
+
+  /**
+   * Create a new video mode.
+   */
+  public VideoMode(int pixelFormat, int width, int height, int fps) {
+    this.pixelFormat = getPixelFormatFromInt(pixelFormat);
+    this.width = width;
+    this.height = height;
+    this.fps = fps;
+  }
+
+  /**
+   * Create a new video mode.
+   */
+  public VideoMode(PixelFormat pixelFormat, int width, int height, int fps) {
+    this.pixelFormat = pixelFormat;
+    this.width = width;
+    this.height = height;
+    this.fps = fps;
+  }
+
+  /**
+   * Pixel format.
+   */
+  @SuppressWarnings("MemberName")
+  public PixelFormat pixelFormat;
+
+  /**
+   * Width in pixels.
+   */
+  @SuppressWarnings("MemberName")
+  public int width;
+
+  /**
+   * Height in pixels.
+   */
+  @SuppressWarnings("MemberName")
+  public int height;
+
+  /**
+   * Frames per second.
+   */
+  @SuppressWarnings("MemberName")
+  public int fps;
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/VideoProperty.java b/cscore/src/main/java/edu/wpi/cscore/VideoProperty.java
new file mode 100644
index 0000000..407e107
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/VideoProperty.java
@@ -0,0 +1,124 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source or sink property.
+ */
+public class VideoProperty {
+  public enum Kind {
+    kNone(0), kBoolean(1), kInteger(2), kString(4), kEnum(8);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    Kind(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /**
+   * Convert from the numerical representation of kind to an enum type.
+   *
+   * @param kind The numerical representation of kind
+   * @return The kind
+   */
+  public static Kind getKindFromInt(int kind) {
+    switch (kind) {
+      case 1: return Kind.kBoolean;
+      case 2: return Kind.kInteger;
+      case 4: return Kind.kString;
+      case 8: return Kind.kEnum;
+      default: return Kind.kNone;
+    }
+  }
+
+  public String getName() {
+    return CameraServerJNI.getPropertyName(m_handle);
+  }
+
+  public Kind getKind() {
+    return m_kind;
+  }
+
+  public boolean isValid() {
+    return m_kind != Kind.kNone;
+  }
+
+  // Kind checkers
+  public boolean isBoolean() {
+    return m_kind == Kind.kBoolean;
+  }
+
+  public boolean isInteger() {
+    return m_kind == Kind.kInteger;
+  }
+
+  public boolean isString() {
+    return m_kind == Kind.kString;
+  }
+
+  public boolean isEnum() {
+    return m_kind == Kind.kEnum;
+  }
+
+  public int get() {
+    return CameraServerJNI.getProperty(m_handle);
+  }
+
+  public void set(int value) {
+    CameraServerJNI.setProperty(m_handle, value);
+  }
+
+  public int getMin() {
+    return CameraServerJNI.getPropertyMin(m_handle);
+  }
+
+  public int getMax() {
+    return CameraServerJNI.getPropertyMax(m_handle);
+  }
+
+  public int getStep() {
+    return CameraServerJNI.getPropertyStep(m_handle);
+  }
+
+  public int getDefault() {
+    return CameraServerJNI.getPropertyDefault(m_handle);
+  }
+
+  // String-specific functions
+  public String getString() {
+    return CameraServerJNI.getStringProperty(m_handle);
+  }
+
+  public void setString(String value) {
+    CameraServerJNI.setStringProperty(m_handle, value);
+  }
+
+  // Enum-specific functions
+  public String[] getChoices() {
+    return CameraServerJNI.getEnumPropertyChoices(m_handle);
+  }
+
+  VideoProperty(int handle) {
+    m_handle = handle;
+    m_kind = getKindFromInt(CameraServerJNI.getPropertyKind(handle));
+  }
+
+  VideoProperty(int handle, Kind kind) {
+    m_handle = handle;
+    m_kind = kind;
+  }
+
+  int m_handle;
+  private Kind m_kind;
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/VideoSink.java b/cscore/src/main/java/edu/wpi/cscore/VideoSink.java
new file mode 100644
index 0000000..107f6d9
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/VideoSink.java
@@ -0,0 +1,217 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source for video that provides a sequence of frames.  Each frame may
+ * consist of multiple images (e.g. from a stereo or depth camera); these
+ * are called channels.
+ */
+public class VideoSink implements AutoCloseable {
+  public enum Kind {
+    kUnknown(0), kMjpeg(2), kCv(4), kRaw(8);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    Kind(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /**
+   * Convert from the numerical representation of kind to an enum type.
+   *
+   * @param kind The numerical representation of kind
+   * @return The kind
+   */
+  public static Kind getKindFromInt(int kind) {
+    switch (kind) {
+      case 2: return Kind.kMjpeg;
+      case 4: return Kind.kCv;
+      default: return Kind.kUnknown;
+    }
+  }
+
+  protected VideoSink(int handle) {
+    m_handle = handle;
+  }
+
+  @Override
+  public synchronized void close() {
+    if (m_handle != 0) {
+      CameraServerJNI.releaseSink(m_handle);
+    }
+    m_handle = 0;
+  }
+
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  public int getHandle() {
+    return m_handle;
+  }
+
+  @Override
+  public boolean equals(Object other) {
+    if (this == other) {
+      return true;
+    }
+    if (other == null) {
+      return false;
+    }
+    if (getClass() != other.getClass()) {
+      return false;
+    }
+    VideoSink sink = (VideoSink) other;
+    return m_handle == sink.m_handle;
+  }
+
+  @Override
+  public int hashCode() {
+    return m_handle;
+  }
+
+  /**
+   * Get the kind of the sink.
+   */
+  public Kind getKind() {
+    return getKindFromInt(CameraServerJNI.getSinkKind(m_handle));
+  }
+
+  /**
+   * Get the name of the sink.  The name is an arbitrary identifier
+   * provided when the sink is created, and should be unique.
+   */
+  public String getName() {
+    return CameraServerJNI.getSinkName(m_handle);
+  }
+
+  /**
+   * Get the sink description.  This is sink-kind specific.
+   */
+  public String getDescription() {
+    return CameraServerJNI.getSinkDescription(m_handle);
+  }
+
+  /**
+   * Get a property of the sink.
+   *
+   * @param name Property name
+   * @return Property (kind Property::kNone if no property with
+   *         the given name exists)
+   */
+  public VideoProperty getProperty(String name) {
+    return new VideoProperty(CameraServerJNI.getSinkProperty(m_handle, name));
+  }
+
+  /**
+   * Enumerate all properties of this sink.
+   */
+  @SuppressWarnings("PMD.AvoidInstantiatingObjectsInLoops")
+  public VideoProperty[] enumerateProperties() {
+    int[] handles = CameraServerJNI.enumerateSinkProperties(m_handle);
+    VideoProperty[] rv = new VideoProperty[handles.length];
+    for (int i = 0; i < handles.length; i++) {
+      rv[i] = new VideoProperty(handles[i]);
+    }
+    return rv;
+  }
+
+  /**
+   * Set properties from a JSON configuration string.
+   *
+   * <p>The format of the JSON input is:
+   *
+   * <pre>
+   * {
+   *     "properties": [
+   *         {
+   *             "name": property name
+   *             "value": property value
+   *         }
+   *     ]
+   * }
+   * </pre>
+   *
+   * @param config configuration
+   * @return True if set successfully
+   */
+  public boolean setConfigJson(String config) {
+    return CameraServerJNI.setSinkConfigJson(m_handle, config);
+  }
+
+  /**
+   * Get a JSON configuration string.
+   *
+   * @return JSON configuration string
+   */
+  public String getConfigJson() {
+    return CameraServerJNI.getSinkConfigJson(m_handle);
+  }
+
+  /**
+   * Configure which source should provide frames to this sink.  Each sink
+   * can accept frames from only a single source, but a single source can
+   * provide frames to multiple clients.
+   *
+   * @param source Source
+   */
+  public void setSource(VideoSource source) {
+    if (source == null) {
+      CameraServerJNI.setSinkSource(m_handle, 0);
+    } else {
+      CameraServerJNI.setSinkSource(m_handle, source.m_handle);
+    }
+  }
+
+  /**
+   * Get the connected source.
+   *
+   * @return Connected source; nullptr if no source connected.
+   */
+  public VideoSource getSource() {
+    // While VideoSource.close() will call releaseSource(), getSinkSource()
+    // increments the internal reference count so this is okay to do.
+    return new VideoSource(CameraServerJNI.getSinkSource(m_handle));
+  }
+
+  /**
+   * Get a property of the associated source.
+   *
+   * @param name Property name
+   * @return Property (kind Property::kNone if no property with
+   *         the given name exists or no source connected)
+   */
+  public VideoProperty getSourceProperty(String name) {
+    return new VideoProperty(
+        CameraServerJNI.getSinkSourceProperty(m_handle, name));
+  }
+
+  /**
+   * Enumerate all existing sinks.
+   *
+   * @return Vector of sinks.
+   */
+  @SuppressWarnings("PMD.AvoidInstantiatingObjectsInLoops")
+  public static VideoSink[] enumerateSinks() {
+    int[] handles = CameraServerJNI.enumerateSinks();
+    VideoSink[] rv = new VideoSink[handles.length];
+    for (int i = 0; i < handles.length; i++) {
+      rv[i] = new VideoSink(handles[i]);
+    }
+    return rv;
+  }
+
+  protected int m_handle;
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/VideoSource.java b/cscore/src/main/java/edu/wpi/cscore/VideoSource.java
new file mode 100644
index 0000000..51d3821
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/VideoSource.java
@@ -0,0 +1,371 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source for video that provides a sequence of frames.  Each frame may
+ * consist of multiple images (e.g. from a stereo or depth camera); these
+ * are called channels.
+ */
+public class VideoSource implements AutoCloseable {
+  public enum Kind {
+    kUnknown(0), kUsb(1), kHttp(2), kCv(4), kRaw(8);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    Kind(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /**
+   * Connection strategy.
+   */
+  public enum ConnectionStrategy {
+    /**
+     * Automatically connect or disconnect based on whether any sinks are
+     * connected to this source.  This is the default behavior.
+     */
+    kAutoManage(0),
+
+    /**
+     * Try to keep the connection open regardless of whether any sinks are
+     * connected.
+     */
+    kKeepOpen(1),
+
+    /**
+     * Never open the connection.  If this is set when the connection is open,
+     * close the connection.
+     */
+    kForceClose(2);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    ConnectionStrategy(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /**
+   * Convert from the numerical representation of kind to an enum type.
+   *
+   * @param kind The numerical representation of kind
+   * @return The kind
+   */
+  public static Kind getKindFromInt(int kind) {
+    switch (kind) {
+      case 1: return Kind.kUsb;
+      case 2: return Kind.kHttp;
+      case 4: return Kind.kCv;
+      default: return Kind.kUnknown;
+    }
+  }
+
+  protected VideoSource(int handle) {
+    m_handle = handle;
+  }
+
+  @Override
+  public synchronized void close() {
+    if (m_handle != 0) {
+      CameraServerJNI.releaseSource(m_handle);
+    }
+    m_handle = 0;
+  }
+
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  public int getHandle() {
+    return m_handle;
+  }
+
+  @Override
+  public boolean equals(Object other) {
+    if (this == other) {
+      return true;
+    }
+    if (other == null) {
+      return false;
+    }
+    if (getClass() != other.getClass()) {
+      return false;
+    }
+    VideoSource source = (VideoSource) other;
+    return m_handle == source.m_handle;
+  }
+
+  @Override
+  public int hashCode() {
+    return m_handle;
+  }
+
+  /**
+   * Get the kind of the source.
+   */
+  public Kind getKind() {
+    return getKindFromInt(CameraServerJNI.getSourceKind(m_handle));
+  }
+
+  /**
+   * Get the name of the source.  The name is an arbitrary identifier
+   * provided when the source is created, and should be unique.
+   */
+  public String getName() {
+    return CameraServerJNI.getSourceName(m_handle);
+  }
+
+  /**
+   * Get the source description.  This is source-kind specific.
+   */
+  public String getDescription() {
+    return CameraServerJNI.getSourceDescription(m_handle);
+  }
+
+  /**
+   * Get the last time a frame was captured.
+   * @return Time in 1 us increments.
+   */
+  public long getLastFrameTime() {
+    return CameraServerJNI.getSourceLastFrameTime(m_handle);
+  }
+
+  /**
+   * Sets the connection strategy.  By default, the source will automatically
+   * connect or disconnect based on whether any sinks are connected.
+   *
+   * <p>This function is non-blocking; look for either a connection open or
+   * close event or call {@link #isConnected()} to determine the connection
+   * state.
+   *
+   * @param strategy connection strategy (auto, keep open, or force close)
+   */
+  public void setConnectionStrategy(ConnectionStrategy strategy) {
+    CameraServerJNI.setSourceConnectionStrategy(m_handle, strategy.getValue());
+  }
+
+  /**
+   * Returns if the source currently connected to whatever is providing the images.
+   */
+  public boolean isConnected() {
+    return CameraServerJNI.isSourceConnected(m_handle);
+  }
+
+  /**
+   * Gets source enable status.  This is determined with a combination of
+   * connection strategy and the number of sinks connected.
+   *
+   * @return True if enabled, false otherwise.
+   */
+  public boolean isEnabled() {
+    return CameraServerJNI.isSourceEnabled(m_handle);
+  }
+
+  /**
+   * Get a property.
+   *
+   * @param name Property name
+   * @return Property contents (of kind Property::kNone if no property with
+   *         the given name exists)
+   */
+  public VideoProperty getProperty(String name) {
+    return new VideoProperty(CameraServerJNI.getSourceProperty(m_handle, name));
+  }
+
+  /**
+   * Enumerate all properties of this source.
+   */
+  @SuppressWarnings("PMD.AvoidInstantiatingObjectsInLoops")
+  public VideoProperty[] enumerateProperties() {
+    int[] handles = CameraServerJNI.enumerateSourceProperties(m_handle);
+    VideoProperty[] rv = new VideoProperty[handles.length];
+    for (int i = 0; i < handles.length; i++) {
+      rv[i] = new VideoProperty(handles[i]);
+    }
+    return rv;
+  }
+
+  /**
+   * Get the current video mode.
+   */
+  public VideoMode getVideoMode() {
+    return CameraServerJNI.getSourceVideoMode(m_handle);
+  }
+
+  /**
+   * Set the video mode.
+   * @param mode Video mode
+   */
+  public boolean setVideoMode(VideoMode mode) {
+    return CameraServerJNI.setSourceVideoMode(m_handle,
+        mode.pixelFormat.getValue(),
+        mode.width,
+        mode.height,
+        mode.fps);
+  }
+
+  /**
+   * Set the video mode.
+   *
+   * @param pixelFormat desired pixel format
+   * @param width desired width
+   * @param height desired height
+   * @param fps desired FPS
+   * @return True if set successfully
+   */
+  public boolean setVideoMode(VideoMode.PixelFormat pixelFormat, int width, int height, int fps) {
+    return CameraServerJNI.setSourceVideoMode(m_handle, pixelFormat.getValue(), width, height, fps);
+  }
+
+  /**
+   * Set the pixel format.
+   *
+   * @param pixelFormat desired pixel format
+   * @return True if set successfully
+   */
+  public boolean setPixelFormat(VideoMode.PixelFormat pixelFormat) {
+    return CameraServerJNI.setSourcePixelFormat(m_handle, pixelFormat.getValue());
+  }
+
+  /**
+   * Set the resolution.
+   *
+   * @param width desired width
+   * @param height desired height
+   * @return True if set successfully
+   */
+  public boolean setResolution(int width, int height) {
+    return CameraServerJNI.setSourceResolution(m_handle, width, height);
+  }
+
+  /**
+   * Set the frames per second (FPS).
+   *
+   * @param fps desired FPS
+   * @return True if set successfully
+   */
+  public boolean setFPS(int fps) {
+    return CameraServerJNI.setSourceFPS(m_handle, fps);
+  }
+
+  /**
+   * Set video mode and properties from a JSON configuration string.
+   *
+   * <p>The format of the JSON input is:
+   *
+   * <pre>
+   * {
+   *     "pixel format": "MJPEG", "YUYV", etc
+   *     "width": video mode width
+   *     "height": video mode height
+   *     "fps": video mode fps
+   *     "brightness": percentage brightness
+   *     "white balance": "auto", "hold", or value
+   *     "exposure": "auto", "hold", or value
+   *     "properties": [
+   *         {
+   *             "name": property name
+   *             "value": property value
+   *         }
+   *     ]
+   * }
+   * </pre>
+   *
+   * @param config configuration
+   * @return True if set successfully
+   */
+  public boolean setConfigJson(String config) {
+    return CameraServerJNI.setSourceConfigJson(m_handle, config);
+  }
+
+  /**
+   * Get a JSON configuration string.
+   *
+   * @return JSON configuration string
+   */
+  public String getConfigJson() {
+    return CameraServerJNI.getSourceConfigJson(m_handle);
+  }
+
+  /**
+   * Get the actual FPS.
+   *
+   * <p>CameraServerJNI#setTelemetryPeriod() must be called for this to be valid
+   * (throws VisionException if telemetry is not enabled).
+   *
+   * @return Actual FPS averaged over the telemetry period.
+   */
+  public double getActualFPS() {
+    return CameraServerJNI.getTelemetryAverageValue(m_handle,
+        CameraServerJNI.TelemetryKind.kSourceFramesReceived);
+  }
+
+  /**
+   * Get the data rate (in bytes per second).
+   *
+   * <p>CameraServerJNI#setTelemetryPeriod() must be called for this to be valid
+   * (throws VisionException if telemetry is not enabled).
+   *
+   * @return Data rate averaged over the telemetry period.
+   */
+  public double getActualDataRate() {
+    return CameraServerJNI.getTelemetryAverageValue(m_handle,
+        CameraServerJNI.TelemetryKind.kSourceBytesReceived);
+  }
+
+  /**
+   * Enumerate all known video modes for this source.
+   */
+  public VideoMode[] enumerateVideoModes() {
+    return CameraServerJNI.enumerateSourceVideoModes(m_handle);
+  }
+
+  /**
+   * Enumerate all sinks connected to this source.
+   *
+   * @return Vector of sinks.
+   */
+  @SuppressWarnings("PMD.AvoidInstantiatingObjectsInLoops")
+  public VideoSink[] enumerateSinks() {
+    int[] handles = CameraServerJNI.enumerateSourceSinks(m_handle);
+    VideoSink[] rv = new VideoSink[handles.length];
+    for (int i = 0; i < handles.length; i++) {
+      rv[i] = new VideoSink(handles[i]);
+    }
+    return rv;
+  }
+
+  /**
+   * Enumerate all existing sources.
+   *
+   * @return Vector of sources.
+   */
+  @SuppressWarnings("PMD.AvoidInstantiatingObjectsInLoops")
+  public static VideoSource[] enumerateSources() {
+    int[] handles = CameraServerJNI.enumerateSources();
+    VideoSource[] rv = new VideoSource[handles.length];
+    for (int i = 0; i < handles.length; i++) {
+      rv[i] = new VideoSource(handles[i]);
+    }
+    return rv;
+  }
+
+  protected int m_handle;
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/raw/RawFrame.java b/cscore/src/main/java/edu/wpi/cscore/raw/RawFrame.java
new file mode 100644
index 0000000..0e7a9ce
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/raw/RawFrame.java
@@ -0,0 +1,130 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore.raw;
+
+import java.nio.ByteBuffer;
+
+import edu.wpi.cscore.CameraServerJNI;
+
+/**
+ * Class for storing raw frame data between image read call.
+ *
+ * <p>Data is reused for each frame read, rather then reallocating every frame.
+ */
+public class RawFrame implements AutoCloseable {
+  private final long m_framePtr;
+  private ByteBuffer m_dataByteBuffer;
+  private long m_dataPtr;
+  private int m_totalData;
+  private int m_width;
+  private int m_height;
+  private int m_pixelFormat;
+
+  /**
+   * Construct a new RawFrame.
+   */
+  public RawFrame() {
+    m_framePtr = CameraServerJNI.allocateRawFrame();
+  }
+
+  /**
+   * Close the RawFrame, releasing native resources.
+   * Any images currently using the data will be invalidated.
+   */
+  @Override
+  public void close() {
+    CameraServerJNI.freeRawFrame(m_framePtr);
+  }
+
+  /**
+   * Called from JNI to set data in class.
+   */
+  public void setData(ByteBuffer dataByteBuffer, long dataPtr, int totalData,
+                      int width, int height, int pixelFormat) {
+    m_dataByteBuffer = dataByteBuffer;
+    m_dataPtr = dataPtr;
+    m_totalData = totalData;
+    m_width = width;
+    m_height = height;
+    m_pixelFormat = pixelFormat;
+  }
+
+  /**
+   * Get the pointer to native representation of this frame.
+   */
+  public long getFramePtr() {
+    return m_framePtr;
+  }
+
+  /**
+   * Get a ByteBuffer pointing to the frame data.
+   * This ByteBuffer is backed by the frame directly. Its lifetime is controlled by
+   * the frame. If a new frame gets read, it will overwrite the current one.
+   */
+  public ByteBuffer getDataByteBuffer() {
+    return m_dataByteBuffer;
+  }
+
+  /**
+   * Get a long (is a char* in native code) pointing to the frame data.
+   * This pointer is backed by the frame directly. Its lifetime is controlled by
+   * the frame. If a new frame gets read, it will overwrite the current one.
+   */
+  public long getDataPtr() {
+    return m_dataPtr;
+  }
+
+  /**
+   * Get the total length of the data stored in the frame.
+   */
+  public int getTotalData() {
+    return m_totalData;
+  }
+
+  /**
+   * Get the width of the frame.
+   */
+  public int getWidth() {
+    return m_width;
+  }
+
+  /**
+   * Set the width of the frame.
+   */
+  public void setWidth(int width) {
+    this.m_width = width;
+  }
+
+  /**
+   * Get the height of the frame.
+   */
+  public int getHeight() {
+    return m_height;
+  }
+
+  /**
+   * Set the height of the frame.
+   */
+  public void setHeight(int height) {
+    this.m_height = height;
+  }
+
+  /**
+   * Get the PixelFormat of the frame.
+   */
+  public int getPixelFormat() {
+    return m_pixelFormat;
+  }
+
+  /**
+   * Set the PixelFormat of the frame.
+   */
+  public void setPixelFormat(int pixelFormat) {
+    this.m_pixelFormat = pixelFormat;
+  }
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/raw/RawSink.java b/cscore/src/main/java/edu/wpi/cscore/raw/RawSink.java
new file mode 100644
index 0000000..535f356
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/raw/RawSink.java
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore.raw;
+
+import edu.wpi.cscore.CameraServerJNI;
+import edu.wpi.cscore.ImageSink;
+
+/**
+ * A sink for user code to accept video frames as raw bytes.
+ *
+ * <p>This is a complex API, most cases should use CvSink.
+ */
+public class RawSink extends ImageSink {
+  /**
+   * Create a sink for accepting raw images.
+   *
+   * <p>grabFrame() must be called on the created sink to get each new
+   * image.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   */
+  public RawSink(String name) {
+    super(CameraServerJNI.createRawSink(name));
+  }
+
+  /**
+   * Wait for the next frame and get the image.
+   * Times out (returning 0) after 0.225 seconds.
+   * The provided image will have three 8-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call getError() to obtain the error
+   *         message); the frame time is in the same time base as wpi::Now(),
+   *         and is in 1 us increments.
+   */
+  protected long grabFrame(RawFrame frame) {
+    return grabFrame(frame, 0.225);
+  }
+
+  /**
+   * Wait for the next frame and get the image.
+   * Times out (returning 0) after timeout seconds.
+   * The provided image will have three 8-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call getError() to obtain the error
+   *         message); the frame time is in the same time base as wpi::Now(),
+   *         and is in 1 us increments.
+   */
+  protected long grabFrame(RawFrame frame, double timeout) {
+    return CameraServerJNI.grabSinkFrameTimeout(m_handle, frame, timeout);
+  }
+
+  /**
+   * Wait for the next frame and get the image.  May block forever.
+   * The provided image will have three 8-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call getError() to obtain the error
+   *         message); the frame time is in the same time base as wpi::Now(),
+   *         and is in 1 us increments.
+   */
+  protected long grabFrameNoTimeout(RawFrame frame) {
+    return CameraServerJNI.grabSinkFrame(m_handle, frame);
+  }
+}
diff --git a/cscore/src/main/java/edu/wpi/cscore/raw/RawSource.java b/cscore/src/main/java/edu/wpi/cscore/raw/RawSource.java
new file mode 100644
index 0000000..9dfb3f3
--- /dev/null
+++ b/cscore/src/main/java/edu/wpi/cscore/raw/RawSource.java
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore.raw;
+
+import edu.wpi.cscore.CameraServerJNI;
+import edu.wpi.cscore.ImageSource;
+import edu.wpi.cscore.VideoMode;
+
+/**
+ * A source for user code to provide video frames as raw bytes.
+ *
+ * <p>This is a complex API, most cases should use CvSource.
+ */
+public class RawSource extends ImageSource {
+  /**
+   * Create a raw frame source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param mode Video mode being generated
+   */
+  public RawSource(String name, VideoMode mode) {
+    super(CameraServerJNI.createRawSource(name,
+        mode.pixelFormat.getValue(),
+        mode.width, mode.height,
+        mode.fps));
+  }
+
+  /**
+   * Create a raw frame source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param pixelFormat Pixel format
+   * @param width width
+   * @param height height
+   * @param fps fps
+   */
+  public RawSource(String name, VideoMode.PixelFormat pixelFormat, int width, int height, int fps) {
+    super(CameraServerJNI.createRawSource(name,
+        pixelFormat.getValue(),
+        width, height,
+        fps));
+  }
+
+  /**
+   * Put a raw image and notify sinks.
+   *
+   * @param image raw frame image
+   */
+  protected void putFrame(RawFrame image) {
+    CameraServerJNI.putRawSourceFrame(m_handle, image);
+  }
+
+  /**
+   * Put a raw image and notify sinks.
+   *
+   * @param data raw frame data pointer
+   * @param width frame width
+   * @param height frame height
+   * @param pixelFormat pixel format
+   * @param totalData length of data in total
+   */
+  protected void putFrame(long data, int width, int height, int pixelFormat, int totalData) {
+    CameraServerJNI.putRawSourceFrame(m_handle, data, width, height, pixelFormat, totalData);
+  }
+
+  /**
+   * Put a raw image and notify sinks.
+   *
+   * @param data raw frame data pointer
+   * @param width frame width
+   * @param height frame height
+   * @param pixelFormat pixel format
+   * @param totalData length of data in total
+   */
+  protected void putFrame(long data, int width, int height, VideoMode.PixelFormat pixelFormat,
+                          int totalData) {
+    CameraServerJNI.putRawSourceFrame(m_handle, data, width, height, pixelFormat.getValue(),
+                                      totalData);
+  }
+}
diff --git a/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp b/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp
new file mode 100644
index 0000000..b974169
--- /dev/null
+++ b/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "ConfigurableSourceImpl.h"
+
+#include <wpi/timestamp.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "Log.h"
+#include "Notifier.h"
+
+using namespace cs;
+
+ConfigurableSourceImpl::ConfigurableSourceImpl(const wpi::Twine& name,
+                                               wpi::Logger& logger,
+                                               Notifier& notifier,
+                                               Telemetry& telemetry,
+                                               const VideoMode& mode)
+    : SourceImpl{name, logger, notifier, telemetry} {
+  m_mode = mode;
+  m_videoModes.push_back(m_mode);
+}
+
+ConfigurableSourceImpl::~ConfigurableSourceImpl() {}
+
+void ConfigurableSourceImpl::Start() {
+  m_notifier.NotifySource(*this, CS_SOURCE_CONNECTED);
+  m_notifier.NotifySource(*this, CS_SOURCE_VIDEOMODES_UPDATED);
+  m_notifier.NotifySourceVideoMode(*this, m_mode);
+}
+
+bool ConfigurableSourceImpl::SetVideoMode(const VideoMode& mode,
+                                          CS_Status* status) {
+  {
+    std::scoped_lock lock(m_mutex);
+    m_mode = mode;
+    m_videoModes[0] = mode;
+  }
+  m_notifier.NotifySourceVideoMode(*this, mode);
+  return true;
+}
+
+void ConfigurableSourceImpl::NumSinksChanged() {
+  // ignore
+}
+
+void ConfigurableSourceImpl::NumSinksEnabledChanged() {
+  // ignore
+}
+
+void ConfigurableSourceImpl::NotifyError(const wpi::Twine& msg) {
+  PutError(msg, wpi::Now());
+}
+
+int ConfigurableSourceImpl::CreateProperty(const wpi::Twine& name,
+                                           CS_PropertyKind kind, int minimum,
+                                           int maximum, int step,
+                                           int defaultValue, int value) {
+  std::scoped_lock lock(m_mutex);
+  int ndx = CreateOrUpdateProperty(name,
+                                   [=] {
+                                     return std::make_unique<PropertyImpl>(
+                                         name, kind, minimum, maximum, step,
+                                         defaultValue, value);
+                                   },
+                                   [&](PropertyImpl& prop) {
+                                     // update all but value
+                                     prop.propKind = kind;
+                                     prop.minimum = minimum;
+                                     prop.maximum = maximum;
+                                     prop.step = step;
+                                     prop.defaultValue = defaultValue;
+                                     value = prop.value;
+                                   });
+  m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CREATED, name, ndx,
+                                  kind, value, wpi::Twine{});
+  return ndx;
+}
+
+int ConfigurableSourceImpl::CreateProperty(
+    const wpi::Twine& name, CS_PropertyKind kind, int minimum, int maximum,
+    int step, int defaultValue, int value,
+    std::function<void(CS_Property property)> onChange) {
+  // TODO
+  return 0;
+}
+
+void ConfigurableSourceImpl::SetEnumPropertyChoices(
+    int property, wpi::ArrayRef<std::string> choices, CS_Status* status) {
+  std::scoped_lock lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return;
+  }
+  if (prop->propKind != CS_PROP_ENUM) {
+    *status = CS_WRONG_PROPERTY_TYPE;
+    return;
+  }
+  prop->enumChoices = choices;
+  m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CHOICES_UPDATED,
+                                  prop->name, property, CS_PROP_ENUM,
+                                  prop->value, wpi::Twine{});
+}
diff --git a/cscore/src/main/native/cpp/ConfigurableSourceImpl.h b/cscore/src/main/native/cpp/ConfigurableSourceImpl.h
new file mode 100644
index 0000000..a10f27e
--- /dev/null
+++ b/cscore/src/main/native/cpp/ConfigurableSourceImpl.h
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CONFIGURABLESOURCEIMPL_H_
+#define CSCORE_CONFIGURABLESOURCEIMPL_H_
+
+#include <atomic>
+#include <functional>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/Twine.h>
+
+#include "SourceImpl.h"
+
+namespace cs {
+
+class ConfigurableSourceImpl : public SourceImpl {
+ protected:
+  ConfigurableSourceImpl(const wpi::Twine& name, wpi::Logger& logger,
+                         Notifier& notifier, Telemetry& telemetry,
+                         const VideoMode& mode);
+
+ public:
+  ~ConfigurableSourceImpl() override;
+
+  void Start() override;
+
+  bool SetVideoMode(const VideoMode& mode, CS_Status* status) override;
+
+  void NumSinksChanged() override;
+  void NumSinksEnabledChanged() override;
+
+  // OpenCV-specific functions
+  void NotifyError(const wpi::Twine& msg);
+  int CreateProperty(const wpi::Twine& name, CS_PropertyKind kind, int minimum,
+                     int maximum, int step, int defaultValue, int value);
+  int CreateProperty(const wpi::Twine& name, CS_PropertyKind kind, int minimum,
+                     int maximum, int step, int defaultValue, int value,
+                     std::function<void(CS_Property property)> onChange);
+  void SetEnumPropertyChoices(int property, wpi::ArrayRef<std::string> choices,
+                              CS_Status* status);
+
+ private:
+  std::atomic_bool m_connected{true};
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_CONFIGURABLESOURCEIMPL_H_
diff --git a/cscore/src/main/native/cpp/CvSinkImpl.cpp b/cscore/src/main/native/cpp/CvSinkImpl.cpp
new file mode 100644
index 0000000..7ba505a
--- /dev/null
+++ b/cscore/src/main/native/cpp/CvSinkImpl.cpp
@@ -0,0 +1,254 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "CvSinkImpl.h"
+
+#include <opencv2/core/core.hpp>
+#include <opencv2/highgui/highgui.hpp>
+#include <opencv2/imgproc/imgproc.hpp>
+#include <wpi/SmallString.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "c_util.h"
+#include "cscore_cpp.h"
+
+using namespace cs;
+
+CvSinkImpl::CvSinkImpl(const wpi::Twine& name, wpi::Logger& logger,
+                       Notifier& notifier, Telemetry& telemetry)
+    : SinkImpl{name, logger, notifier, telemetry} {
+  m_active = true;
+  // m_thread = std::thread(&CvSinkImpl::ThreadMain, this);
+}
+
+CvSinkImpl::CvSinkImpl(const wpi::Twine& name, wpi::Logger& logger,
+                       Notifier& notifier, Telemetry& telemetry,
+                       std::function<void(uint64_t time)> processFrame)
+    : SinkImpl{name, logger, notifier, telemetry} {}
+
+CvSinkImpl::~CvSinkImpl() { Stop(); }
+
+void CvSinkImpl::Stop() {
+  m_active = false;
+
+  // wake up any waiters by forcing an empty frame to be sent
+  if (auto source = GetSource()) source->Wakeup();
+
+  // join thread
+  if (m_thread.joinable()) m_thread.join();
+}
+
+uint64_t CvSinkImpl::GrabFrame(cv::Mat& image) {
+  SetEnabled(true);
+
+  auto source = GetSource();
+  if (!source) {
+    // Source disconnected; sleep for one second
+    std::this_thread::sleep_for(std::chrono::seconds(1));
+    return 0;
+  }
+
+  auto frame = source->GetNextFrame();  // blocks
+  if (!frame) {
+    // Bad frame; sleep for 20 ms so we don't consume all processor time.
+    std::this_thread::sleep_for(std::chrono::milliseconds(20));
+    return 0;  // signal error
+  }
+
+  if (!frame.GetCv(image)) {
+    // Shouldn't happen, but just in case...
+    std::this_thread::sleep_for(std::chrono::milliseconds(20));
+    return 0;
+  }
+
+  return frame.GetTime();
+}
+
+uint64_t CvSinkImpl::GrabFrame(cv::Mat& image, double timeout) {
+  SetEnabled(true);
+
+  auto source = GetSource();
+  if (!source) {
+    // Source disconnected; sleep for one second
+    std::this_thread::sleep_for(std::chrono::seconds(1));
+    return 0;
+  }
+
+  auto frame = source->GetNextFrame(timeout);  // blocks
+  if (!frame) {
+    // Bad frame; sleep for 20 ms so we don't consume all processor time.
+    std::this_thread::sleep_for(std::chrono::milliseconds(20));
+    return 0;  // signal error
+  }
+
+  if (!frame.GetCv(image)) {
+    // Shouldn't happen, but just in case...
+    std::this_thread::sleep_for(std::chrono::milliseconds(20));
+    return 0;
+  }
+
+  return frame.GetTime();
+}
+
+// Send HTTP response and a stream of JPG-frames
+void CvSinkImpl::ThreadMain() {
+  Enable();
+  while (m_active) {
+    auto source = GetSource();
+    if (!source) {
+      // Source disconnected; sleep for one second
+      std::this_thread::sleep_for(std::chrono::seconds(1));
+      continue;
+    }
+    SDEBUG4("waiting for frame");
+    Frame frame = source->GetNextFrame();  // blocks
+    if (!m_active) break;
+    if (!frame) {
+      // Bad frame; sleep for 10 ms so we don't consume all processor time.
+      std::this_thread::sleep_for(std::chrono::milliseconds(10));
+      continue;
+    }
+    // TODO m_processFrame();
+  }
+  Disable();
+}
+
+namespace cs {
+
+CS_Sink CreateCvSink(const wpi::Twine& name, CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  return inst.CreateSink(
+      CS_SINK_CV, std::make_shared<CvSinkImpl>(name, inst.logger, inst.notifier,
+                                               inst.telemetry));
+}
+
+CS_Sink CreateCvSinkCallback(const wpi::Twine& name,
+                             std::function<void(uint64_t time)> processFrame,
+                             CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  return inst.CreateSink(
+      CS_SINK_CV, std::make_shared<CvSinkImpl>(name, inst.logger, inst.notifier,
+                                               inst.telemetry, processFrame));
+}
+
+static constexpr unsigned SinkMask = CS_SINK_CV | CS_SINK_RAW;
+
+void SetSinkDescription(CS_Sink sink, const wpi::Twine& description,
+                        CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || (data->kind & SinkMask) == 0) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<CvSinkImpl&>(*data->sink).SetDescription(description);
+}
+
+uint64_t GrabSinkFrame(CS_Sink sink, cv::Mat& image, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_CV) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return static_cast<CvSinkImpl&>(*data->sink).GrabFrame(image);
+}
+
+uint64_t GrabSinkFrameTimeout(CS_Sink sink, cv::Mat& image, double timeout,
+                              CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_CV) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return static_cast<CvSinkImpl&>(*data->sink).GrabFrame(image, timeout);
+}
+
+std::string GetSinkError(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || (data->kind & SinkMask) == 0) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return static_cast<CvSinkImpl&>(*data->sink).GetError();
+}
+
+wpi::StringRef GetSinkError(CS_Sink sink, wpi::SmallVectorImpl<char>& buf,
+                            CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || (data->kind & SinkMask) == 0) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::StringRef{};
+  }
+  return static_cast<CvSinkImpl&>(*data->sink).GetError(buf);
+}
+
+void SetSinkEnabled(CS_Sink sink, bool enabled, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || (data->kind & SinkMask) == 0) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<CvSinkImpl&>(*data->sink).SetEnabled(enabled);
+}
+
+}  // namespace cs
+
+extern "C" {
+
+CS_Sink CS_CreateCvSink(const char* name, CS_Status* status) {
+  return cs::CreateCvSink(name, status);
+}
+
+CS_Sink CS_CreateCvSinkCallback(const char* name, void* data,
+                                void (*processFrame)(void* data, uint64_t time),
+                                CS_Status* status) {
+  return cs::CreateCvSinkCallback(
+      name, [=](uint64_t time) { processFrame(data, time); }, status);
+}
+
+void CS_SetSinkDescription(CS_Sink sink, const char* description,
+                           CS_Status* status) {
+  return cs::SetSinkDescription(sink, description, status);
+}
+
+#if CV_VERSION_MAJOR < 4
+uint64_t CS_GrabSinkFrame(CS_Sink sink, struct CvMat* image,
+                          CS_Status* status) {
+  auto mat = cv::cvarrToMat(image);
+  return cs::GrabSinkFrame(sink, mat, status);
+}
+
+uint64_t CS_GrabSinkFrameTimeout(CS_Sink sink, struct CvMat* image,
+                                 double timeout, CS_Status* status) {
+  auto mat = cv::cvarrToMat(image);
+  return cs::GrabSinkFrameTimeout(sink, mat, timeout, status);
+}
+#endif  // CV_VERSION_MAJOR < 4
+
+uint64_t CS_GrabSinkFrameCpp(CS_Sink sink, cv::Mat* image, CS_Status* status) {
+  return cs::GrabSinkFrame(sink, *image, status);
+}
+
+uint64_t CS_GrabSinkFrameTimeoutCpp(CS_Sink sink, cv::Mat* image,
+                                    double timeout, CS_Status* status) {
+  return cs::GrabSinkFrameTimeout(sink, *image, timeout, status);
+}
+
+char* CS_GetSinkError(CS_Sink sink, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSinkError(sink, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+void CS_SetSinkEnabled(CS_Sink sink, CS_Bool enabled, CS_Status* status) {
+  return cs::SetSinkEnabled(sink, enabled, status);
+}
+
+}  // extern "C"
diff --git a/cscore/src/main/native/cpp/CvSinkImpl.h b/cscore/src/main/native/cpp/CvSinkImpl.h
new file mode 100644
index 0000000..9b7820f
--- /dev/null
+++ b/cscore/src/main/native/cpp/CvSinkImpl.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CVSINKIMPL_H_
+#define CSCORE_CVSINKIMPL_H_
+
+#include <stdint.h>
+
+#include <atomic>
+#include <functional>
+#include <thread>
+
+#include <opencv2/core/core.hpp>
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+
+#include "Frame.h"
+#include "SinkImpl.h"
+
+namespace cs {
+
+class SourceImpl;
+
+class CvSinkImpl : public SinkImpl {
+ public:
+  CvSinkImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+             Telemetry& telemetry);
+  CvSinkImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+             Telemetry& telemetry,
+             std::function<void(uint64_t time)> processFrame);
+  ~CvSinkImpl() override;
+
+  void Stop();
+
+  uint64_t GrabFrame(cv::Mat& image);
+  uint64_t GrabFrame(cv::Mat& image, double timeout);
+
+ private:
+  void ThreadMain();
+
+  std::atomic_bool m_active;  // set to false to terminate threads
+  std::thread m_thread;
+  std::function<void(uint64_t time)> m_processFrame;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_CVSINKIMPL_H_
diff --git a/cscore/src/main/native/cpp/CvSourceImpl.cpp b/cscore/src/main/native/cpp/CvSourceImpl.cpp
new file mode 100644
index 0000000..49b9d28
--- /dev/null
+++ b/cscore/src/main/native/cpp/CvSourceImpl.cpp
@@ -0,0 +1,234 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "CvSourceImpl.h"
+
+#include <opencv2/core/core.hpp>
+#include <opencv2/highgui/highgui.hpp>
+#include <opencv2/imgproc/imgproc.hpp>
+#include <wpi/STLExtras.h>
+#include <wpi/timestamp.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "c_util.h"
+#include "cscore_cpp.h"
+
+using namespace cs;
+
+CvSourceImpl::CvSourceImpl(const wpi::Twine& name, wpi::Logger& logger,
+                           Notifier& notifier, Telemetry& telemetry,
+                           const VideoMode& mode)
+    : ConfigurableSourceImpl{name, logger, notifier, telemetry, mode} {}
+
+CvSourceImpl::~CvSourceImpl() {}
+
+void CvSourceImpl::PutFrame(cv::Mat& image) {
+  // We only support 8-bit images; convert if necessary.
+  cv::Mat finalImage;
+  if (image.depth() == CV_8U)
+    finalImage = image;
+  else
+    image.convertTo(finalImage, CV_8U);
+
+  std::unique_ptr<Image> dest;
+  switch (image.channels()) {
+    case 1:
+      dest =
+          AllocImage(VideoMode::kGray, image.cols, image.rows, image.total());
+      finalImage.copyTo(dest->AsMat());
+      break;
+    case 3:
+      dest = AllocImage(VideoMode::kBGR, image.cols, image.rows,
+                        image.total() * 3);
+      finalImage.copyTo(dest->AsMat());
+      break;
+    case 4:
+      dest = AllocImage(VideoMode::kBGR, image.cols, image.rows,
+                        image.total() * 3);
+      cv::cvtColor(finalImage, dest->AsMat(), cv::COLOR_BGRA2BGR);
+      break;
+    default:
+      SERROR("PutFrame: " << image.channels()
+                          << "-channel images not supported");
+      return;
+  }
+  SourceImpl::PutFrame(std::move(dest), wpi::Now());
+}
+
+namespace cs {
+
+CS_Source CreateCvSource(const wpi::Twine& name, const VideoMode& mode,
+                         CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  return inst.CreateSource(CS_SOURCE_CV, std::make_shared<CvSourceImpl>(
+                                             name, inst.logger, inst.notifier,
+                                             inst.telemetry, mode));
+}
+
+void PutSourceFrame(CS_Source source, cv::Mat& image, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_CV) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<CvSourceImpl&>(*data->source).PutFrame(image);
+}
+
+static constexpr unsigned SourceMask = CS_SINK_CV | CS_SINK_RAW;
+
+void NotifySourceError(CS_Source source, const wpi::Twine& msg,
+                       CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || (data->kind & SourceMask) == 0) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<CvSourceImpl&>(*data->source).NotifyError(msg);
+}
+
+void SetSourceConnected(CS_Source source, bool connected, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || (data->kind & SourceMask) == 0) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<CvSourceImpl&>(*data->source).SetConnected(connected);
+}
+
+void SetSourceDescription(CS_Source source, const wpi::Twine& description,
+                          CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || (data->kind & SourceMask) == 0) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<CvSourceImpl&>(*data->source).SetDescription(description);
+}
+
+CS_Property CreateSourceProperty(CS_Source source, const wpi::Twine& name,
+                                 CS_PropertyKind kind, int minimum, int maximum,
+                                 int step, int defaultValue, int value,
+                                 CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || (data->kind & SourceMask) == 0) {
+    *status = CS_INVALID_HANDLE;
+    return -1;
+  }
+  int property = static_cast<CvSourceImpl&>(*data->source)
+                     .CreateProperty(name, kind, minimum, maximum, step,
+                                     defaultValue, value);
+  return Handle{source, property, Handle::kProperty};
+}
+
+CS_Property CreateSourcePropertyCallback(
+    CS_Source source, const wpi::Twine& name, CS_PropertyKind kind, int minimum,
+    int maximum, int step, int defaultValue, int value,
+    std::function<void(CS_Property property)> onChange, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || (data->kind & SourceMask) == 0) {
+    *status = CS_INVALID_HANDLE;
+    return -1;
+  }
+  int property = static_cast<CvSourceImpl&>(*data->source)
+                     .CreateProperty(name, kind, minimum, maximum, step,
+                                     defaultValue, value, onChange);
+  return Handle{source, property, Handle::kProperty};
+}
+
+void SetSourceEnumPropertyChoices(CS_Source source, CS_Property property,
+                                  wpi::ArrayRef<std::string> choices,
+                                  CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || (data->kind & SourceMask) == 0) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+
+  // Get property index; also validate the source owns this property
+  Handle handle{property};
+  int i = handle.GetParentIndex();
+  if (i < 0) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  auto data2 = Instance::GetInstance().GetSource(Handle{i, Handle::kSource});
+  if (!data2 || data->source.get() != data2->source.get()) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  int propertyIndex = handle.GetIndex();
+  static_cast<CvSourceImpl&>(*data->source)
+      .SetEnumPropertyChoices(propertyIndex, choices, status);
+}
+
+}  // namespace cs
+
+extern "C" {
+
+CS_Source CS_CreateCvSource(const char* name, const CS_VideoMode* mode,
+                            CS_Status* status) {
+  return cs::CreateCvSource(name, static_cast<const cs::VideoMode&>(*mode),
+                            status);
+}
+
+#if CV_VERSION_MAJOR < 4
+void CS_PutSourceFrame(CS_Source source, struct CvMat* image,
+                       CS_Status* status) {
+  auto mat = cv::cvarrToMat(image);
+  return cs::PutSourceFrame(source, mat, status);
+}
+#endif  // CV_VERSION_MAJOR < 4
+
+void CS_PutSourceFrameCpp(CS_Source source, cv::Mat* image, CS_Status* status) {
+  return cs::PutSourceFrame(source, *image, status);
+}
+
+void CS_NotifySourceError(CS_Source source, const char* msg,
+                          CS_Status* status) {
+  return cs::NotifySourceError(source, msg, status);
+}
+
+void CS_SetSourceConnected(CS_Source source, CS_Bool connected,
+                           CS_Status* status) {
+  return cs::SetSourceConnected(source, connected, status);
+}
+
+void CS_SetSourceDescription(CS_Source source, const char* description,
+                             CS_Status* status) {
+  return cs::SetSourceDescription(source, description, status);
+}
+
+CS_Property CS_CreateSourceProperty(CS_Source source, const char* name,
+                                    enum CS_PropertyKind kind, int minimum,
+                                    int maximum, int step, int defaultValue,
+                                    int value, CS_Status* status) {
+  return cs::CreateSourceProperty(source, name, kind, minimum, maximum, step,
+                                  defaultValue, value, status);
+}
+
+CS_Property CS_CreateSourcePropertyCallback(
+    CS_Source source, const char* name, enum CS_PropertyKind kind, int minimum,
+    int maximum, int step, int defaultValue, int value, void* data,
+    void (*onChange)(void* data, CS_Property property), CS_Status* status) {
+  return cs::CreateSourcePropertyCallback(
+      source, name, kind, minimum, maximum, step, defaultValue, value,
+      [=](CS_Property property) { onChange(data, property); }, status);
+}
+
+void CS_SetSourceEnumPropertyChoices(CS_Source source, CS_Property property,
+                                     const char** choices, int count,
+                                     CS_Status* status) {
+  wpi::SmallVector<std::string, 8> vec;
+  vec.reserve(count);
+  for (int i = 0; i < count; ++i) vec.push_back(choices[i]);
+  return cs::SetSourceEnumPropertyChoices(source, property, vec, status);
+}
+
+}  // extern "C"
diff --git a/cscore/src/main/native/cpp/CvSourceImpl.h b/cscore/src/main/native/cpp/CvSourceImpl.h
new file mode 100644
index 0000000..978d012
--- /dev/null
+++ b/cscore/src/main/native/cpp/CvSourceImpl.h
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CVSOURCEIMPL_H_
+#define CSCORE_CVSOURCEIMPL_H_
+
+#include <atomic>
+#include <functional>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <opencv2/core/core.hpp>
+#include <wpi/ArrayRef.h>
+#include <wpi/Twine.h>
+
+#include "ConfigurableSourceImpl.h"
+#include "SourceImpl.h"
+
+namespace cs {
+
+class CvSourceImpl : public ConfigurableSourceImpl {
+ public:
+  CvSourceImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+               Telemetry& telemetry, const VideoMode& mode);
+  ~CvSourceImpl() override;
+
+  // OpenCV-specific functions
+  void PutFrame(cv::Mat& image);
+
+ private:
+  std::atomic_bool m_connected{true};
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_CVSOURCEIMPL_H_
diff --git a/cscore/src/main/native/cpp/Frame.cpp b/cscore/src/main/native/cpp/Frame.cpp
new file mode 100644
index 0000000..466cb52
--- /dev/null
+++ b/cscore/src/main/native/cpp/Frame.cpp
@@ -0,0 +1,499 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "Frame.h"
+
+#include <cstdlib>
+
+#include <opencv2/core/core.hpp>
+#include <opencv2/highgui/highgui.hpp>
+#include <opencv2/imgproc/imgproc.hpp>
+
+#include "Instance.h"
+#include "Log.h"
+#include "SourceImpl.h"
+
+using namespace cs;
+
+Frame::Frame(SourceImpl& source, const wpi::Twine& error, Time time)
+    : m_impl{source.AllocFrameImpl().release()} {
+  m_impl->refcount = 1;
+  m_impl->error = error.str();
+  m_impl->time = time;
+}
+
+Frame::Frame(SourceImpl& source, std::unique_ptr<Image> image, Time time)
+    : m_impl{source.AllocFrameImpl().release()} {
+  m_impl->refcount = 1;
+  m_impl->error.resize(0);
+  m_impl->time = time;
+  m_impl->images.push_back(image.release());
+}
+
+Image* Frame::GetNearestImage(int width, int height) const {
+  if (!m_impl) return nullptr;
+  std::scoped_lock lock(m_impl->mutex);
+  Image* found = nullptr;
+
+  // Ideally we want the smallest image at least width/height in size
+  for (auto i : m_impl->images) {
+    if (i->IsLarger(width, height) && (!found || (i->IsSmaller(*found))))
+      found = i;
+  }
+  if (found) return found;
+
+  // Find the largest image (will be less than width/height)
+  for (auto i : m_impl->images) {
+    if (!found || (i->IsLarger(*found))) found = i;
+  }
+  if (found) return found;
+
+  // Shouldn't reach this, but just in case...
+  return m_impl->images.empty() ? nullptr : m_impl->images[0];
+}
+
+Image* Frame::GetNearestImage(int width, int height,
+                              VideoMode::PixelFormat pixelFormat,
+                              int jpegQuality) const {
+  if (!m_impl) return nullptr;
+  std::scoped_lock lock(m_impl->mutex);
+  Image* found = nullptr;
+
+  // We want the smallest image at least width/height (or the next largest),
+  // but the primary search order is in order of conversion cost.
+  // If we don't find exactly what we want, we prefer non-JPEG source images
+  // (because JPEG source images require a decompression step).
+  // While the searching takes a little time, it pales in comparison to the
+  // image processing to come, so it's worth spending a little extra time
+  // looking for the most efficient conversion.
+
+  // 1) Same width, height, pixelFormat, and (possibly) JPEG quality
+  //    (e.g. exactly what we want)
+  for (auto i : m_impl->images) {
+    if (i->Is(width, height, pixelFormat, jpegQuality)) return i;
+  }
+
+  // 2) Same width, height, different (but non-JPEG) pixelFormat (color conv)
+  // 2a) If we want JPEG output, prefer BGR over other pixel formats
+  if (pixelFormat == VideoMode::kMJPEG) {
+    for (auto i : m_impl->images) {
+      if (i->Is(width, height, VideoMode::kBGR)) return i;
+    }
+  }
+
+  for (auto i : m_impl->images) {
+    if (i->Is(width, height) && i->pixelFormat != VideoMode::kMJPEG) return i;
+  }
+
+  // 3) Different width, height, same pixelFormat (only if non-JPEG) (resample)
+  if (pixelFormat != VideoMode::kMJPEG) {
+    // 3a) Smallest image at least width/height in size
+    for (auto i : m_impl->images) {
+      if (i->IsLarger(width, height) && i->pixelFormat == pixelFormat &&
+          (!found || (i->IsSmaller(*found))))
+        found = i;
+    }
+    if (found) return found;
+
+    // 3b) Largest image (less than width/height)
+    for (auto i : m_impl->images) {
+      if (i->pixelFormat == pixelFormat && (!found || (i->IsLarger(*found))))
+        found = i;
+    }
+    if (found) return found;
+  }
+
+  // 4) Different width, height, different (but non-JPEG) pixelFormat
+  //    (color conversion + resample)
+  // 4a) Smallest image at least width/height in size
+  for (auto i : m_impl->images) {
+    if (i->IsLarger(width, height) && i->pixelFormat != VideoMode::kMJPEG &&
+        (!found || (i->IsSmaller(*found))))
+      found = i;
+  }
+  if (found) return found;
+
+  // 4b) Largest image (less than width/height)
+  for (auto i : m_impl->images) {
+    if (i->pixelFormat != VideoMode::kMJPEG &&
+        (!found || (i->IsLarger(*found))))
+      found = i;
+  }
+  if (found) return found;
+
+  // 5) Same width, height, JPEG pixelFormat (decompression).  As there may be
+  //    multiple JPEG images, find the highest quality one.
+  for (auto i : m_impl->images) {
+    if (i->Is(width, height, VideoMode::kMJPEG) &&
+        (!found || i->jpegQuality > found->jpegQuality)) {
+      found = i;
+      // consider one without a quality setting to be the highest quality
+      // (e.g. directly from the camera)
+      if (i->jpegQuality == -1) break;
+    }
+  }
+  if (found) return found;
+
+  // 6) Different width, height, JPEG pixelFormat (decompression)
+  // 6a) Smallest image at least width/height in size
+  for (auto i : m_impl->images) {
+    if (i->IsLarger(width, height) && i->pixelFormat == VideoMode::kMJPEG &&
+        (!found || (i->IsSmaller(*found))))
+      found = i;
+  }
+  if (found) return found;
+
+  // 6b) Largest image (less than width/height)
+  for (auto i : m_impl->images) {
+    if (i->pixelFormat != VideoMode::kMJPEG &&
+        (!found || (i->IsLarger(*found))))
+      found = i;
+  }
+  if (found) return found;
+
+  // Shouldn't reach this, but just in case...
+  return m_impl->images.empty() ? nullptr : m_impl->images[0];
+}
+
+Image* Frame::ConvertImpl(Image* image, VideoMode::PixelFormat pixelFormat,
+                          int requiredJpegQuality, int defaultJpegQuality) {
+  if (!image ||
+      image->Is(image->width, image->height, pixelFormat, requiredJpegQuality))
+    return image;
+  Image* cur = image;
+
+  // If the source image is a JPEG, we need to decode it before we can do
+  // anything else with it.  Note that if the destination format is JPEG, we
+  // still need to do this (unless it was already a JPEG, in which case we
+  // would have returned above).
+  if (cur->pixelFormat == VideoMode::kMJPEG) {
+    cur = ConvertMJPEGToBGR(cur);
+    if (pixelFormat == VideoMode::kBGR) return cur;
+  }
+
+  // Color convert
+  switch (pixelFormat) {
+    case VideoMode::kRGB565:
+      // If source is YUYV or Gray, need to convert to BGR first
+      if (cur->pixelFormat == VideoMode::kYUYV) {
+        // Check to see if BGR version already exists...
+        if (Image* newImage =
+                GetExistingImage(cur->width, cur->height, VideoMode::kBGR))
+          cur = newImage;
+        else
+          cur = ConvertYUYVToBGR(cur);
+      } else if (cur->pixelFormat == VideoMode::kGray) {
+        // Check to see if BGR version already exists...
+        if (Image* newImage =
+                GetExistingImage(cur->width, cur->height, VideoMode::kBGR))
+          cur = newImage;
+        else
+          cur = ConvertGrayToBGR(cur);
+      }
+      return ConvertBGRToRGB565(cur);
+    case VideoMode::kGray:
+      // If source is YUYV or RGB565, need to convert to BGR first
+      if (cur->pixelFormat == VideoMode::kYUYV) {
+        // Check to see if BGR version already exists...
+        if (Image* newImage =
+                GetExistingImage(cur->width, cur->height, VideoMode::kBGR))
+          cur = newImage;
+        else
+          cur = ConvertYUYVToBGR(cur);
+      } else if (cur->pixelFormat == VideoMode::kRGB565) {
+        // Check to see if BGR version already exists...
+        if (Image* newImage =
+                GetExistingImage(cur->width, cur->height, VideoMode::kBGR))
+          cur = newImage;
+        else
+          cur = ConvertRGB565ToBGR(cur);
+      }
+      return ConvertBGRToGray(cur);
+    case VideoMode::kBGR:
+    case VideoMode::kMJPEG:
+      if (cur->pixelFormat == VideoMode::kYUYV) {
+        cur = ConvertYUYVToBGR(cur);
+      } else if (cur->pixelFormat == VideoMode::kRGB565) {
+        cur = ConvertRGB565ToBGR(cur);
+      } else if (cur->pixelFormat == VideoMode::kGray) {
+        if (pixelFormat == VideoMode::kBGR)
+          return ConvertGrayToBGR(cur);
+        else
+          return ConvertGrayToMJPEG(cur, defaultJpegQuality);
+      }
+      break;
+    case VideoMode::kYUYV:
+    default:
+      return nullptr;  // Unsupported
+  }
+
+  // Compress if destination is JPEG
+  if (pixelFormat == VideoMode::kMJPEG)
+    cur = ConvertBGRToMJPEG(cur, defaultJpegQuality);
+
+  return cur;
+}
+
+Image* Frame::ConvertMJPEGToBGR(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kMJPEG) return nullptr;
+
+  // Allocate an BGR image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kBGR, image->width, image->height,
+                                image->width * image->height * 3);
+
+  // Decode
+  cv::Mat newMat = newImage->AsMat();
+  cv::imdecode(image->AsInputArray(), cv::IMREAD_COLOR, &newMat);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::scoped_lock lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertMJPEGToGray(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kMJPEG) return nullptr;
+
+  // Allocate an grayscale image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kGray, image->width, image->height,
+                                image->width * image->height);
+
+  // Decode
+  cv::Mat newMat = newImage->AsMat();
+  cv::imdecode(image->AsInputArray(), cv::IMREAD_GRAYSCALE, &newMat);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::scoped_lock lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertYUYVToBGR(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kYUYV) return nullptr;
+
+  // Allocate a BGR image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kBGR, image->width, image->height,
+                                image->width * image->height * 3);
+
+  // Convert
+  cv::cvtColor(image->AsMat(), newImage->AsMat(), cv::COLOR_YUV2BGR_YUYV);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::scoped_lock lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertBGRToRGB565(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kBGR) return nullptr;
+
+  // Allocate a RGB565 image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kRGB565, image->width, image->height,
+                                image->width * image->height * 2);
+
+  // Convert
+  cv::cvtColor(image->AsMat(), newImage->AsMat(), cv::COLOR_RGB2BGR565);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::scoped_lock lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertRGB565ToBGR(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kRGB565) return nullptr;
+
+  // Allocate a BGR image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kBGR, image->width, image->height,
+                                image->width * image->height * 3);
+
+  // Convert
+  cv::cvtColor(image->AsMat(), newImage->AsMat(), cv::COLOR_BGR5652RGB);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::scoped_lock lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertBGRToGray(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kBGR) return nullptr;
+
+  // Allocate a Grayscale image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kGray, image->width, image->height,
+                                image->width * image->height);
+
+  // Convert
+  cv::cvtColor(image->AsMat(), newImage->AsMat(), cv::COLOR_BGR2GRAY);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::scoped_lock lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertGrayToBGR(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kGray) return nullptr;
+
+  // Allocate a BGR image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kBGR, image->width, image->height,
+                                image->width * image->height * 3);
+
+  // Convert
+  cv::cvtColor(image->AsMat(), newImage->AsMat(), cv::COLOR_GRAY2BGR);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::scoped_lock lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertBGRToMJPEG(Image* image, int quality) {
+  if (!image || image->pixelFormat != VideoMode::kBGR) return nullptr;
+  if (!m_impl) return nullptr;
+  std::scoped_lock lock(m_impl->mutex);
+
+  // Allocate a JPEG image.  We don't actually know what the resulting size
+  // will be; while the destination will automatically grow, doing so will
+  // cause an extra malloc, so we don't want to be too conservative here.
+  // Per Wikipedia, Q=100 on a sample image results in 8.25 bits per pixel,
+  // this is a little bit more conservative in assuming 50% space savings over
+  // the equivalent BGR image.
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kMJPEG, image->width, image->height,
+                                image->width * image->height * 1.5);
+
+  // Compress
+  if (m_impl->compressionParams.empty()) {
+    m_impl->compressionParams.push_back(cv::IMWRITE_JPEG_QUALITY);
+    m_impl->compressionParams.push_back(quality);
+  } else {
+    m_impl->compressionParams[1] = quality;
+  }
+  cv::imencode(".jpg", image->AsMat(), newImage->vec(),
+               m_impl->compressionParams);
+
+  // Save the result
+  Image* rv = newImage.release();
+  m_impl->images.push_back(rv);
+  return rv;
+}
+
+Image* Frame::ConvertGrayToMJPEG(Image* image, int quality) {
+  if (!image || image->pixelFormat != VideoMode::kGray) return nullptr;
+  if (!m_impl) return nullptr;
+  std::scoped_lock lock(m_impl->mutex);
+
+  // Allocate a JPEG image.  We don't actually know what the resulting size
+  // will be; while the destination will automatically grow, doing so will
+  // cause an extra malloc, so we don't want to be too conservative here.
+  // Per Wikipedia, Q=100 on a sample image results in 8.25 bits per pixel,
+  // this is a little bit more conservative in assuming 25% space savings over
+  // the equivalent grayscale image.
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kMJPEG, image->width, image->height,
+                                image->width * image->height * 0.75);
+
+  // Compress
+  if (m_impl->compressionParams.empty()) {
+    m_impl->compressionParams.push_back(cv::IMWRITE_JPEG_QUALITY);
+    m_impl->compressionParams.push_back(quality);
+  } else {
+    m_impl->compressionParams[1] = quality;
+  }
+  cv::imencode(".jpg", image->AsMat(), newImage->vec(),
+               m_impl->compressionParams);
+
+  // Save the result
+  Image* rv = newImage.release();
+  m_impl->images.push_back(rv);
+  return rv;
+}
+
+Image* Frame::GetImageImpl(int width, int height,
+                           VideoMode::PixelFormat pixelFormat,
+                           int requiredJpegQuality, int defaultJpegQuality) {
+  if (!m_impl) return nullptr;
+  std::scoped_lock lock(m_impl->mutex);
+  Image* cur = GetNearestImage(width, height, pixelFormat, requiredJpegQuality);
+  if (!cur || cur->Is(width, height, pixelFormat, requiredJpegQuality))
+    return cur;
+
+  WPI_DEBUG4(Instance::GetInstance().logger,
+             "converting image from " << cur->width << "x" << cur->height
+                                      << " type " << cur->pixelFormat << " to "
+                                      << width << "x" << height << " type "
+                                      << pixelFormat);
+
+  // If the source image is a JPEG, we need to decode it before we can do
+  // anything else with it.  Note that if the destination format is JPEG, we
+  // still need to do this (unless the width/height/compression were the same,
+  // in which case we already returned the existing JPEG above).
+  if (cur->pixelFormat == VideoMode::kMJPEG) cur = ConvertMJPEGToBGR(cur);
+
+  // Resize
+  if (!cur->Is(width, height)) {
+    // Allocate an image.
+    auto newImage = m_impl->source.AllocImage(
+        cur->pixelFormat, width, height,
+        width * height * (cur->size() / (cur->width * cur->height)));
+
+    // Resize
+    cv::Mat newMat = newImage->AsMat();
+    cv::resize(cur->AsMat(), newMat, newMat.size(), 0, 0);
+
+    // Save the result
+    cur = newImage.release();
+    m_impl->images.push_back(cur);
+  }
+
+  // Convert to output format
+  return ConvertImpl(cur, pixelFormat, requiredJpegQuality, defaultJpegQuality);
+}
+
+bool Frame::GetCv(cv::Mat& image, int width, int height) {
+  Image* rawImage = GetImage(width, height, VideoMode::kBGR);
+  if (!rawImage) return false;
+  rawImage->AsMat().copyTo(image);
+  return true;
+}
+
+void Frame::ReleaseFrame() {
+  for (auto image : m_impl->images)
+    m_impl->source.ReleaseImage(std::unique_ptr<Image>(image));
+  m_impl->images.clear();
+  m_impl->source.ReleaseFrameImpl(std::unique_ptr<Impl>(m_impl));
+  m_impl = nullptr;
+}
diff --git a/cscore/src/main/native/cpp/Frame.h b/cscore/src/main/native/cpp/Frame.h
new file mode 100644
index 0000000..07fa24f
--- /dev/null
+++ b/cscore/src/main/native/cpp/Frame.h
@@ -0,0 +1,200 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_FRAME_H_
+#define CSCORE_FRAME_H_
+
+#include <atomic>
+#include <memory>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include <wpi/SmallVector.h>
+#include <wpi/Twine.h>
+#include <wpi/mutex.h>
+
+#include "Image.h"
+#include "cscore_cpp.h"
+
+namespace cs {
+
+class SourceImpl;
+
+class Frame {
+  friend class SourceImpl;
+
+ public:
+  using Time = uint64_t;
+
+ private:
+  struct Impl {
+    explicit Impl(SourceImpl& source_) : source(source_) {}
+
+    wpi::recursive_mutex mutex;
+    std::atomic_int refcount{0};
+    Time time{0};
+    SourceImpl& source;
+    std::string error;
+    wpi::SmallVector<Image*, 4> images;
+    std::vector<int> compressionParams;
+  };
+
+ public:
+  Frame() noexcept : m_impl{nullptr} {}
+
+  Frame(SourceImpl& source, const wpi::Twine& error, Time time);
+
+  Frame(SourceImpl& source, std::unique_ptr<Image> image, Time time);
+
+  Frame(const Frame& frame) noexcept : m_impl{frame.m_impl} {
+    if (m_impl) ++m_impl->refcount;
+  }
+
+  Frame(Frame&& other) noexcept : Frame() { swap(*this, other); }
+
+  ~Frame() { DecRef(); }
+
+  Frame& operator=(Frame other) noexcept {
+    swap(*this, other);
+    return *this;
+  }
+
+  explicit operator bool() const { return m_impl && m_impl->error.empty(); }
+
+  friend void swap(Frame& first, Frame& second) noexcept {
+    using std::swap;
+    swap(first.m_impl, second.m_impl);
+  }
+
+  Time GetTime() const { return m_impl ? m_impl->time : 0; }
+
+  wpi::StringRef GetError() const {
+    if (!m_impl) return wpi::StringRef{};
+    return m_impl->error;
+  }
+
+  int GetOriginalWidth() const {
+    if (!m_impl) return 0;
+    std::scoped_lock lock(m_impl->mutex);
+    if (m_impl->images.empty()) return 0;
+    return m_impl->images[0]->width;
+  }
+
+  int GetOriginalHeight() const {
+    if (!m_impl) return 0;
+    std::scoped_lock lock(m_impl->mutex);
+    if (m_impl->images.empty()) return 0;
+    return m_impl->images[0]->height;
+  }
+
+  int GetOriginalPixelFormat() const {
+    if (!m_impl) return 0;
+    std::scoped_lock lock(m_impl->mutex);
+    if (m_impl->images.empty()) return 0;
+    return m_impl->images[0]->pixelFormat;
+  }
+
+  int GetOriginalJpegQuality() const {
+    if (!m_impl) return 0;
+    std::scoped_lock lock(m_impl->mutex);
+    if (m_impl->images.empty()) return 0;
+    return m_impl->images[0]->jpegQuality;
+  }
+
+  Image* GetExistingImage(size_t i = 0) const {
+    if (!m_impl) return nullptr;
+    std::scoped_lock lock(m_impl->mutex);
+    if (i >= m_impl->images.size()) return nullptr;
+    return m_impl->images[i];
+  }
+
+  Image* GetExistingImage(int width, int height) const {
+    if (!m_impl) return nullptr;
+    std::scoped_lock lock(m_impl->mutex);
+    for (auto i : m_impl->images) {
+      if (i->Is(width, height)) return i;
+    }
+    return nullptr;
+  }
+
+  Image* GetExistingImage(int width, int height,
+                          VideoMode::PixelFormat pixelFormat) const {
+    if (!m_impl) return nullptr;
+    std::scoped_lock lock(m_impl->mutex);
+    for (auto i : m_impl->images) {
+      if (i->Is(width, height, pixelFormat)) return i;
+    }
+    return nullptr;
+  }
+
+  Image* GetExistingImage(int width, int height,
+                          VideoMode::PixelFormat pixelFormat,
+                          int jpegQuality) const {
+    if (!m_impl) return nullptr;
+    std::scoped_lock lock(m_impl->mutex);
+    for (auto i : m_impl->images) {
+      if (i->Is(width, height, pixelFormat, jpegQuality)) return i;
+    }
+    return nullptr;
+  }
+
+  Image* GetNearestImage(int width, int height) const;
+  Image* GetNearestImage(int width, int height,
+                         VideoMode::PixelFormat pixelFormat,
+                         int jpegQuality = -1) const;
+
+  Image* Convert(Image* image, VideoMode::PixelFormat pixelFormat) {
+    if (pixelFormat == VideoMode::kMJPEG) return nullptr;
+    return ConvertImpl(image, pixelFormat, -1, 80);
+  }
+  Image* ConvertToMJPEG(Image* image, int requiredQuality,
+                        int defaultQuality = 80) {
+    return ConvertImpl(image, VideoMode::kMJPEG, requiredQuality,
+                       defaultQuality);
+  }
+  Image* ConvertMJPEGToBGR(Image* image);
+  Image* ConvertMJPEGToGray(Image* image);
+  Image* ConvertYUYVToBGR(Image* image);
+  Image* ConvertBGRToRGB565(Image* image);
+  Image* ConvertRGB565ToBGR(Image* image);
+  Image* ConvertBGRToGray(Image* image);
+  Image* ConvertGrayToBGR(Image* image);
+  Image* ConvertBGRToMJPEG(Image* image, int quality);
+  Image* ConvertGrayToMJPEG(Image* image, int quality);
+
+  Image* GetImage(int width, int height, VideoMode::PixelFormat pixelFormat) {
+    if (pixelFormat == VideoMode::kMJPEG) return nullptr;
+    return GetImageImpl(width, height, pixelFormat, -1, 80);
+  }
+  Image* GetImageMJPEG(int width, int height, int requiredQuality,
+                       int defaultQuality = 80) {
+    return GetImageImpl(width, height, VideoMode::kMJPEG, requiredQuality,
+                        defaultQuality);
+  }
+
+  bool GetCv(cv::Mat& image) {
+    return GetCv(image, GetOriginalWidth(), GetOriginalHeight());
+  }
+  bool GetCv(cv::Mat& image, int width, int height);
+
+ private:
+  Image* ConvertImpl(Image* image, VideoMode::PixelFormat pixelFormat,
+                     int requiredJpegQuality, int defaultJpegQuality);
+  Image* GetImageImpl(int width, int height, VideoMode::PixelFormat pixelFormat,
+                      int requiredJpegQuality, int defaultJpegQuality);
+  void DecRef() {
+    if (m_impl && --(m_impl->refcount) == 0) ReleaseFrame();
+  }
+  void ReleaseFrame();
+
+  Impl* m_impl;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_FRAME_H_
diff --git a/cscore/src/main/native/cpp/Handle.h b/cscore/src/main/native/cpp/Handle.h
new file mode 100644
index 0000000..ebb3a55
--- /dev/null
+++ b/cscore/src/main/native/cpp/Handle.h
@@ -0,0 +1,69 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_HANDLE_H_
+#define CSCORE_HANDLE_H_
+
+#include "cscore_c.h"
+
+namespace cs {
+
+// Handle data layout:
+// Bits 0-15:  Handle index
+// Bits 16-23: Parent index (property only)
+// Bits 24-30: Type
+
+class Handle {
+ public:
+  enum Type {
+    kUndefined = 0,
+    kProperty = 0x40,
+    kSource,
+    kSink,
+    kListener,
+    kSinkProperty
+  };
+  enum { kIndexMax = 0xffff };
+
+  Handle(CS_Handle handle) : m_handle(handle) {}  // NOLINT
+  operator CS_Handle() const { return m_handle; }
+
+  Handle(int index, Type type) {
+    if (index < 0) {
+      m_handle = 0;
+      return;
+    }
+    m_handle = ((static_cast<int>(type) & 0x7f) << 24) | (index & 0xffff);
+  }
+  Handle(int index, int property, Type type) {
+    if (index < 0 || property < 0) {
+      m_handle = 0;
+      return;
+    }
+    m_handle = ((static_cast<int>(type) & 0x7f) << 24) |
+               ((index & 0xff) << 16) | (property & 0xffff);
+  }
+
+  int GetIndex() const { return static_cast<int>(m_handle) & 0xffff; }
+  Type GetType() const {
+    return static_cast<Type>((static_cast<int>(m_handle) >> 24) & 0xff);
+  }
+  bool IsType(Type type) const { return type == GetType(); }
+  int GetTypedIndex(Type type) const { return IsType(type) ? GetIndex() : -1; }
+  int GetParentIndex() const {
+    return (IsType(Handle::kProperty) || IsType(Handle::kSinkProperty))
+               ? (static_cast<int>(m_handle) >> 16) & 0xff
+               : -1;
+  }
+
+ private:
+  CS_Handle m_handle;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_HANDLE_H_
diff --git a/cscore/src/main/native/cpp/HttpCameraImpl.cpp b/cscore/src/main/native/cpp/HttpCameraImpl.cpp
new file mode 100644
index 0000000..57c86a8
--- /dev/null
+++ b/cscore/src/main/native/cpp/HttpCameraImpl.cpp
@@ -0,0 +1,629 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "HttpCameraImpl.h"
+
+#include <wpi/MemAlloc.h>
+#include <wpi/TCPConnector.h>
+#include <wpi/timestamp.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "JpegUtil.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "Telemetry.h"
+#include "c_util.h"
+
+using namespace cs;
+
+HttpCameraImpl::HttpCameraImpl(const wpi::Twine& name, CS_HttpCameraKind kind,
+                               wpi::Logger& logger, Notifier& notifier,
+                               Telemetry& telemetry)
+    : SourceImpl{name, logger, notifier, telemetry}, m_kind{kind} {}
+
+HttpCameraImpl::~HttpCameraImpl() {
+  m_active = false;
+
+  // force wakeup of monitor thread
+  m_monitorCond.notify_one();
+
+  // join monitor thread
+  if (m_monitorThread.joinable()) m_monitorThread.join();
+
+  // Close file if it's open
+  {
+    std::scoped_lock lock(m_mutex);
+    if (m_streamConn) m_streamConn->stream->close();
+    if (m_settingsConn) m_settingsConn->stream->close();
+  }
+
+  // force wakeup of camera thread in case it's waiting on cv
+  m_sinkEnabledCond.notify_one();
+
+  // join camera thread
+  if (m_streamThread.joinable()) m_streamThread.join();
+
+  // force wakeup of settings thread
+  m_settingsCond.notify_one();
+
+  // join settings thread
+  if (m_settingsThread.joinable()) m_settingsThread.join();
+}
+
+void HttpCameraImpl::Start() {
+  // Kick off the stream and settings threads
+  m_streamThread = std::thread(&HttpCameraImpl::StreamThreadMain, this);
+  m_settingsThread = std::thread(&HttpCameraImpl::SettingsThreadMain, this);
+  m_monitorThread = std::thread(&HttpCameraImpl::MonitorThreadMain, this);
+}
+
+void HttpCameraImpl::MonitorThreadMain() {
+  while (m_active) {
+    std::unique_lock lock(m_mutex);
+    // sleep for 1 second between checks
+    m_monitorCond.wait_for(lock, std::chrono::seconds(1),
+                           [=] { return !m_active; });
+
+    if (!m_active) break;
+
+    // check to see if we got any frames, and close the stream if not
+    // (this will result in an error at the read point, and ultimately
+    // a reconnect attempt)
+    if (m_streamConn && m_frameCount == 0) {
+      SWARNING("Monitor detected stream hung, disconnecting");
+      m_streamConn->stream->close();
+    }
+
+    // reset the frame counter
+    m_frameCount = 0;
+  }
+
+  SDEBUG("Monitor Thread exiting");
+}
+
+void HttpCameraImpl::StreamThreadMain() {
+  while (m_active) {
+    SetConnected(false);
+
+    // sleep between retries
+    std::this_thread::sleep_for(std::chrono::milliseconds(250));
+
+    // disconnect if not enabled
+    if (!IsEnabled()) {
+      std::unique_lock lock(m_mutex);
+      if (m_streamConn) m_streamConn->stream->close();
+      // Wait for enable
+      m_sinkEnabledCond.wait(lock, [=] { return !m_active || IsEnabled(); });
+      if (!m_active) return;
+    }
+
+    // connect
+    wpi::SmallString<64> boundary;
+    wpi::HttpConnection* conn = DeviceStreamConnect(boundary);
+
+    if (!m_active) break;
+
+    // keep retrying
+    if (!conn) continue;
+
+    // update connected since we're actually connected
+    SetConnected(true);
+
+    // stream
+    DeviceStream(conn->is, boundary);
+    {
+      std::unique_lock lock(m_mutex);
+      m_streamConn = nullptr;
+    }
+  }
+
+  SDEBUG("Camera Thread exiting");
+  SetConnected(false);
+}
+
+wpi::HttpConnection* HttpCameraImpl::DeviceStreamConnect(
+    wpi::SmallVectorImpl<char>& boundary) {
+  // Build the request
+  wpi::HttpRequest req;
+  {
+    std::scoped_lock lock(m_mutex);
+    if (m_locations.empty()) {
+      SERROR("locations array is empty!?");
+      std::this_thread::sleep_for(std::chrono::seconds(1));
+      return nullptr;
+    }
+    if (m_nextLocation >= m_locations.size()) m_nextLocation = 0;
+    req = wpi::HttpRequest{m_locations[m_nextLocation++], m_streamSettings};
+    m_streamSettingsUpdated = false;
+  }
+
+  // Try to connect
+  auto stream =
+      wpi::TCPConnector::connect(req.host.c_str(), req.port, m_logger, 1);
+
+  if (!m_active || !stream) return nullptr;
+
+  auto connPtr = std::make_unique<wpi::HttpConnection>(std::move(stream), 1);
+  wpi::HttpConnection* conn = connPtr.get();
+
+  // update m_streamConn
+  {
+    std::scoped_lock lock(m_mutex);
+    m_frameCount = 1;  // avoid a race with monitor thread
+    m_streamConn = std::move(connPtr);
+  }
+
+  std::string warn;
+  if (!conn->Handshake(req, &warn)) {
+    SWARNING(GetName() << ": " << warn);
+    std::scoped_lock lock(m_mutex);
+    m_streamConn = nullptr;
+    return nullptr;
+  }
+
+  // Parse Content-Type header to get the boundary
+  wpi::StringRef mediaType, contentType;
+  std::tie(mediaType, contentType) = conn->contentType.str().split(';');
+  mediaType = mediaType.trim();
+  if (mediaType != "multipart/x-mixed-replace") {
+    SWARNING("\"" << req.host << "\": unrecognized Content-Type \"" << mediaType
+                  << "\"");
+    std::scoped_lock lock(m_mutex);
+    m_streamConn = nullptr;
+    return nullptr;
+  }
+
+  // media parameters
+  boundary.clear();
+  while (!contentType.empty()) {
+    wpi::StringRef keyvalue;
+    std::tie(keyvalue, contentType) = contentType.split(';');
+    contentType = contentType.ltrim();
+    wpi::StringRef key, value;
+    std::tie(key, value) = keyvalue.split('=');
+    if (key.trim() == "boundary") {
+      value = value.trim().trim('"');  // value may be quoted
+      if (value.startswith("--")) {
+        value = value.substr(2);
+      }
+      boundary.append(value.begin(), value.end());
+    }
+  }
+
+  if (boundary.empty()) {
+    SWARNING("\"" << req.host
+                  << "\": empty multi-part boundary or no Content-Type");
+    std::scoped_lock lock(m_mutex);
+    m_streamConn = nullptr;
+    return nullptr;
+  }
+
+  return conn;
+}
+
+void HttpCameraImpl::DeviceStream(wpi::raw_istream& is,
+                                  wpi::StringRef boundary) {
+  // Stored here so we reuse it from frame to frame
+  std::string imageBuf;
+
+  // keep track of number of bad images received; if we receive 3 bad images
+  // in a row, we reconnect
+  int numErrors = 0;
+
+  // streaming loop
+  while (m_active && !is.has_error() && IsEnabled() && numErrors < 3 &&
+         !m_streamSettingsUpdated) {
+    if (!FindMultipartBoundary(is, boundary, nullptr)) break;
+
+    // Read the next two characters after the boundary (normally \r\n)
+    // Handle just \n for LabVIEW however
+    char eol[2];
+    is.read(eol, 1);
+    if (!m_active || is.has_error()) break;
+    if (eol[0] != '\n') {
+      is.read(eol + 1, 1);
+      if (!m_active || is.has_error()) break;
+      // End-of-stream is indicated with trailing --
+      if (eol[0] == '-' && eol[1] == '-') break;
+    }
+
+    if (!DeviceStreamFrame(is, imageBuf))
+      ++numErrors;
+    else
+      numErrors = 0;
+  }
+}
+
+bool HttpCameraImpl::DeviceStreamFrame(wpi::raw_istream& is,
+                                       std::string& imageBuf) {
+  // Read the headers
+  wpi::SmallString<64> contentTypeBuf;
+  wpi::SmallString<64> contentLengthBuf;
+  if (!ParseHttpHeaders(is, &contentTypeBuf, &contentLengthBuf)) {
+    SWARNING("disconnected during headers");
+    PutError("disconnected during headers", wpi::Now());
+    return false;
+  }
+
+  // Check the content type (if present)
+  if (!contentTypeBuf.str().empty() &&
+      !contentTypeBuf.str().startswith("image/jpeg")) {
+    wpi::SmallString<64> errBuf;
+    wpi::raw_svector_ostream errMsg{errBuf};
+    errMsg << "received unknown Content-Type \"" << contentTypeBuf << "\"";
+    SWARNING(errMsg.str());
+    PutError(errMsg.str(), wpi::Now());
+    return false;
+  }
+
+  unsigned int contentLength = 0;
+  if (contentLengthBuf.str().getAsInteger(10, contentLength)) {
+    // Ugh, no Content-Length?  Read the blocks of the JPEG file.
+    int width, height;
+    if (!ReadJpeg(is, imageBuf, &width, &height)) {
+      SWARNING("did not receive a JPEG image");
+      PutError("did not receive a JPEG image", wpi::Now());
+      return false;
+    }
+    PutFrame(VideoMode::PixelFormat::kMJPEG, width, height, imageBuf,
+             wpi::Now());
+    ++m_frameCount;
+    return true;
+  }
+
+  // We know how big it is!  Just get a frame of the right size and read
+  // the data directly into it.
+  auto image = AllocImage(VideoMode::PixelFormat::kMJPEG, 0, 0, contentLength);
+  is.read(image->data(), contentLength);
+  if (!m_active || is.has_error()) return false;
+  int width, height;
+  if (!GetJpegSize(image->str(), &width, &height)) {
+    SWARNING("did not receive a JPEG image");
+    PutError("did not receive a JPEG image", wpi::Now());
+    return false;
+  }
+  image->width = width;
+  image->height = height;
+  PutFrame(std::move(image), wpi::Now());
+  ++m_frameCount;
+  return true;
+}
+
+void HttpCameraImpl::SettingsThreadMain() {
+  for (;;) {
+    wpi::HttpRequest req;
+    {
+      std::unique_lock lock(m_mutex);
+      m_settingsCond.wait(lock, [=] {
+        return !m_active || (m_prefLocation != -1 && !m_settings.empty());
+      });
+      if (!m_active) break;
+
+      // Build the request
+      req = wpi::HttpRequest{m_locations[m_prefLocation], m_settings};
+    }
+
+    DeviceSendSettings(req);
+  }
+
+  SDEBUG("Settings Thread exiting");
+}
+
+void HttpCameraImpl::DeviceSendSettings(wpi::HttpRequest& req) {
+  // Try to connect
+  auto stream =
+      wpi::TCPConnector::connect(req.host.c_str(), req.port, m_logger, 1);
+
+  if (!m_active || !stream) return;
+
+  auto connPtr = std::make_unique<wpi::HttpConnection>(std::move(stream), 1);
+  wpi::HttpConnection* conn = connPtr.get();
+
+  // update m_settingsConn
+  {
+    std::scoped_lock lock(m_mutex);
+    m_settingsConn = std::move(connPtr);
+  }
+
+  // Just need a handshake as settings are sent via GET parameters
+  std::string warn;
+  if (!conn->Handshake(req, &warn)) SWARNING(GetName() << ": " << warn);
+
+  conn->stream->close();
+}
+
+CS_HttpCameraKind HttpCameraImpl::GetKind() const {
+  std::scoped_lock lock(m_mutex);
+  return m_kind;
+}
+
+bool HttpCameraImpl::SetUrls(wpi::ArrayRef<std::string> urls,
+                             CS_Status* status) {
+  std::vector<wpi::HttpLocation> locations;
+  for (const auto& url : urls) {
+    bool error = false;
+    std::string errorMsg;
+    locations.emplace_back(url, &error, &errorMsg);
+    if (error) {
+      SERROR(GetName() << ": " << errorMsg);
+      *status = CS_BAD_URL;
+      return false;
+    }
+  }
+
+  std::scoped_lock lock(m_mutex);
+  m_locations.swap(locations);
+  m_nextLocation = 0;
+  m_streamSettingsUpdated = true;
+  return true;
+}
+
+std::vector<std::string> HttpCameraImpl::GetUrls() const {
+  std::scoped_lock lock(m_mutex);
+  std::vector<std::string> urls;
+  for (const auto& loc : m_locations) urls.push_back(loc.url);
+  return urls;
+}
+
+void HttpCameraImpl::CreateProperty(const wpi::Twine& name,
+                                    const wpi::Twine& httpParam,
+                                    bool viaSettings, CS_PropertyKind kind,
+                                    int minimum, int maximum, int step,
+                                    int defaultValue, int value) const {
+  std::scoped_lock lock(m_mutex);
+  m_propertyData.emplace_back(std::make_unique<PropertyData>(
+      name, httpParam, viaSettings, kind, minimum, maximum, step, defaultValue,
+      value));
+
+  m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CREATED, name,
+                                  m_propertyData.size() + 1, kind, value,
+                                  wpi::Twine{});
+}
+
+template <typename T>
+void HttpCameraImpl::CreateEnumProperty(
+    const wpi::Twine& name, const wpi::Twine& httpParam, bool viaSettings,
+    int defaultValue, int value, std::initializer_list<T> choices) const {
+  std::scoped_lock lock(m_mutex);
+  m_propertyData.emplace_back(std::make_unique<PropertyData>(
+      name, httpParam, viaSettings, CS_PROP_ENUM, 0, choices.size() - 1, 1,
+      defaultValue, value));
+
+  auto& enumChoices = m_propertyData.back()->enumChoices;
+  enumChoices.clear();
+  for (const auto& choice : choices) enumChoices.emplace_back(choice);
+
+  m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CREATED, name,
+                                  m_propertyData.size() + 1, CS_PROP_ENUM,
+                                  value, wpi::Twine{});
+  m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CHOICES_UPDATED,
+                                  name, m_propertyData.size() + 1, CS_PROP_ENUM,
+                                  value, wpi::Twine{});
+}
+
+std::unique_ptr<PropertyImpl> HttpCameraImpl::CreateEmptyProperty(
+    const wpi::Twine& name) const {
+  return std::make_unique<PropertyData>(name);
+}
+
+bool HttpCameraImpl::CacheProperties(CS_Status* status) const {
+#ifdef _MSC_VER  // work around VS2019 16.4.0 bug
+  std::scoped_lock<wpi::mutex> lock(m_mutex);
+#else
+  std::scoped_lock lock(m_mutex);
+#endif
+
+  // Pretty typical set of video modes
+  m_videoModes.clear();
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 640, 480, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 320, 240, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 160, 120, 30);
+
+  m_properties_cached = true;
+  return true;
+}
+
+void HttpCameraImpl::SetProperty(int property, int value, CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetStringProperty(int property, const wpi::Twine& value,
+                                       CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetBrightness(int brightness, CS_Status* status) {
+  // TODO
+}
+
+int HttpCameraImpl::GetBrightness(CS_Status* status) const {
+  // TODO
+  return 0;
+}
+
+void HttpCameraImpl::SetWhiteBalanceAuto(CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetWhiteBalanceHoldCurrent(CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetWhiteBalanceManual(int value, CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetExposureAuto(CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetExposureHoldCurrent(CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetExposureManual(int value, CS_Status* status) {
+  // TODO
+}
+
+bool HttpCameraImpl::SetVideoMode(const VideoMode& mode, CS_Status* status) {
+  if (mode.pixelFormat != VideoMode::kMJPEG) return false;
+  std::scoped_lock lock(m_mutex);
+  m_mode = mode;
+  m_streamSettingsUpdated = true;
+  return true;
+}
+
+void HttpCameraImpl::NumSinksChanged() {
+  // ignore
+}
+
+void HttpCameraImpl::NumSinksEnabledChanged() {
+  m_sinkEnabledCond.notify_one();
+}
+
+bool AxisCameraImpl::CacheProperties(CS_Status* status) const {
+  CreateProperty("brightness", "ImageSource.I0.Sensor.Brightness", true,
+                 CS_PROP_INTEGER, 0, 100, 1, 50, 50);
+  CreateEnumProperty("white_balance", "ImageSource.I0.Sensor.WhiteBalance",
+                     true, 0, 0,
+                     {"auto", "hold", "fixed_outdoor1", "fixed_outdoor2",
+                      "fixed_indoor", "fixed_fluor1", "fixed_fluor2"});
+  CreateProperty("color_level", "ImageSource.I0.Sensor.ColorLevel", true,
+                 CS_PROP_INTEGER, 0, 100, 1, 50, 50);
+  CreateEnumProperty("exposure", "ImageSource.I0.Sensor.Exposure", true, 0, 0,
+                     {"auto", "hold", "flickerfree50", "flickerfree60"});
+  CreateProperty("exposure_priority", "ImageSource.I0.Sensor.ExposurePriority",
+                 true, CS_PROP_INTEGER, 0, 100, 1, 50, 50);
+
+  // TODO: get video modes from device
+  std::scoped_lock lock(m_mutex);
+  m_videoModes.clear();
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 640, 480, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 480, 360, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 320, 240, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 240, 180, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 176, 144, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 160, 120, 30);
+
+  m_properties_cached = true;
+  return true;
+}
+
+namespace cs {
+
+CS_Source CreateHttpCamera(const wpi::Twine& name, const wpi::Twine& url,
+                           CS_HttpCameraKind kind, CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  std::shared_ptr<HttpCameraImpl> source;
+  switch (kind) {
+    case CS_HTTP_AXIS:
+      source = std::make_shared<AxisCameraImpl>(name, inst.logger,
+                                                inst.notifier, inst.telemetry);
+      break;
+    default:
+      source = std::make_shared<HttpCameraImpl>(name, kind, inst.logger,
+                                                inst.notifier, inst.telemetry);
+      break;
+  }
+  if (!source->SetUrls(url.str(), status)) return 0;
+  return inst.CreateSource(CS_SOURCE_HTTP, source);
+}
+
+CS_Source CreateHttpCamera(const wpi::Twine& name,
+                           wpi::ArrayRef<std::string> urls,
+                           CS_HttpCameraKind kind, CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  if (urls.empty()) {
+    *status = CS_EMPTY_VALUE;
+    return 0;
+  }
+  auto source = std::make_shared<HttpCameraImpl>(name, kind, inst.logger,
+                                                 inst.notifier, inst.telemetry);
+  if (!source->SetUrls(urls, status)) return 0;
+  return inst.CreateSource(CS_SOURCE_HTTP, source);
+}
+
+CS_HttpCameraKind GetHttpCameraKind(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_HTTP) {
+    *status = CS_INVALID_HANDLE;
+    return CS_HTTP_UNKNOWN;
+  }
+  return static_cast<HttpCameraImpl&>(*data->source).GetKind();
+}
+
+void SetHttpCameraUrls(CS_Source source, wpi::ArrayRef<std::string> urls,
+                       CS_Status* status) {
+  if (urls.empty()) {
+    *status = CS_EMPTY_VALUE;
+    return;
+  }
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_HTTP) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<HttpCameraImpl&>(*data->source).SetUrls(urls, status);
+}
+
+std::vector<std::string> GetHttpCameraUrls(CS_Source source,
+                                           CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_HTTP) {
+    *status = CS_INVALID_HANDLE;
+    return std::vector<std::string>{};
+  }
+  return static_cast<HttpCameraImpl&>(*data->source).GetUrls();
+}
+
+}  // namespace cs
+
+extern "C" {
+
+CS_Source CS_CreateHttpCamera(const char* name, const char* url,
+                              CS_HttpCameraKind kind, CS_Status* status) {
+  return cs::CreateHttpCamera(name, url, kind, status);
+}
+
+CS_Source CS_CreateHttpCameraMulti(const char* name, const char** urls,
+                                   int count, CS_HttpCameraKind kind,
+                                   CS_Status* status) {
+  wpi::SmallVector<std::string, 4> vec;
+  vec.reserve(count);
+  for (int i = 0; i < count; ++i) vec.push_back(urls[i]);
+  return cs::CreateHttpCamera(name, vec, kind, status);
+}
+
+CS_HttpCameraKind CS_GetHttpCameraKind(CS_Source source, CS_Status* status) {
+  return cs::GetHttpCameraKind(source, status);
+}
+
+void CS_SetHttpCameraUrls(CS_Source source, const char** urls, int count,
+                          CS_Status* status) {
+  wpi::SmallVector<std::string, 4> vec;
+  vec.reserve(count);
+  for (int i = 0; i < count; ++i) vec.push_back(urls[i]);
+  cs::SetHttpCameraUrls(source, vec, status);
+}
+
+char** CS_GetHttpCameraUrls(CS_Source source, int* count, CS_Status* status) {
+  auto urls = cs::GetHttpCameraUrls(source, status);
+  char** out =
+      static_cast<char**>(wpi::safe_malloc(urls.size() * sizeof(char*)));
+  *count = urls.size();
+  for (size_t i = 0; i < urls.size(); ++i) out[i] = cs::ConvertToC(urls[i]);
+  return out;
+}
+
+void CS_FreeHttpCameraUrls(char** urls, int count) {
+  if (!urls) return;
+  for (int i = 0; i < count; ++i) std::free(urls[i]);
+  std::free(urls);
+}
+
+}  // extern "C"
diff --git a/cscore/src/main/native/cpp/HttpCameraImpl.h b/cscore/src/main/native/cpp/HttpCameraImpl.h
new file mode 100644
index 0000000..5967015
--- /dev/null
+++ b/cscore/src/main/native/cpp/HttpCameraImpl.h
@@ -0,0 +1,166 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_HTTPCAMERAIMPL_H_
+#define CSCORE_HTTPCAMERAIMPL_H_
+
+#include <atomic>
+#include <functional>
+#include <initializer_list>
+#include <memory>
+#include <string>
+#include <thread>
+#include <vector>
+
+#include <wpi/HttpUtil.h>
+#include <wpi/SmallString.h>
+#include <wpi/StringMap.h>
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+#include <wpi/raw_istream.h>
+
+#include "SourceImpl.h"
+#include "cscore_cpp.h"
+
+namespace cs {
+
+class HttpCameraImpl : public SourceImpl {
+ public:
+  HttpCameraImpl(const wpi::Twine& name, CS_HttpCameraKind kind,
+                 wpi::Logger& logger, Notifier& notifier, Telemetry& telemetry);
+  ~HttpCameraImpl() override;
+
+  void Start() override;
+
+  // Property functions
+  void SetProperty(int property, int value, CS_Status* status) override;
+  void SetStringProperty(int property, const wpi::Twine& value,
+                         CS_Status* status) override;
+
+  // Standard common camera properties
+  void SetBrightness(int brightness, CS_Status* status) override;
+  int GetBrightness(CS_Status* status) const override;
+  void SetWhiteBalanceAuto(CS_Status* status) override;
+  void SetWhiteBalanceHoldCurrent(CS_Status* status) override;
+  void SetWhiteBalanceManual(int value, CS_Status* status) override;
+  void SetExposureAuto(CS_Status* status) override;
+  void SetExposureHoldCurrent(CS_Status* status) override;
+  void SetExposureManual(int value, CS_Status* status) override;
+
+  bool SetVideoMode(const VideoMode& mode, CS_Status* status) override;
+
+  void NumSinksChanged() override;
+  void NumSinksEnabledChanged() override;
+
+  CS_HttpCameraKind GetKind() const;
+  bool SetUrls(wpi::ArrayRef<std::string> urls, CS_Status* status);
+  std::vector<std::string> GetUrls() const;
+
+  // Property data
+  class PropertyData : public PropertyImpl {
+   public:
+    PropertyData() = default;
+    explicit PropertyData(const wpi::Twine& name_) : PropertyImpl{name_} {}
+    PropertyData(const wpi::Twine& name_, const wpi::Twine& httpParam_,
+                 bool viaSettings_, CS_PropertyKind kind_, int minimum_,
+                 int maximum_, int step_, int defaultValue_, int value_)
+        : PropertyImpl(name_, kind_, step_, defaultValue_, value_),
+          viaSettings(viaSettings_),
+          httpParam(httpParam_.str()) {
+      hasMinimum = true;
+      minimum = minimum_;
+      hasMaximum = true;
+      maximum = maximum_;
+    }
+    ~PropertyData() override = default;
+
+    bool viaSettings{false};
+    std::string httpParam;
+  };
+
+ protected:
+  std::unique_ptr<PropertyImpl> CreateEmptyProperty(
+      const wpi::Twine& name) const override;
+
+  bool CacheProperties(CS_Status* status) const override;
+
+  void CreateProperty(const wpi::Twine& name, const wpi::Twine& httpParam,
+                      bool viaSettings, CS_PropertyKind kind, int minimum,
+                      int maximum, int step, int defaultValue, int value) const;
+
+  template <typename T>
+  void CreateEnumProperty(const wpi::Twine& name, const wpi::Twine& httpParam,
+                          bool viaSettings, int defaultValue, int value,
+                          std::initializer_list<T> choices) const;
+
+ private:
+  // The camera streaming thread
+  void StreamThreadMain();
+
+  // Functions used by StreamThreadMain()
+  wpi::HttpConnection* DeviceStreamConnect(
+      wpi::SmallVectorImpl<char>& boundary);
+  void DeviceStream(wpi::raw_istream& is, wpi::StringRef boundary);
+  bool DeviceStreamFrame(wpi::raw_istream& is, std::string& imageBuf);
+
+  // The camera settings thread
+  void SettingsThreadMain();
+  void DeviceSendSettings(wpi::HttpRequest& req);
+
+  // The monitor thread
+  void MonitorThreadMain();
+
+  std::atomic_bool m_connected{false};
+  std::atomic_bool m_active{true};  // set to false to terminate thread
+  std::thread m_streamThread;
+  std::thread m_settingsThread;
+  std::thread m_monitorThread;
+
+  //
+  // Variables protected by m_mutex
+  //
+
+  // The camera connections
+  std::unique_ptr<wpi::HttpConnection> m_streamConn;
+  std::unique_ptr<wpi::HttpConnection> m_settingsConn;
+
+  CS_HttpCameraKind m_kind;
+
+  std::vector<wpi::HttpLocation> m_locations;
+  size_t m_nextLocation{0};
+  int m_prefLocation{-1};  // preferred location
+
+  std::atomic_int m_frameCount{0};
+
+  wpi::condition_variable m_sinkEnabledCond;
+
+  wpi::StringMap<wpi::SmallString<16>> m_settings;
+  wpi::condition_variable m_settingsCond;
+
+  wpi::StringMap<wpi::SmallString<16>> m_streamSettings;
+  std::atomic_bool m_streamSettingsUpdated{false};
+
+  wpi::condition_variable m_monitorCond;
+};
+
+class AxisCameraImpl : public HttpCameraImpl {
+ public:
+  AxisCameraImpl(const wpi::Twine& name, wpi::Logger& logger,
+                 Notifier& notifier, Telemetry& telemetry)
+      : HttpCameraImpl{name, CS_HTTP_AXIS, logger, notifier, telemetry} {}
+#if 0
+  void SetProperty(int property, int value, CS_Status* status) override;
+  void SetStringProperty(int property, const wpi::Twine& value,
+                         CS_Status* status) override;
+#endif
+ protected:
+  bool CacheProperties(CS_Status* status) const override;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_HTTPCAMERAIMPL_H_
diff --git a/cscore/src/main/native/cpp/Image.h b/cscore/src/main/native/cpp/Image.h
new file mode 100644
index 0000000..6305d93
--- /dev/null
+++ b/cscore/src/main/native/cpp/Image.h
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_IMAGE_H_
+#define CSCORE_IMAGE_H_
+
+#include <vector>
+
+#include <opencv2/core/core.hpp>
+#include <wpi/StringRef.h>
+
+#include "cscore_cpp.h"
+#include "default_init_allocator.h"
+
+namespace cs {
+
+class Frame;
+
+class Image {
+  friend class Frame;
+
+ public:
+#ifndef __linux__
+  explicit Image(size_t capacity) { m_data.reserve(capacity); }
+#else
+  explicit Image(size_t capacity)
+      : m_data{capacity, default_init_allocator<uchar>{}} {
+    m_data.resize(0);
+  }
+#endif
+
+  Image(const Image&) = delete;
+  Image& operator=(const Image&) = delete;
+
+  // Getters
+  operator wpi::StringRef() const { return str(); }
+  wpi::StringRef str() const { return wpi::StringRef(data(), size()); }
+  size_t capacity() const { return m_data.capacity(); }
+  const char* data() const {
+    return reinterpret_cast<const char*>(m_data.data());
+  }
+  char* data() { return reinterpret_cast<char*>(m_data.data()); }
+  size_t size() const { return m_data.size(); }
+
+  const std::vector<uchar>& vec() const { return m_data; }
+  std::vector<uchar>& vec() { return m_data; }
+
+  void resize(size_t size) { m_data.resize(size); }
+  void SetSize(size_t size) { m_data.resize(size); }
+
+  cv::Mat AsMat() {
+    int type;
+    switch (pixelFormat) {
+      case VideoMode::kYUYV:
+      case VideoMode::kRGB565:
+        type = CV_8UC2;
+        break;
+      case VideoMode::kBGR:
+        type = CV_8UC3;
+        break;
+      case VideoMode::kGray:
+      case VideoMode::kMJPEG:
+      default:
+        type = CV_8UC1;
+        break;
+    }
+    return cv::Mat{height, width, type, m_data.data()};
+  }
+
+  cv::_InputArray AsInputArray() { return cv::_InputArray{m_data}; }
+
+  bool Is(int width_, int height_) {
+    return width == width_ && height == height_;
+  }
+  bool Is(int width_, int height_, VideoMode::PixelFormat pixelFormat_) {
+    return width == width_ && height == height_ && pixelFormat == pixelFormat_;
+  }
+  bool Is(int width_, int height_, VideoMode::PixelFormat pixelFormat_,
+          int jpegQuality_) {
+    // Consider +/-5 on JPEG quality to be "close enough"
+    return width == width_ && height == height_ &&
+           pixelFormat == pixelFormat_ &&
+           (pixelFormat != VideoMode::kMJPEG || jpegQuality_ == -1 ||
+            (jpegQuality != -1 && std::abs(jpegQuality - jpegQuality_) <= 5));
+  }
+  bool IsLarger(int width_, int height_) {
+    return width >= width_ && height >= height_;
+  }
+  bool IsLarger(const Image& oth) {
+    return width >= oth.width && height >= oth.height;
+  }
+  bool IsSmaller(int width_, int height_) { return !IsLarger(width_, height_); }
+  bool IsSmaller(const Image& oth) { return !IsLarger(oth); }
+
+ private:
+  std::vector<uchar> m_data;
+
+ public:
+  VideoMode::PixelFormat pixelFormat{VideoMode::kUnknown};
+  int width{0};
+  int height{0};
+  int jpegQuality{-1};
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_IMAGE_H_
diff --git a/cscore/src/main/native/cpp/Instance.cpp b/cscore/src/main/native/cpp/Instance.cpp
new file mode 100644
index 0000000..8dd5c26
--- /dev/null
+++ b/cscore/src/main/native/cpp/Instance.cpp
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "Instance.h"
+
+#include <wpi/Path.h>
+#include <wpi/SmallString.h>
+#include <wpi/StringRef.h>
+#include <wpi/raw_ostream.h>
+
+using namespace cs;
+
+static void def_log_func(unsigned int level, const char* file,
+                         unsigned int line, const char* msg) {
+  wpi::SmallString<128> buf;
+  wpi::raw_svector_ostream oss(buf);
+  if (level == 20) {
+    oss << "CS: " << msg << '\n';
+    wpi::errs() << oss.str();
+    return;
+  }
+
+  wpi::StringRef levelmsg;
+  if (level >= 50)
+    levelmsg = "CRITICAL: ";
+  else if (level >= 40)
+    levelmsg = "ERROR: ";
+  else if (level >= 30)
+    levelmsg = "WARNING: ";
+  else
+    return;
+  oss << "CS: " << levelmsg << msg << " (" << wpi::sys::path::filename(file)
+      << ':' << line << ")\n";
+  wpi::errs() << oss.str();
+}
+
+Instance::Instance() : telemetry(notifier), networkListener(logger, notifier) {
+  SetDefaultLogger();
+}
+
+Instance::~Instance() {}
+
+Instance& Instance::GetInstance() {
+  static Instance* inst = new Instance;
+  return *inst;
+}
+
+void Instance::Shutdown() {
+  eventLoop.Stop();
+  m_sinks.FreeAll();
+  m_sources.FreeAll();
+  networkListener.Stop();
+  telemetry.Stop();
+  notifier.Stop();
+}
+
+void Instance::SetDefaultLogger() { logger.SetLogger(def_log_func); }
+
+std::pair<CS_Source, std::shared_ptr<SourceData>> Instance::FindSource(
+    const SourceImpl& source) {
+  return m_sources.FindIf(
+      [&](const SourceData& data) { return data.source.get() == &source; });
+}
+
+std::pair<CS_Sink, std::shared_ptr<SinkData>> Instance::FindSink(
+    const SinkImpl& sink) {
+  return m_sinks.FindIf(
+      [&](const SinkData& data) { return data.sink.get() == &sink; });
+}
+
+CS_Source Instance::CreateSource(CS_SourceKind kind,
+                                 std::shared_ptr<SourceImpl> source) {
+  auto handle = m_sources.Allocate(kind, source);
+  notifier.NotifySource(source->GetName(), handle, CS_SOURCE_CREATED);
+  source->Start();
+  return handle;
+}
+
+CS_Sink Instance::CreateSink(CS_SinkKind kind, std::shared_ptr<SinkImpl> sink) {
+  auto handle = m_sinks.Allocate(kind, sink);
+  notifier.NotifySink(sink->GetName(), handle, CS_SINK_CREATED);
+  return handle;
+}
+
+void Instance::DestroySource(CS_Source handle) {
+  if (auto data = m_sources.Free(handle))
+    notifier.NotifySource(data->source->GetName(), handle, CS_SOURCE_DESTROYED);
+}
+
+void Instance::DestroySink(CS_Sink handle) {
+  if (auto data = m_sinks.Free(handle))
+    notifier.NotifySink(data->sink->GetName(), handle, CS_SINK_DESTROYED);
+}
diff --git a/cscore/src/main/native/cpp/Instance.h b/cscore/src/main/native/cpp/Instance.h
new file mode 100644
index 0000000..0c566f3
--- /dev/null
+++ b/cscore/src/main/native/cpp/Instance.h
@@ -0,0 +1,115 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_INSTANCE_H_
+#define CSCORE_INSTANCE_H_
+
+#include <memory>
+#include <utility>
+
+#include <wpi/EventLoopRunner.h>
+#include <wpi/Logger.h>
+
+#include "Log.h"
+#include "NetworkListener.h"
+#include "Notifier.h"
+#include "SinkImpl.h"
+#include "SourceImpl.h"
+#include "Telemetry.h"
+#include "UnlimitedHandleResource.h"
+
+namespace cs {
+
+struct SourceData {
+  SourceData(CS_SourceKind kind_, std::shared_ptr<SourceImpl> source_)
+      : kind{kind_}, refCount{0}, source{source_} {}
+
+  CS_SourceKind kind;
+  std::atomic_int refCount;
+  std::shared_ptr<SourceImpl> source;
+};
+
+struct SinkData {
+  explicit SinkData(CS_SinkKind kind_, std::shared_ptr<SinkImpl> sink_)
+      : kind{kind_}, refCount{0}, sourceHandle{0}, sink{sink_} {}
+
+  CS_SinkKind kind;
+  std::atomic_int refCount;
+  std::atomic<CS_Source> sourceHandle;
+  std::shared_ptr<SinkImpl> sink;
+};
+
+class Instance {
+ public:
+  Instance(const Instance&) = delete;
+  Instance& operator=(const Instance&) = delete;
+  ~Instance();
+
+  static Instance& GetInstance();
+
+  void Shutdown();
+
+  wpi::Logger logger;
+  Notifier notifier;
+  Telemetry telemetry;
+  NetworkListener networkListener;
+
+ private:
+  UnlimitedHandleResource<Handle, SourceData, Handle::kSource> m_sources;
+  UnlimitedHandleResource<Handle, SinkData, Handle::kSink> m_sinks;
+
+ public:
+  wpi::EventLoopRunner eventLoop;
+
+  std::pair<CS_Sink, std::shared_ptr<SinkData>> FindSink(const SinkImpl& sink);
+  std::pair<CS_Source, std::shared_ptr<SourceData>> FindSource(
+      const SourceImpl& source);
+
+  void SetDefaultLogger();
+
+  std::shared_ptr<SourceData> GetSource(CS_Source handle) {
+    return m_sources.Get(handle);
+  }
+
+  std::shared_ptr<SinkData> GetSink(CS_Sink handle) {
+    return m_sinks.Get(handle);
+  }
+
+  CS_Source CreateSource(CS_SourceKind kind,
+                         std::shared_ptr<SourceImpl> source);
+
+  CS_Sink CreateSink(CS_SinkKind kind, std::shared_ptr<SinkImpl> sink);
+
+  void DestroySource(CS_Source handle);
+  void DestroySink(CS_Sink handle);
+
+  wpi::ArrayRef<CS_Source> EnumerateSourceHandles(
+      wpi::SmallVectorImpl<CS_Source>& vec) {
+    return m_sources.GetAll(vec);
+  }
+
+  wpi::ArrayRef<CS_Sink> EnumerateSinkHandles(
+      wpi::SmallVectorImpl<CS_Sink>& vec) {
+    return m_sinks.GetAll(vec);
+  }
+
+  wpi::ArrayRef<CS_Sink> EnumerateSourceSinks(
+      CS_Source source, wpi::SmallVectorImpl<CS_Sink>& vec) {
+    vec.clear();
+    m_sinks.ForEach([&](CS_Sink sinkHandle, const SinkData& data) {
+      if (source == data.sourceHandle.load()) vec.push_back(sinkHandle);
+    });
+    return vec;
+  }
+
+ private:
+  Instance();
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_INSTANCE_H_
diff --git a/cscore/src/main/native/cpp/JpegUtil.cpp b/cscore/src/main/native/cpp/JpegUtil.cpp
new file mode 100644
index 0000000..35891e8
--- /dev/null
+++ b/cscore/src/main/native/cpp/JpegUtil.cpp
@@ -0,0 +1,197 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "JpegUtil.h"
+
+#include <wpi/raw_istream.h>
+
+namespace cs {
+
+// DHT data for MJPEG images that don't have it.
+static const unsigned char dhtData[] = {
+    0xff, 0xc4, 0x01, 0xa2, 0x00, 0x00, 0x01, 0x05, 0x01, 0x01, 0x01, 0x01,
+    0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02,
+    0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09, 0x0a, 0x0b, 0x01, 0x00, 0x03,
+    0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09,
+    0x0a, 0x0b, 0x10, 0x00, 0x02, 0x01, 0x03, 0x03, 0x02, 0x04, 0x03, 0x05,
+    0x05, 0x04, 0x04, 0x00, 0x00, 0x01, 0x7d, 0x01, 0x02, 0x03, 0x00, 0x04,
+    0x11, 0x05, 0x12, 0x21, 0x31, 0x41, 0x06, 0x13, 0x51, 0x61, 0x07, 0x22,
+    0x71, 0x14, 0x32, 0x81, 0x91, 0xa1, 0x08, 0x23, 0x42, 0xb1, 0xc1, 0x15,
+    0x52, 0xd1, 0xf0, 0x24, 0x33, 0x62, 0x72, 0x82, 0x09, 0x0a, 0x16, 0x17,
+    0x18, 0x19, 0x1a, 0x25, 0x26, 0x27, 0x28, 0x29, 0x2a, 0x34, 0x35, 0x36,
+    0x37, 0x38, 0x39, 0x3a, 0x43, 0x44, 0x45, 0x46, 0x47, 0x48, 0x49, 0x4a,
+    0x53, 0x54, 0x55, 0x56, 0x57, 0x58, 0x59, 0x5a, 0x63, 0x64, 0x65, 0x66,
+    0x67, 0x68, 0x69, 0x6a, 0x73, 0x74, 0x75, 0x76, 0x77, 0x78, 0x79, 0x7a,
+    0x83, 0x84, 0x85, 0x86, 0x87, 0x88, 0x89, 0x8a, 0x92, 0x93, 0x94, 0x95,
+    0x96, 0x97, 0x98, 0x99, 0x9a, 0xa2, 0xa3, 0xa4, 0xa5, 0xa6, 0xa7, 0xa8,
+    0xa9, 0xaa, 0xb2, 0xb3, 0xb4, 0xb5, 0xb6, 0xb7, 0xb8, 0xb9, 0xba, 0xc2,
+    0xc3, 0xc4, 0xc5, 0xc6, 0xc7, 0xc8, 0xc9, 0xca, 0xd2, 0xd3, 0xd4, 0xd5,
+    0xd6, 0xd7, 0xd8, 0xd9, 0xda, 0xe1, 0xe2, 0xe3, 0xe4, 0xe5, 0xe6, 0xe7,
+    0xe8, 0xe9, 0xea, 0xf1, 0xf2, 0xf3, 0xf4, 0xf5, 0xf6, 0xf7, 0xf8, 0xf9,
+    0xfa, 0x11, 0x00, 0x02, 0x01, 0x02, 0x04, 0x04, 0x03, 0x04, 0x07, 0x05,
+    0x04, 0x04, 0x00, 0x01, 0x02, 0x77, 0x00, 0x01, 0x02, 0x03, 0x11, 0x04,
+    0x05, 0x21, 0x31, 0x06, 0x12, 0x41, 0x51, 0x07, 0x61, 0x71, 0x13, 0x22,
+    0x32, 0x81, 0x08, 0x14, 0x42, 0x91, 0xa1, 0xb1, 0xc1, 0x09, 0x23, 0x33,
+    0x52, 0xf0, 0x15, 0x62, 0x72, 0xd1, 0x0a, 0x16, 0x24, 0x34, 0xe1, 0x25,
+    0xf1, 0x17, 0x18, 0x19, 0x1a, 0x26, 0x27, 0x28, 0x29, 0x2a, 0x35, 0x36,
+    0x37, 0x38, 0x39, 0x3a, 0x43, 0x44, 0x45, 0x46, 0x47, 0x48, 0x49, 0x4a,
+    0x53, 0x54, 0x55, 0x56, 0x57, 0x58, 0x59, 0x5a, 0x63, 0x64, 0x65, 0x66,
+    0x67, 0x68, 0x69, 0x6a, 0x73, 0x74, 0x75, 0x76, 0x77, 0x78, 0x79, 0x7a,
+    0x82, 0x83, 0x84, 0x85, 0x86, 0x87, 0x88, 0x89, 0x8a, 0x92, 0x93, 0x94,
+    0x95, 0x96, 0x97, 0x98, 0x99, 0x9a, 0xa2, 0xa3, 0xa4, 0xa5, 0xa6, 0xa7,
+    0xa8, 0xa9, 0xaa, 0xb2, 0xb3, 0xb4, 0xb5, 0xb6, 0xb7, 0xb8, 0xb9, 0xba,
+    0xc2, 0xc3, 0xc4, 0xc5, 0xc6, 0xc7, 0xc8, 0xc9, 0xca, 0xd2, 0xd3, 0xd4,
+    0xd5, 0xd6, 0xd7, 0xd8, 0xd9, 0xda, 0xe2, 0xe3, 0xe4, 0xe5, 0xe6, 0xe7,
+    0xe8, 0xe9, 0xea, 0xf2, 0xf3, 0xf4, 0xf5, 0xf6, 0xf7, 0xf8, 0xf9, 0xfa};
+
+bool IsJpeg(wpi::StringRef data) {
+  if (data.size() < 11) return false;
+
+  // Check for valid SOI
+  auto bytes = data.bytes_begin();
+  if (bytes[0] != 0xff || bytes[1] != 0xd8) return false;
+  return true;
+}
+
+bool GetJpegSize(wpi::StringRef data, int* width, int* height) {
+  if (!IsJpeg(data)) return false;
+
+  data = data.substr(2);  // Get to the first block
+  auto bytes = data.bytes_begin();
+  for (;;) {
+    if (data.size() < 4) return false;  // EOF
+    bytes = data.bytes_begin();
+    if (bytes[0] != 0xff) return false;  // not a tag
+    if (bytes[1] == 0xd9) return false;  // EOI without finding SOF?
+    if (bytes[1] == 0xda) return false;  // SOS without finding SOF?
+    if (bytes[1] == 0xc0) {
+      // SOF contains the file size
+      if (data.size() < 9) return false;
+      *height = bytes[5] * 256 + bytes[6];
+      *width = bytes[7] * 256 + bytes[8];
+      return true;
+    }
+    // Go to the next block
+    data = data.substr(bytes[2] * 256 + bytes[3] + 2);
+  }
+}
+
+bool JpegNeedsDHT(const char* data, size_t* size, size_t* locSOF) {
+  wpi::StringRef sdata(data, *size);
+  if (!IsJpeg(sdata)) return false;
+
+  *locSOF = *size;
+
+  // Search until SOS for DHT tag
+  sdata = sdata.substr(2);  // Get to the first block
+  auto bytes = sdata.bytes_begin();
+  for (;;) {
+    if (sdata.size() < 4) return false;  // EOF
+    bytes = sdata.bytes_begin();
+    if (bytes[0] != 0xff) return false;                   // not a tag
+    if (bytes[1] == 0xda) break;                          // SOS
+    if (bytes[1] == 0xc4) return false;                   // DHT
+    if (bytes[1] == 0xc0) *locSOF = sdata.data() - data;  // SOF
+    // Go to the next block
+    sdata = sdata.substr(bytes[2] * 256 + bytes[3] + 2);
+  }
+
+  // Only add DHT if we also found SOF (insertion point)
+  if (*locSOF != *size) {
+    *size += sizeof(dhtData);
+    return true;
+  }
+  return false;
+}
+
+wpi::StringRef JpegGetDHT() {
+  return wpi::StringRef(reinterpret_cast<const char*>(dhtData),
+                        sizeof(dhtData));
+}
+
+static inline void ReadInto(wpi::raw_istream& is, std::string& buf,
+                            size_t len) {
+  size_t oldSize = buf.size();
+  buf.resize(oldSize + len);
+  is.read(&(*buf.begin()) + oldSize, len);
+}
+
+bool ReadJpeg(wpi::raw_istream& is, std::string& buf, int* width, int* height) {
+  // in case we don't get a SOF
+  *width = 0;
+  *height = 0;
+
+  // read SOI and first marker
+  buf.resize(4);
+  is.read(&(*buf.begin()), 4);
+  if (is.has_error()) return false;
+
+  // Check for valid SOI
+  auto bytes = reinterpret_cast<const unsigned char*>(buf.data());
+  if (bytes[0] != 0xff || bytes[1] != 0xd8) return false;
+  size_t pos = 2;  // point to first marker
+  for (;;) {
+    bytes = reinterpret_cast<const unsigned char*>(buf.data() + pos);
+    if (bytes[0] != 0xff) return false;  // not a marker
+    unsigned char marker = bytes[1];
+
+    if (marker == 0xd9) return true;  // EOI, we're done
+
+    if (marker == 0xda) {
+      // SOS: need to keep reading until we reach a normal marker.
+      // Byte stuffing ensures we don't get false markers.
+      // Have to read a byte at a time as we don't want to overread.
+      pos += 2;  // point after SOS marker
+      bool maybeMarker = false;
+      for (;;) {
+        ReadInto(is, buf, 1);
+        if (is.has_error()) return false;
+        bytes = reinterpret_cast<const unsigned char*>(buf.data() + pos);
+        if (maybeMarker) {
+          if (bytes[0] != 0x00 && bytes[0] != 0xff &&
+              (bytes[0] < 0xd0 || bytes[0] > 0xd7))
+            break;
+          maybeMarker = false;
+        } else if (bytes[0] == 0xff) {
+          maybeMarker = true;
+        }
+        ++pos;  // point after byte we finished reading
+      }
+      --pos;  // point back to start of marker
+      continue;
+    }
+
+    // A normal block. Read the length
+    ReadInto(is, buf, 2);  // read length
+    if (is.has_error()) return false;
+
+    // Point to length
+    pos += 2;
+    bytes = reinterpret_cast<const unsigned char*>(buf.data() + pos);
+
+    // Read the block and the next marker
+    size_t blockLength = bytes[0] * 256 + bytes[1];
+    ReadInto(is, buf, blockLength);
+    if (is.has_error()) return false;
+    bytes = reinterpret_cast<const unsigned char*>(buf.data() + pos);
+
+    // Special block processing
+    if (marker == 0xc0) {
+      // SOF: contains the file size; make sure we actually read enough bytes
+      if (blockLength >= 7) {
+        *height = bytes[3] * 256 + bytes[4];
+        *width = bytes[5] * 256 + bytes[6];
+      }
+    }
+
+    // Point to next marker
+    pos += blockLength;
+  }
+}
+
+}  // namespace cs
diff --git a/cscore/src/main/native/cpp/JpegUtil.h b/cscore/src/main/native/cpp/JpegUtil.h
new file mode 100644
index 0000000..082fdc4
--- /dev/null
+++ b/cscore/src/main/native/cpp/JpegUtil.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_JPEGUTIL_H_
+#define CSCORE_JPEGUTIL_H_
+
+#include <string>
+
+#include <wpi/StringRef.h>
+
+namespace wpi {
+class raw_istream;
+}  // namespace wpi
+
+namespace cs {
+
+bool IsJpeg(wpi::StringRef data);
+
+bool GetJpegSize(wpi::StringRef data, int* width, int* height);
+
+bool JpegNeedsDHT(const char* data, size_t* size, size_t* locSOF);
+
+wpi::StringRef JpegGetDHT();
+
+bool ReadJpeg(wpi::raw_istream& is, std::string& buf, int* width, int* height);
+
+}  // namespace cs
+
+#endif  // CSCORE_JPEGUTIL_H_
diff --git a/cscore/src/main/native/cpp/Log.h b/cscore/src/main/native/cpp/Log.h
new file mode 100644
index 0000000..b9fd9ab
--- /dev/null
+++ b/cscore/src/main/native/cpp/Log.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_LOG_H_
+#define CSCORE_LOG_H_
+
+#include <wpi/Logger.h>
+
+#define LOG(level, x) WPI_LOG(m_logger, level, x)
+
+#undef ERROR
+#define ERROR(x) WPI_ERROR(m_logger, x)
+#define WARNING(x) WPI_WARNING(m_logger, x)
+#define INFO(x) WPI_INFO(m_logger, x)
+
+#define DEBUG0(x) WPI_DEBUG(m_logger, x)
+#define DEBUG1(x) WPI_DEBUG1(m_logger, x)
+#define DEBUG2(x) WPI_DEBUG2(m_logger, x)
+#define DEBUG3(x) WPI_DEBUG3(m_logger, x)
+#define DEBUG4(x) WPI_DEBUG4(m_logger, x)
+
+#define SERROR(x) ERROR(GetName() << ": " << x)
+#define SWARNING(x) WARNING(GetName() << ": " << x)
+#define SINFO(x) INFO(GetName() << ": " << x)
+
+#define SDEBUG(x) DEBUG0(GetName() << ": " << x)
+#define SDEBUG1(x) DEBUG1(GetName() << ": " << x)
+#define SDEBUG2(x) DEBUG2(GetName() << ": " << x)
+#define SDEBUG3(x) DEBUG3(GetName() << ": " << x)
+#define SDEBUG4(x) DEBUG4(GetName() << ": " << x)
+
+#endif  // CSCORE_LOG_H_
diff --git a/cscore/src/main/native/cpp/MjpegServerImpl.cpp b/cscore/src/main/native/cpp/MjpegServerImpl.cpp
new file mode 100644
index 0000000..e30b745
--- /dev/null
+++ b/cscore/src/main/native/cpp/MjpegServerImpl.cpp
@@ -0,0 +1,1005 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "MjpegServerImpl.h"
+
+#include <chrono>
+
+#include <wpi/HttpUtil.h>
+#include <wpi/SmallString.h>
+#include <wpi/TCPAcceptor.h>
+#include <wpi/raw_socket_istream.h>
+#include <wpi/raw_socket_ostream.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "JpegUtil.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "SourceImpl.h"
+#include "c_util.h"
+#include "cscore_cpp.h"
+
+using namespace cs;
+
+// The boundary used for the M-JPEG stream.
+// It separates the multipart stream of pictures
+#define BOUNDARY "boundarydonotcross"
+
+// A bare-bones HTML webpage for user friendliness.
+static const char* emptyRootPage =
+    "</head><body>"
+    "<img src=\"/stream.mjpg\" /><p />"
+    "<a href=\"/settings.json\">Settings JSON</a>"
+    "</body></html>";
+
+// An HTML page to be sent when a source exists
+static const char* startRootPage =
+    "<script>\n"
+    "function httpGetAsync(name, val)\n"
+    "{\n"
+    "    var host = location.protocol + '//' + location.host + "
+    "'/?action=command&' + name + '=' + val;\n"
+    "    var xmlHttp = new XMLHttpRequest();\n"
+    "    xmlHttp.open(\"GET\", host, true);\n"
+    "    xmlHttp.send(null);\n"
+    "}\n"
+    "function updateInt(prop, name, val) {\n"
+    "    document.querySelector(prop).value = val;\n"
+    "    httpGetAsync(name, val);\n"
+    "}\n"
+    "function update(name, val) {\n"
+    "    httpGetAsync(name, val);\n"
+    "}\n"
+    "</script>\n"
+    "<style>\n"
+    "table, th, td {\n"
+    "    border: 1px solid black;\n"
+    "    border-collapse: collapse;\n"
+    "}\n"
+    ".settings { float: left; }\n"
+    ".stream { display: inline-block; margin-left: 10px; }\n"
+    "</style>\n"
+    "</head><body>\n"
+    "<div class=\"stream\">\n"
+    "<img src=\"/stream.mjpg\" /><p />\n"
+    "<a href=\"/settings.json\">Settings JSON</a> |\n"
+    "<a href=\"/config.json\">Source Config JSON</a>\n"
+    "</div>\n"
+    "<div class=\"settings\">\n";
+static const char* endRootPage = "</div></body></html>";
+
+class MjpegServerImpl::ConnThread : public wpi::SafeThread {
+ public:
+  explicit ConnThread(const wpi::Twine& name, wpi::Logger& logger)
+      : m_name(name.str()), m_logger(logger) {}
+
+  void Main();
+
+  bool ProcessCommand(wpi::raw_ostream& os, SourceImpl& source,
+                      wpi::StringRef parameters, bool respond);
+  void SendJSON(wpi::raw_ostream& os, SourceImpl& source, bool header);
+  void SendHTMLHeadTitle(wpi::raw_ostream& os) const;
+  void SendHTML(wpi::raw_ostream& os, SourceImpl& source, bool header);
+  void SendStream(wpi::raw_socket_ostream& os);
+  void ProcessRequest();
+
+  std::unique_ptr<wpi::NetworkStream> m_stream;
+  std::shared_ptr<SourceImpl> m_source;
+  bool m_streaming = false;
+  bool m_noStreaming = false;
+  int m_width = 0;
+  int m_height = 0;
+  int m_compression = -1;
+  int m_defaultCompression = 80;
+  int m_fps = 0;
+
+ private:
+  std::string m_name;
+  wpi::Logger& m_logger;
+
+  wpi::StringRef GetName() { return m_name; }
+
+  std::shared_ptr<SourceImpl> GetSource() {
+    std::scoped_lock lock(m_mutex);
+    return m_source;
+  }
+
+  void StartStream() {
+    std::scoped_lock lock(m_mutex);
+    if (m_source) m_source->EnableSink();
+    m_streaming = true;
+  }
+
+  void StopStream() {
+    std::scoped_lock lock(m_mutex);
+    if (m_source) m_source->DisableSink();
+    m_streaming = false;
+  }
+};
+
+// Standard header to send along with other header information like mimetype.
+//
+// The parameters should ensure the browser does not cache our answer.
+// A browser should connect for each file and not serve files from its cache.
+// Using cached pictures would lead to showing old/outdated pictures.
+// Many browsers seem to ignore, or at least not always obey, those headers.
+static void SendHeader(wpi::raw_ostream& os, int code,
+                       const wpi::Twine& codeText,
+                       const wpi::Twine& contentType,
+                       const wpi::Twine& extra = wpi::Twine{}) {
+  os << "HTTP/1.0 " << code << ' ' << codeText << "\r\n";
+  os << "Connection: close\r\n"
+        "Server: CameraServer/1.0\r\n"
+        "Cache-Control: no-store, no-cache, must-revalidate, pre-check=0, "
+        "post-check=0, max-age=0\r\n"
+        "Pragma: no-cache\r\n"
+        "Expires: Mon, 3 Jan 2000 12:34:56 GMT\r\n";
+  os << "Content-Type: " << contentType << "\r\n";
+  os << "Access-Control-Allow-Origin: *\r\nAccess-Control-Allow-Methods: *\r\n";
+  wpi::SmallString<128> extraBuf;
+  wpi::StringRef extraStr = extra.toStringRef(extraBuf);
+  if (!extraStr.empty()) os << extraStr << "\r\n";
+  os << "\r\n";  // header ends with a blank line
+}
+
+// Send error header and message
+// @param code HTTP error code (e.g. 404)
+// @param message Additional message text
+static void SendError(wpi::raw_ostream& os, int code,
+                      const wpi::Twine& message) {
+  wpi::StringRef codeText, extra, baseMessage;
+  switch (code) {
+    case 401:
+      codeText = "Unauthorized";
+      extra = "WWW-Authenticate: Basic realm=\"CameraServer\"";
+      baseMessage = "401: Not Authenticated!";
+      break;
+    case 404:
+      codeText = "Not Found";
+      baseMessage = "404: Not Found!";
+      break;
+    case 500:
+      codeText = "Internal Server Error";
+      baseMessage = "500: Internal Server Error!";
+      break;
+    case 400:
+      codeText = "Bad Request";
+      baseMessage = "400: Not Found!";
+      break;
+    case 403:
+      codeText = "Forbidden";
+      baseMessage = "403: Forbidden!";
+      break;
+    case 503:
+      codeText = "Service Unavailable";
+      baseMessage = "503: Service Unavailable";
+      break;
+    default:
+      code = 501;
+      codeText = "Not Implemented";
+      baseMessage = "501: Not Implemented!";
+      break;
+  }
+  SendHeader(os, code, codeText, "text/plain", extra);
+  os << baseMessage << "\r\n" << message;
+}
+
+// Perform a command specified by HTTP GET parameters.
+bool MjpegServerImpl::ConnThread::ProcessCommand(wpi::raw_ostream& os,
+                                                 SourceImpl& source,
+                                                 wpi::StringRef parameters,
+                                                 bool respond) {
+  wpi::SmallString<256> responseBuf;
+  wpi::raw_svector_ostream response{responseBuf};
+  // command format: param1=value1&param2=value2...
+  while (!parameters.empty()) {
+    // split out next param and value
+    wpi::StringRef rawParam, rawValue;
+    std::tie(rawParam, parameters) = parameters.split('&');
+    if (rawParam.empty()) continue;  // ignore "&&"
+    std::tie(rawParam, rawValue) = rawParam.split('=');
+    if (rawParam.empty() || rawValue.empty()) continue;  // ignore "param="
+    SDEBUG4("HTTP parameter \"" << rawParam << "\" value \"" << rawValue
+                                << "\"");
+
+    // unescape param
+    bool error = false;
+    wpi::SmallString<64> paramBuf;
+    wpi::StringRef param = wpi::UnescapeURI(rawParam, paramBuf, &error);
+    if (error) {
+      wpi::SmallString<128> error;
+      wpi::raw_svector_ostream oss{error};
+      oss << "could not unescape parameter \"" << rawParam << "\"";
+      SendError(os, 500, error.str());
+      SDEBUG(error.str());
+      return false;
+    }
+
+    // unescape value
+    wpi::SmallString<64> valueBuf;
+    wpi::StringRef value = wpi::UnescapeURI(rawValue, valueBuf, &error);
+    if (error) {
+      wpi::SmallString<128> error;
+      wpi::raw_svector_ostream oss{error};
+      oss << "could not unescape value \"" << rawValue << "\"";
+      SendError(os, 500, error.str());
+      SDEBUG(error.str());
+      return false;
+    }
+
+    // Handle resolution, compression, and FPS.  These are handled locally
+    // rather than passed to the source.
+    if (param == "resolution") {
+      wpi::StringRef widthStr, heightStr;
+      std::tie(widthStr, heightStr) = value.split('x');
+      int width, height;
+      if (widthStr.getAsInteger(10, width)) {
+        response << param << ": \"width is not an integer\"\r\n";
+        SWARNING("HTTP parameter \"" << param << "\" width \"" << widthStr
+                                     << "\" is not an integer");
+        continue;
+      }
+      if (heightStr.getAsInteger(10, height)) {
+        response << param << ": \"height is not an integer\"\r\n";
+        SWARNING("HTTP parameter \"" << param << "\" height \"" << heightStr
+                                     << "\" is not an integer");
+        continue;
+      }
+      m_width = width;
+      m_height = height;
+      response << param << ": \"ok\"\r\n";
+      continue;
+    }
+
+    if (param == "fps") {
+      int fps;
+      if (value.getAsInteger(10, fps)) {
+        response << param << ": \"invalid integer\"\r\n";
+        SWARNING("HTTP parameter \"" << param << "\" value \"" << value
+                                     << "\" is not an integer");
+        continue;
+      } else {
+        m_fps = fps;
+        response << param << ": \"ok\"\r\n";
+      }
+      continue;
+    }
+
+    if (param == "compression") {
+      int compression;
+      if (value.getAsInteger(10, compression)) {
+        response << param << ": \"invalid integer\"\r\n";
+        SWARNING("HTTP parameter \"" << param << "\" value \"" << value
+                                     << "\" is not an integer");
+        continue;
+      } else {
+        m_compression = compression;
+        response << param << ": \"ok\"\r\n";
+      }
+      continue;
+    }
+
+    // ignore name parameter
+    if (param == "name") continue;
+
+    // try to assign parameter
+    auto prop = source.GetPropertyIndex(param);
+    if (!prop) {
+      response << param << ": \"ignored\"\r\n";
+      SWARNING("ignoring HTTP parameter \"" << param << "\"");
+      continue;
+    }
+
+    CS_Status status = 0;
+    auto kind = source.GetPropertyKind(prop);
+    switch (kind) {
+      case CS_PROP_BOOLEAN:
+      case CS_PROP_INTEGER:
+      case CS_PROP_ENUM: {
+        int val = 0;
+        if (value.getAsInteger(10, val)) {
+          response << param << ": \"invalid integer\"\r\n";
+          SWARNING("HTTP parameter \"" << param << "\" value \"" << value
+                                       << "\" is not an integer");
+        } else {
+          response << param << ": " << val << "\r\n";
+          SDEBUG4("HTTP parameter \"" << param << "\" value " << value);
+          source.SetProperty(prop, val, &status);
+        }
+        break;
+      }
+      case CS_PROP_STRING: {
+        response << param << ": \"ok\"\r\n";
+        SDEBUG4("HTTP parameter \"" << param << "\" value \"" << value << "\"");
+        source.SetStringProperty(prop, value, &status);
+        break;
+      }
+      default:
+        break;
+    }
+  }
+
+  // Send HTTP response
+  if (respond) {
+    SendHeader(os, 200, "OK", "text/plain");
+    os << response.str() << "\r\n";
+  }
+
+  return true;
+}
+
+void MjpegServerImpl::ConnThread::SendHTMLHeadTitle(
+    wpi::raw_ostream& os) const {
+  os << "<html><head><title>" << m_name << " CameraServer</title>"
+     << "<meta charset=\"UTF-8\">";
+}
+
+// Send the root html file with controls for all the settable properties.
+void MjpegServerImpl::ConnThread::SendHTML(wpi::raw_ostream& os,
+                                           SourceImpl& source, bool header) {
+  if (header) SendHeader(os, 200, "OK", "text/html");
+
+  SendHTMLHeadTitle(os);
+  os << startRootPage;
+  wpi::SmallVector<int, 32> properties_vec;
+  CS_Status status = 0;
+  for (auto prop : source.EnumerateProperties(properties_vec, &status)) {
+    wpi::SmallString<128> name_buf;
+    auto name = source.GetPropertyName(prop, name_buf, &status);
+    if (name.startswith("raw_")) continue;
+    auto kind = source.GetPropertyKind(prop);
+    os << "<p />"
+       << "<label for=\"" << name << "\">" << name << "</label>\n";
+    switch (kind) {
+      case CS_PROP_BOOLEAN:
+        os << "<input id=\"" << name
+           << "\" type=\"checkbox\" onclick=\"update('" << name
+           << "', this.checked ? 1 : 0)\" ";
+        if (source.GetProperty(prop, &status) != 0)
+          os << "checked />\n";
+        else
+          os << " />\n";
+        break;
+      case CS_PROP_INTEGER: {
+        auto valI = source.GetProperty(prop, &status);
+        auto min = source.GetPropertyMin(prop, &status);
+        auto max = source.GetPropertyMax(prop, &status);
+        auto step = source.GetPropertyStep(prop, &status);
+        os << "<input type=\"range\" min=\"" << min << "\" max=\"" << max
+           << "\" value=\"" << valI << "\" id=\"" << name << "\" step=\""
+           << step << "\" oninput=\"updateInt('#" << name << "op', '" << name
+           << "', value)\" />\n";
+        os << "<output for=\"" << name << "\" id=\"" << name << "op\">" << valI
+           << "</output>\n";
+        break;
+      }
+      case CS_PROP_ENUM: {
+        auto valE = source.GetProperty(prop, &status);
+        auto choices = source.GetEnumPropertyChoices(prop, &status);
+        int j = 0;
+        for (auto choice = choices.begin(), end = choices.end(); choice != end;
+             ++j, ++choice) {
+          if (choice->empty()) continue;  // skip empty choices
+          // replace any non-printable characters in name with spaces
+          wpi::SmallString<128> ch_name;
+          for (char ch : *choice)
+            ch_name.push_back(std::isprint(ch) ? ch : ' ');
+          os << "<input id=\"" << name << j << "\" type=\"radio\" name=\""
+             << name << "\" value=\"" << ch_name << "\" onclick=\"update('"
+             << name << "', " << j << ")\"";
+          if (j == valE) {
+            os << " checked";
+          }
+          os << " /><label for=\"" << name << j << "\">" << ch_name
+             << "</label>\n";
+        }
+        break;
+      }
+      case CS_PROP_STRING: {
+        wpi::SmallString<128> strval_buf;
+        os << "<input type=\"text\" id=\"" << name << "box\" name=\"" << name
+           << "\" value=\""
+           << source.GetStringProperty(prop, strval_buf, &status) << "\" />\n";
+        os << "<input type=\"button\" value =\"Submit\" onclick=\"update('"
+           << name << "', " << name << "box.value)\" />\n";
+        break;
+      }
+      default:
+        break;
+    }
+  }
+
+  status = 0;
+  auto info = GetUsbCameraInfo(Instance::GetInstance().FindSource(source).first,
+                               &status);
+  if (status == CS_OK) {
+    os << "<p>USB device path: " << info.path << '\n';
+    for (auto&& path : info.otherPaths)
+      os << "<p>Alternate device path: " << path << '\n';
+  }
+
+  os << "<p>Supported Video Modes:</p>\n";
+  os << "<table cols=\"4\" style=\"border: 1px solid black\">\n";
+  os << "<tr><th>Pixel Format</th>"
+     << "<th>Width</th>"
+     << "<th>Height</th>"
+     << "<th>FPS</th></tr>";
+  for (auto mode : source.EnumerateVideoModes(&status)) {
+    os << "<tr><td>";
+    switch (mode.pixelFormat) {
+      case VideoMode::kMJPEG:
+        os << "MJPEG";
+        break;
+      case VideoMode::kYUYV:
+        os << "YUYV";
+        break;
+      case VideoMode::kRGB565:
+        os << "RGB565";
+        break;
+      case VideoMode::kBGR:
+        os << "BGR";
+        break;
+      case VideoMode::kGray:
+        os << "gray";
+        break;
+      default:
+        os << "unknown";
+        break;
+    }
+    os << "</td><td>" << mode.width;
+    os << "</td><td>" << mode.height;
+    os << "</td><td>" << mode.fps;
+    os << "</td></tr>";
+  }
+  os << "</table>\n";
+  os << endRootPage << "\r\n";
+  os.flush();
+}
+
+// Send a JSON file which is contains information about the source parameters.
+void MjpegServerImpl::ConnThread::SendJSON(wpi::raw_ostream& os,
+                                           SourceImpl& source, bool header) {
+  if (header) SendHeader(os, 200, "OK", "application/json");
+
+  os << "{\n\"controls\": [\n";
+  wpi::SmallVector<int, 32> properties_vec;
+  bool first = true;
+  CS_Status status = 0;
+  for (auto prop : source.EnumerateProperties(properties_vec, &status)) {
+    if (first)
+      first = false;
+    else
+      os << ",\n";
+    os << '{';
+    wpi::SmallString<128> name_buf;
+    auto name = source.GetPropertyName(prop, name_buf, &status);
+    auto kind = source.GetPropertyKind(prop);
+    os << "\n\"name\": \"" << name << '"';
+    os << ",\n\"id\": \"" << prop << '"';
+    os << ",\n\"type\": \"" << kind << '"';
+    os << ",\n\"min\": \"" << source.GetPropertyMin(prop, &status) << '"';
+    os << ",\n\"max\": \"" << source.GetPropertyMax(prop, &status) << '"';
+    os << ",\n\"step\": \"" << source.GetPropertyStep(prop, &status) << '"';
+    os << ",\n\"default\": \"" << source.GetPropertyDefault(prop, &status)
+       << '"';
+    os << ",\n\"value\": \"";
+    switch (kind) {
+      case CS_PROP_BOOLEAN:
+      case CS_PROP_INTEGER:
+      case CS_PROP_ENUM:
+        os << source.GetProperty(prop, &status);
+        break;
+      case CS_PROP_STRING: {
+        wpi::SmallString<128> strval_buf;
+        os << source.GetStringProperty(prop, strval_buf, &status);
+        break;
+      }
+      default:
+        break;
+    }
+    os << '"';
+    // os << ",\n\"dest\": \"0\"";
+    // os << ",\n\"flags\": \"" << param->flags << '"';
+    // os << ",\n\"group\": \"" << param->group << '"';
+
+    // append the menu object to the menu typecontrols
+    if (source.GetPropertyKind(prop) == CS_PROP_ENUM) {
+      os << ",\n\"menu\": {";
+      auto choices = source.GetEnumPropertyChoices(prop, &status);
+      int j = 0;
+      for (auto choice = choices.begin(), end = choices.end(); choice != end;
+           ++j, ++choice) {
+        if (j != 0) os << ", ";
+        // replace any non-printable characters in name with spaces
+        wpi::SmallString<128> ch_name;
+        for (char ch : *choice) ch_name.push_back(std::isprint(ch) ? ch : ' ');
+        os << '"' << j << "\": \"" << ch_name << '"';
+      }
+      os << "}\n";
+    }
+    os << '}';
+  }
+  os << "\n],\n\"modes\": [\n";
+  first = true;
+  for (auto mode : source.EnumerateVideoModes(&status)) {
+    if (first)
+      first = false;
+    else
+      os << ",\n";
+    os << '{';
+    os << "\n\"pixelFormat\": \"";
+    switch (mode.pixelFormat) {
+      case VideoMode::kMJPEG:
+        os << "MJPEG";
+        break;
+      case VideoMode::kYUYV:
+        os << "YUYV";
+        break;
+      case VideoMode::kRGB565:
+        os << "RGB565";
+        break;
+      case VideoMode::kBGR:
+        os << "BGR";
+        break;
+      case VideoMode::kGray:
+        os << "gray";
+        break;
+      default:
+        os << "unknown";
+        break;
+    }
+    os << "\",\n\"width\": \"" << mode.width << '"';
+    os << ",\n\"height\": \"" << mode.height << '"';
+    os << ",\n\"fps\": \"" << mode.fps << '"';
+    os << '}';
+  }
+  os << "\n]\n}\n";
+  os.flush();
+}
+
+MjpegServerImpl::MjpegServerImpl(const wpi::Twine& name, wpi::Logger& logger,
+                                 Notifier& notifier, Telemetry& telemetry,
+                                 const wpi::Twine& listenAddress, int port,
+                                 std::unique_ptr<wpi::NetworkAcceptor> acceptor)
+    : SinkImpl{name, logger, notifier, telemetry},
+      m_listenAddress(listenAddress.str()),
+      m_port(port),
+      m_acceptor{std::move(acceptor)} {
+  m_active = true;
+
+  wpi::SmallString<128> descBuf;
+  wpi::raw_svector_ostream desc{descBuf};
+  desc << "HTTP Server on port " << port;
+  SetDescription(desc.str());
+
+  // Create properties
+  m_widthProp = CreateProperty("width", [] {
+    return std::make_unique<PropertyImpl>("width", CS_PROP_INTEGER, 1, 0, 0);
+  });
+  m_heightProp = CreateProperty("height", [] {
+    return std::make_unique<PropertyImpl>("height", CS_PROP_INTEGER, 1, 0, 0);
+  });
+  m_compressionProp = CreateProperty("compression", [] {
+    return std::make_unique<PropertyImpl>("compression", CS_PROP_INTEGER, -1,
+                                          100, 1, -1, -1);
+  });
+  m_defaultCompressionProp = CreateProperty("default_compression", [] {
+    return std::make_unique<PropertyImpl>("default_compression",
+                                          CS_PROP_INTEGER, 0, 100, 1, 80, 80);
+  });
+  m_fpsProp = CreateProperty("fps", [] {
+    return std::make_unique<PropertyImpl>("fps", CS_PROP_INTEGER, 1, 0, 0);
+  });
+
+  m_serverThread = std::thread(&MjpegServerImpl::ServerThreadMain, this);
+}
+
+MjpegServerImpl::~MjpegServerImpl() { Stop(); }
+
+void MjpegServerImpl::Stop() {
+  m_active = false;
+
+  // wake up server thread by shutting down the socket
+  m_acceptor->shutdown();
+
+  // join server thread
+  if (m_serverThread.joinable()) m_serverThread.join();
+
+  // close streams
+  for (auto& connThread : m_connThreads) {
+    if (auto thr = connThread.GetThread()) {
+      if (thr->m_stream) thr->m_stream->close();
+    }
+    connThread.Stop();
+  }
+
+  // wake up connection threads by forcing an empty frame to be sent
+  if (auto source = GetSource()) source->Wakeup();
+}
+
+// Send HTTP response and a stream of JPG-frames
+void MjpegServerImpl::ConnThread::SendStream(wpi::raw_socket_ostream& os) {
+  if (m_noStreaming) {
+    SERROR("Too many simultaneous client streams");
+    SendError(os, 503, "Too many simultaneous streams");
+    return;
+  }
+
+  os.SetUnbuffered();
+
+  wpi::SmallString<256> header;
+  wpi::raw_svector_ostream oss{header};
+
+  SendHeader(oss, 200, "OK", "multipart/x-mixed-replace;boundary=" BOUNDARY);
+  os << oss.str();
+
+  SDEBUG("Headers send, sending stream now");
+
+  Frame::Time lastFrameTime = 0;
+  Frame::Time timePerFrame = 0;
+  if (m_fps != 0) timePerFrame = 1000000.0 / m_fps;
+  Frame::Time averageFrameTime = 0;
+  Frame::Time averagePeriod = 1000000;  // 1 second window
+  if (averagePeriod < timePerFrame) averagePeriod = timePerFrame * 10;
+
+  StartStream();
+  while (m_active && !os.has_error()) {
+    auto source = GetSource();
+    if (!source) {
+      // Source disconnected; sleep so we don't consume all processor time.
+      os << "\r\n";  // Keep connection alive
+      std::this_thread::sleep_for(std::chrono::milliseconds(200));
+      continue;
+    }
+    SDEBUG4("waiting for frame");
+    Frame frame = source->GetNextFrame(0.225);  // blocks
+    if (!m_active) break;
+    if (!frame) {
+      // Bad frame; sleep for 20 ms so we don't consume all processor time.
+      os << "\r\n";  // Keep connection alive
+      std::this_thread::sleep_for(std::chrono::milliseconds(20));
+      continue;
+    }
+
+    auto thisFrameTime = frame.GetTime();
+    if (thisFrameTime != 0 && timePerFrame != 0 && lastFrameTime != 0) {
+      Frame::Time deltaTime = thisFrameTime - lastFrameTime;
+
+      // drop frame if it is early compared to the desired frame rate AND
+      // the current average is higher than the desired average
+      if (deltaTime < timePerFrame && averageFrameTime < timePerFrame) {
+        // sleep for 1 ms so we don't consume all processor time
+        std::this_thread::sleep_for(std::chrono::milliseconds(1));
+        continue;
+      }
+
+      // update average
+      if (averageFrameTime != 0) {
+        averageFrameTime =
+            averageFrameTime * (averagePeriod - timePerFrame) / averagePeriod +
+            deltaTime * timePerFrame / averagePeriod;
+      } else {
+        averageFrameTime = deltaTime;
+      }
+    }
+
+    int width = m_width != 0 ? m_width : frame.GetOriginalWidth();
+    int height = m_height != 0 ? m_height : frame.GetOriginalHeight();
+    Image* image = frame.GetImageMJPEG(
+        width, height, m_compression,
+        m_compression == -1 ? m_defaultCompression : m_compression);
+    if (!image) {
+      // Shouldn't happen, but just in case...
+      std::this_thread::sleep_for(std::chrono::milliseconds(20));
+      continue;
+    }
+
+    const char* data = image->data();
+    size_t size = image->size();
+    bool addDHT = false;
+    size_t locSOF = size;
+    switch (image->pixelFormat) {
+      case VideoMode::kMJPEG:
+        // Determine if we need to add DHT to it, and allocate enough space
+        // for adding it if required.
+        addDHT = JpegNeedsDHT(data, &size, &locSOF);
+        break;
+      case VideoMode::kYUYV:
+      case VideoMode::kRGB565:
+      default:
+        // Bad frame; sleep for 10 ms so we don't consume all processor time.
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+        continue;
+    }
+
+    SDEBUG4("sending frame size=" << size << " addDHT=" << addDHT);
+
+    // print the individual mimetype and the length
+    // sending the content-length fixes random stream disruption observed
+    // with firefox
+    lastFrameTime = thisFrameTime;
+    double timestamp = lastFrameTime / 1000000.0;
+    header.clear();
+    oss << "\r\n--" BOUNDARY "\r\n"
+        << "Content-Type: image/jpeg\r\n"
+        << "Content-Length: " << size << "\r\n"
+        << "X-Timestamp: " << timestamp << "\r\n"
+        << "\r\n";
+    os << oss.str();
+    if (addDHT) {
+      // Insert DHT data immediately before SOF
+      os << wpi::StringRef(data, locSOF);
+      os << JpegGetDHT();
+      os << wpi::StringRef(data + locSOF, image->size() - locSOF);
+    } else {
+      os << wpi::StringRef(data, size);
+    }
+    // os.flush();
+  }
+  StopStream();
+}
+
+void MjpegServerImpl::ConnThread::ProcessRequest() {
+  wpi::raw_socket_istream is{*m_stream};
+  wpi::raw_socket_ostream os{*m_stream, true};
+
+  // Read the request string from the stream
+  wpi::SmallString<128> reqBuf;
+  wpi::StringRef req = is.getline(reqBuf, 4096);
+  if (is.has_error()) {
+    SDEBUG("error getting request string");
+    return;
+  }
+
+  enum { kCommand, kStream, kGetSettings, kGetSourceConfig, kRootPage } kind;
+  wpi::StringRef parameters;
+  size_t pos;
+
+  SDEBUG("HTTP request: '" << req << "'\n");
+
+  // Determine request kind.  Most of these are for mjpgstreamer
+  // compatibility, others are for Axis camera compatibility.
+  if ((pos = req.find("POST /stream")) != wpi::StringRef::npos) {
+    kind = kStream;
+    parameters = req.substr(req.find('?', pos + 12)).substr(1);
+  } else if ((pos = req.find("GET /?action=stream")) != wpi::StringRef::npos) {
+    kind = kStream;
+    parameters = req.substr(req.find('&', pos + 19)).substr(1);
+  } else if ((pos = req.find("GET /stream.mjpg")) != wpi::StringRef::npos) {
+    kind = kStream;
+    parameters = req.substr(req.find('?', pos + 16)).substr(1);
+  } else if (req.find("GET /settings") != wpi::StringRef::npos &&
+             req.find(".json") != wpi::StringRef::npos) {
+    kind = kGetSettings;
+  } else if (req.find("GET /config") != wpi::StringRef::npos &&
+             req.find(".json") != wpi::StringRef::npos) {
+    kind = kGetSourceConfig;
+  } else if (req.find("GET /input") != wpi::StringRef::npos &&
+             req.find(".json") != wpi::StringRef::npos) {
+    kind = kGetSettings;
+  } else if (req.find("GET /output") != wpi::StringRef::npos &&
+             req.find(".json") != wpi::StringRef::npos) {
+    kind = kGetSettings;
+  } else if ((pos = req.find("GET /?action=command")) != wpi::StringRef::npos) {
+    kind = kCommand;
+    parameters = req.substr(req.find('&', pos + 20)).substr(1);
+  } else if (req.find("GET / ") != wpi::StringRef::npos || req == "GET /\n") {
+    kind = kRootPage;
+  } else {
+    SDEBUG("HTTP request resource not found");
+    SendError(os, 404, "Resource not found");
+    return;
+  }
+
+  // Parameter can only be certain characters.  This also strips the EOL.
+  pos = parameters.find_first_not_of(
+      "abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ_"
+      "-=&1234567890%./");
+  parameters = parameters.substr(0, pos);
+  SDEBUG("command parameters: \"" << parameters << "\"");
+
+  // Read the rest of the HTTP request.
+  // The end of the request is marked by a single, empty line
+  wpi::SmallString<128> lineBuf;
+  for (;;) {
+    if (is.getline(lineBuf, 4096).startswith("\n")) break;
+    if (is.has_error()) return;
+  }
+
+  // Send response
+  switch (kind) {
+    case kStream:
+      if (auto source = GetSource()) {
+        SDEBUG("request for stream " << source->GetName());
+        if (!ProcessCommand(os, *source, parameters, false)) return;
+      }
+      SendStream(os);
+      break;
+    case kCommand:
+      if (auto source = GetSource()) {
+        ProcessCommand(os, *source, parameters, true);
+      } else {
+        SendHeader(os, 200, "OK", "text/plain");
+        os << "Ignored due to no connected source."
+           << "\r\n";
+        SDEBUG("Ignored due to no connected source.");
+      }
+      break;
+    case kGetSettings:
+      SDEBUG("request for JSON file");
+      if (auto source = GetSource())
+        SendJSON(os, *source, true);
+      else
+        SendError(os, 404, "Resource not found");
+      break;
+    case kGetSourceConfig:
+      SDEBUG("request for JSON file");
+      if (auto source = GetSource()) {
+        SendHeader(os, 200, "OK", "application/json");
+        CS_Status status = CS_OK;
+        os << source->GetConfigJson(&status);
+        os.flush();
+      } else {
+        SendError(os, 404, "Resource not found");
+      }
+      break;
+    case kRootPage:
+      SDEBUG("request for root page");
+      SendHeader(os, 200, "OK", "text/html");
+      if (auto source = GetSource()) {
+        SendHTML(os, *source, false);
+      } else {
+        SendHTMLHeadTitle(os);
+        os << emptyRootPage << "\r\n";
+      }
+      break;
+  }
+
+  SDEBUG("leaving HTTP client thread");
+}
+
+// worker thread for clients that connected to this server
+void MjpegServerImpl::ConnThread::Main() {
+  std::unique_lock lock(m_mutex);
+  while (m_active) {
+    while (!m_stream) {
+      m_cond.wait(lock);
+      if (!m_active) return;
+    }
+    lock.unlock();
+    ProcessRequest();
+    lock.lock();
+    m_stream = nullptr;
+  }
+}
+
+// Main server thread
+void MjpegServerImpl::ServerThreadMain() {
+  if (m_acceptor->start() != 0) {
+    m_active = false;
+    return;
+  }
+
+  SDEBUG("waiting for clients to connect");
+  while (m_active) {
+    auto stream = m_acceptor->accept();
+    if (!stream) {
+      m_active = false;
+      return;
+    }
+    if (!m_active) return;
+
+    SDEBUG("client connection from " << stream->getPeerIP());
+
+    auto source = GetSource();
+
+    std::scoped_lock lock(m_mutex);
+    // Find unoccupied worker thread, or create one if necessary
+    auto it = std::find_if(m_connThreads.begin(), m_connThreads.end(),
+                           [](const wpi::SafeThreadOwner<ConnThread>& owner) {
+                             auto thr = owner.GetThread();
+                             return !thr || !thr->m_stream;
+                           });
+    if (it == m_connThreads.end()) {
+      m_connThreads.emplace_back();
+      it = std::prev(m_connThreads.end());
+    }
+
+    // Start it if not already started
+    it->Start(GetName(), m_logger);
+
+    auto nstreams =
+        std::count_if(m_connThreads.begin(), m_connThreads.end(),
+                      [](const wpi::SafeThreadOwner<ConnThread>& owner) {
+                        auto thr = owner.GetThread();
+                        return thr && thr->m_streaming;
+                      });
+
+    // Hand off connection to it
+    auto thr = it->GetThread();
+    thr->m_stream = std::move(stream);
+    thr->m_source = source;
+    thr->m_noStreaming = nstreams >= 10;
+    thr->m_width = GetProperty(m_widthProp)->value;
+    thr->m_height = GetProperty(m_heightProp)->value;
+    thr->m_compression = GetProperty(m_compressionProp)->value;
+    thr->m_defaultCompression = GetProperty(m_defaultCompressionProp)->value;
+    thr->m_fps = GetProperty(m_fpsProp)->value;
+    thr->m_cond.notify_one();
+  }
+
+  SDEBUG("leaving server thread");
+}
+
+void MjpegServerImpl::SetSourceImpl(std::shared_ptr<SourceImpl> source) {
+  std::scoped_lock lock(m_mutex);
+  for (auto& connThread : m_connThreads) {
+    if (auto thr = connThread.GetThread()) {
+      if (thr->m_source != source) {
+        bool streaming = thr->m_streaming;
+        if (thr->m_source && streaming) thr->m_source->DisableSink();
+        thr->m_source = source;
+        if (source && streaming) thr->m_source->EnableSink();
+      }
+    }
+  }
+}
+
+namespace cs {
+
+CS_Sink CreateMjpegServer(const wpi::Twine& name,
+                          const wpi::Twine& listenAddress, int port,
+                          CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  wpi::SmallString<128> listenAddressBuf;
+  return inst.CreateSink(
+      CS_SINK_MJPEG,
+      std::make_shared<MjpegServerImpl>(
+          name, inst.logger, inst.notifier, inst.telemetry, listenAddress, port,
+          std::unique_ptr<wpi::NetworkAcceptor>(new wpi::TCPAcceptor(
+              port,
+              listenAddress.toNullTerminatedStringRef(listenAddressBuf).data(),
+              inst.logger))));
+}
+
+std::string GetMjpegServerListenAddress(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_MJPEG) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return static_cast<MjpegServerImpl&>(*data->sink).GetListenAddress();
+}
+
+int GetMjpegServerPort(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_MJPEG) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return static_cast<MjpegServerImpl&>(*data->sink).GetPort();
+}
+
+}  // namespace cs
+
+extern "C" {
+
+CS_Sink CS_CreateMjpegServer(const char* name, const char* listenAddress,
+                             int port, CS_Status* status) {
+  return cs::CreateMjpegServer(name, listenAddress, port, status);
+}
+
+char* CS_GetMjpegServerListenAddress(CS_Sink sink, CS_Status* status) {
+  return ConvertToC(cs::GetMjpegServerListenAddress(sink, status));
+}
+
+int CS_GetMjpegServerPort(CS_Sink sink, CS_Status* status) {
+  return cs::GetMjpegServerPort(sink, status);
+}
+
+}  // extern "C"
diff --git a/cscore/src/main/native/cpp/MjpegServerImpl.h b/cscore/src/main/native/cpp/MjpegServerImpl.h
new file mode 100644
index 0000000..db60b86
--- /dev/null
+++ b/cscore/src/main/native/cpp/MjpegServerImpl.h
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_MJPEGSERVERIMPL_H_
+#define CSCORE_MJPEGSERVERIMPL_H_
+
+#include <atomic>
+#include <memory>
+#include <string>
+#include <thread>
+#include <vector>
+
+#include <wpi/NetworkAcceptor.h>
+#include <wpi/NetworkStream.h>
+#include <wpi/SafeThread.h>
+#include <wpi/SmallVector.h>
+#include <wpi/Twine.h>
+#include <wpi/raw_istream.h>
+#include <wpi/raw_ostream.h>
+#include <wpi/raw_socket_ostream.h>
+
+#include "SinkImpl.h"
+
+namespace cs {
+
+class SourceImpl;
+
+class MjpegServerImpl : public SinkImpl {
+ public:
+  MjpegServerImpl(const wpi::Twine& name, wpi::Logger& logger,
+                  Notifier& notifier, Telemetry& telemetry,
+                  const wpi::Twine& listenAddress, int port,
+                  std::unique_ptr<wpi::NetworkAcceptor> acceptor);
+  ~MjpegServerImpl() override;
+
+  void Stop();
+  std::string GetListenAddress() { return m_listenAddress; }
+  int GetPort() { return m_port; }
+
+ private:
+  void SetSourceImpl(std::shared_ptr<SourceImpl> source) override;
+
+  void ServerThreadMain();
+
+  class ConnThread;
+
+  // Never changed, so not protected by mutex
+  std::string m_listenAddress;
+  int m_port;
+
+  std::unique_ptr<wpi::NetworkAcceptor> m_acceptor;
+  std::atomic_bool m_active;  // set to false to terminate threads
+  std::thread m_serverThread;
+
+  std::vector<wpi::SafeThreadOwner<ConnThread>> m_connThreads;
+
+  // property indices
+  int m_widthProp;
+  int m_heightProp;
+  int m_compressionProp;
+  int m_defaultCompressionProp;
+  int m_fpsProp;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_MJPEGSERVERIMPL_H_
diff --git a/cscore/src/main/native/cpp/NetworkListener.h b/cscore/src/main/native/cpp/NetworkListener.h
new file mode 100644
index 0000000..6d49adc
--- /dev/null
+++ b/cscore/src/main/native/cpp/NetworkListener.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_NETWORKLISTENER_H_
+#define CSCORE_NETWORKLISTENER_H_
+
+#include <memory>
+
+#include <wpi/Logger.h>
+
+namespace cs {
+
+class Notifier;
+
+class NetworkListener {
+ public:
+  NetworkListener(wpi::Logger& logger, Notifier& notifier);
+  ~NetworkListener();
+
+  void Start();
+  void Stop();
+
+ private:
+  class Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_NETWORKLISTENER_H_
diff --git a/cscore/src/main/native/cpp/Notifier.cpp b/cscore/src/main/native/cpp/Notifier.cpp
new file mode 100644
index 0000000..e4645c9
--- /dev/null
+++ b/cscore/src/main/native/cpp/Notifier.cpp
@@ -0,0 +1,248 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "Notifier.h"
+
+#include <queue>
+#include <vector>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "SinkImpl.h"
+#include "SourceImpl.h"
+
+using namespace cs;
+
+bool Notifier::s_destroyed = false;
+
+namespace {
+// Vector which provides an integrated freelist for removal and reuse of
+// individual elements.
+template <typename T>
+class UidVector {
+ public:
+  using size_type = typename std::vector<T>::size_type;
+
+  size_type size() const { return m_vector.size(); }
+  T& operator[](size_type i) { return m_vector[i]; }
+  const T& operator[](size_type i) const { return m_vector[i]; }
+
+  // Add a new T to the vector.  If there are elements on the freelist,
+  // reuses the last one; otherwise adds to the end of the vector.
+  // Returns the resulting element index (+1).
+  template <class... Args>
+  unsigned int emplace_back(Args&&... args) {
+    unsigned int uid;
+    if (m_free.empty()) {
+      uid = m_vector.size();
+      m_vector.emplace_back(std::forward<Args>(args)...);
+    } else {
+      uid = m_free.back();
+      m_free.pop_back();
+      m_vector[uid] = T(std::forward<Args>(args)...);
+    }
+    return uid + 1;
+  }
+
+  // Removes the identified element by replacing it with a default-constructed
+  // one.  The element is added to the freelist for later reuse.
+  void erase(unsigned int uid) {
+    --uid;
+    if (uid >= m_vector.size() || !m_vector[uid]) return;
+    m_free.push_back(uid);
+    m_vector[uid] = T();
+  }
+
+ private:
+  std::vector<T> m_vector;
+  std::vector<unsigned int> m_free;
+};
+
+}  // namespace
+
+class Notifier::Thread : public wpi::SafeThread {
+ public:
+  Thread(std::function<void()> on_start, std::function<void()> on_exit)
+      : m_on_start(on_start), m_on_exit(on_exit) {}
+
+  void Main();
+
+  struct Listener {
+    Listener() = default;
+    Listener(std::function<void(const RawEvent& event)> callback_,
+             int eventMask_)
+        : callback(callback_), eventMask(eventMask_) {}
+
+    explicit operator bool() const { return static_cast<bool>(callback); }
+
+    std::string prefix;
+    std::function<void(const RawEvent& event)> callback;
+    int eventMask;
+  };
+  UidVector<Listener> m_listeners;
+
+  std::queue<RawEvent> m_notifications;
+
+  std::function<void()> m_on_start;
+  std::function<void()> m_on_exit;
+};
+
+Notifier::Notifier() { s_destroyed = false; }
+
+Notifier::~Notifier() { s_destroyed = true; }
+
+void Notifier::Start() { m_owner.Start(m_on_start, m_on_exit); }
+
+void Notifier::Stop() { m_owner.Stop(); }
+
+void Notifier::Thread::Main() {
+  if (m_on_start) m_on_start();
+
+  std::unique_lock lock(m_mutex);
+  while (m_active) {
+    while (m_notifications.empty()) {
+      m_cond.wait(lock);
+      if (!m_active) goto done;
+    }
+
+    while (!m_notifications.empty()) {
+      if (!m_active) goto done;
+      auto item = std::move(m_notifications.front());
+      m_notifications.pop();
+
+      // Use index because iterator might get invalidated.
+      for (size_t i = 0; i < m_listeners.size(); ++i) {
+        if (!m_listeners[i]) continue;  // removed
+
+        // Event type must be within requested set for this listener.
+        if ((item.kind & m_listeners[i].eventMask) == 0) continue;
+
+        // make a copy of the callback so we can safely release the mutex
+        auto callback = m_listeners[i].callback;
+
+        // Don't hold mutex during callback execution!
+        lock.unlock();
+        callback(item);
+        lock.lock();
+      }
+    }
+  }
+
+done:
+  if (m_on_exit) m_on_exit();
+}
+
+int Notifier::AddListener(std::function<void(const RawEvent& event)> callback,
+                          int eventMask) {
+  Start();
+  auto thr = m_owner.GetThread();
+  return thr->m_listeners.emplace_back(callback, eventMask);
+}
+
+void Notifier::RemoveListener(int uid) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+  thr->m_listeners.erase(uid);
+}
+
+void Notifier::NotifySource(const wpi::Twine& name, CS_Source source,
+                            CS_EventKind kind) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+  thr->m_notifications.emplace(name, source, static_cast<RawEvent::Kind>(kind));
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifySource(const SourceImpl& source, CS_EventKind kind) {
+  auto handleData = Instance::GetInstance().FindSource(source);
+  NotifySource(source.GetName(), handleData.first, kind);
+}
+
+void Notifier::NotifySourceVideoMode(const SourceImpl& source,
+                                     const VideoMode& mode) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  auto handleData = Instance::GetInstance().FindSource(source);
+
+  thr->m_notifications.emplace(source.GetName(), handleData.first, mode);
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifySourceProperty(const SourceImpl& source, CS_EventKind kind,
+                                    const wpi::Twine& propertyName,
+                                    int property, CS_PropertyKind propertyKind,
+                                    int value, const wpi::Twine& valueStr) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  auto handleData = Instance::GetInstance().FindSource(source);
+
+  thr->m_notifications.emplace(
+      propertyName, handleData.first, static_cast<RawEvent::Kind>(kind),
+      Handle{handleData.first, property, Handle::kProperty}, propertyKind,
+      value, valueStr);
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifySink(const wpi::Twine& name, CS_Sink sink,
+                          CS_EventKind kind) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  thr->m_notifications.emplace(name, sink, static_cast<RawEvent::Kind>(kind));
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifySink(const SinkImpl& sink, CS_EventKind kind) {
+  auto handleData = Instance::GetInstance().FindSink(sink);
+  NotifySink(sink.GetName(), handleData.first, kind);
+}
+
+void Notifier::NotifySinkSourceChanged(const wpi::Twine& name, CS_Sink sink,
+                                       CS_Source source) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  RawEvent event{name, sink, RawEvent::kSinkSourceChanged};
+  event.sourceHandle = source;
+
+  thr->m_notifications.emplace(std::move(event));
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifySinkProperty(const SinkImpl& sink, CS_EventKind kind,
+                                  const wpi::Twine& propertyName, int property,
+                                  CS_PropertyKind propertyKind, int value,
+                                  const wpi::Twine& valueStr) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  auto handleData = Instance::GetInstance().FindSink(sink);
+
+  thr->m_notifications.emplace(
+      propertyName, handleData.first, static_cast<RawEvent::Kind>(kind),
+      Handle{handleData.first, property, Handle::kSinkProperty}, propertyKind,
+      value, valueStr);
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifyNetworkInterfacesChanged() {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  thr->m_notifications.emplace(RawEvent::kNetworkInterfacesChanged);
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifyTelemetryUpdated() {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  thr->m_notifications.emplace(RawEvent::kTelemetryUpdated);
+  thr->m_cond.notify_one();
+}
diff --git a/cscore/src/main/native/cpp/Notifier.h b/cscore/src/main/native/cpp/Notifier.h
new file mode 100644
index 0000000..526cea8
--- /dev/null
+++ b/cscore/src/main/native/cpp/Notifier.h
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_NOTIFIER_H_
+#define CSCORE_NOTIFIER_H_
+
+#include <functional>
+
+#include <wpi/SafeThread.h>
+
+#include "cscore_cpp.h"
+
+namespace cs {
+
+class SinkImpl;
+class SourceImpl;
+
+class Notifier {
+  friend class NotifierTest;
+
+ public:
+  Notifier();
+  ~Notifier();
+
+  void Start();
+  void Stop();
+
+  static bool destroyed() { return s_destroyed; }
+
+  void SetOnStart(std::function<void()> on_start) { m_on_start = on_start; }
+  void SetOnExit(std::function<void()> on_exit) { m_on_exit = on_exit; }
+
+  int AddListener(std::function<void(const RawEvent& event)> callback,
+                  int eventMask);
+  void RemoveListener(int uid);
+
+  // Notification events
+  void NotifySource(const wpi::Twine& name, CS_Source source,
+                    CS_EventKind kind);
+  void NotifySource(const SourceImpl& source, CS_EventKind kind);
+  void NotifySourceVideoMode(const SourceImpl& source, const VideoMode& mode);
+  void NotifySourceProperty(const SourceImpl& source, CS_EventKind kind,
+                            const wpi::Twine& propertyName, int property,
+                            CS_PropertyKind propertyKind, int value,
+                            const wpi::Twine& valueStr);
+  void NotifySink(const wpi::Twine& name, CS_Sink sink, CS_EventKind kind);
+  void NotifySink(const SinkImpl& sink, CS_EventKind kind);
+  void NotifySinkSourceChanged(const wpi::Twine& name, CS_Sink sink,
+                               CS_Source source);
+  void NotifySinkProperty(const SinkImpl& sink, CS_EventKind kind,
+                          const wpi::Twine& propertyName, int property,
+                          CS_PropertyKind propertyKind, int value,
+                          const wpi::Twine& valueStr);
+  void NotifyNetworkInterfacesChanged();
+  void NotifyTelemetryUpdated();
+
+ private:
+  class Thread;
+  wpi::SafeThreadOwner<Thread> m_owner;
+
+  std::function<void()> m_on_start;
+  std::function<void()> m_on_exit;
+  static bool s_destroyed;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_NOTIFIER_H_
diff --git a/cscore/src/main/native/cpp/PropertyContainer.cpp b/cscore/src/main/native/cpp/PropertyContainer.cpp
new file mode 100644
index 0000000..17bf94b
--- /dev/null
+++ b/cscore/src/main/native/cpp/PropertyContainer.cpp
@@ -0,0 +1,282 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "PropertyContainer.h"
+
+#include <wpi/Logger.h>
+#include <wpi/SmallString.h>
+#include <wpi/SmallVector.h>
+#include <wpi/json.h>
+
+using namespace cs;
+
+int PropertyContainer::GetPropertyIndex(const wpi::Twine& name) const {
+  // We can't fail, so instead we create a new index if caching fails.
+  CS_Status status = 0;
+  if (!m_properties_cached) CacheProperties(&status);
+  std::scoped_lock lock(m_mutex);
+  wpi::SmallVector<char, 64> nameBuf;
+  int& ndx = m_properties[name.toStringRef(nameBuf)];
+  if (ndx == 0) {
+    // create a new index
+    ndx = m_propertyData.size() + 1;
+    m_propertyData.emplace_back(CreateEmptyProperty(name));
+  }
+  return ndx;
+}
+
+wpi::ArrayRef<int> PropertyContainer::EnumerateProperties(
+    wpi::SmallVectorImpl<int>& vec, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status))
+    return wpi::ArrayRef<int>{};
+  std::scoped_lock lock(m_mutex);
+  for (int i = 0; i < static_cast<int>(m_propertyData.size()); ++i) {
+    if (m_propertyData[i]) vec.push_back(i + 1);
+  }
+  return vec;
+}
+
+CS_PropertyKind PropertyContainer::GetPropertyKind(int property) const {
+  CS_Status status = 0;
+  if (!m_properties_cached && !CacheProperties(&status)) return CS_PROP_NONE;
+  std::scoped_lock lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) return CS_PROP_NONE;
+  return prop->propKind;
+}
+
+wpi::StringRef PropertyContainer::GetPropertyName(
+    int property, wpi::SmallVectorImpl<char>& buf, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return wpi::StringRef{};
+  std::scoped_lock lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return wpi::StringRef{};
+  }
+  // safe to not copy because we never modify it after caching
+  return prop->name;
+}
+
+int PropertyContainer::GetProperty(int property, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return 0;
+  std::scoped_lock lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return 0;
+  }
+  if ((prop->propKind & (CS_PROP_BOOLEAN | CS_PROP_INTEGER | CS_PROP_ENUM)) ==
+      0) {
+    *status = CS_WRONG_PROPERTY_TYPE;
+    return 0;
+  }
+  return prop->value;
+}
+
+void PropertyContainer::SetProperty(int property, int value,
+                                    CS_Status* status) {
+  std::scoped_lock lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return;
+  }
+
+  // Guess it's integer if we've set before get
+  if (prop->propKind == CS_PROP_NONE) prop->propKind = CS_PROP_INTEGER;
+
+  if ((prop->propKind & (CS_PROP_BOOLEAN | CS_PROP_INTEGER | CS_PROP_ENUM)) ==
+      0) {
+    *status = CS_WRONG_PROPERTY_TYPE;
+    return;
+  }
+
+  UpdatePropertyValue(property, false, value, wpi::Twine{});
+}
+
+int PropertyContainer::GetPropertyMin(int property, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return 0;
+  std::scoped_lock lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return 0;
+  }
+  return prop->minimum;
+}
+
+int PropertyContainer::GetPropertyMax(int property, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return 0;
+  std::scoped_lock lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return 0;
+  }
+  return prop->maximum;
+}
+
+int PropertyContainer::GetPropertyStep(int property, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return 0;
+  std::scoped_lock lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return 0;
+  }
+  return prop->step;
+}
+
+int PropertyContainer::GetPropertyDefault(int property,
+                                          CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return 0;
+  std::scoped_lock lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return 0;
+  }
+  return prop->defaultValue;
+}
+
+wpi::StringRef PropertyContainer::GetStringProperty(
+    int property, wpi::SmallVectorImpl<char>& buf, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return wpi::StringRef{};
+  std::scoped_lock lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return wpi::StringRef{};
+  }
+  if (prop->propKind != CS_PROP_STRING) {
+    *status = CS_WRONG_PROPERTY_TYPE;
+    return wpi::StringRef{};
+  }
+  buf.clear();
+  buf.append(prop->valueStr.begin(), prop->valueStr.end());
+  return wpi::StringRef(buf.data(), buf.size());
+}
+
+void PropertyContainer::SetStringProperty(int property, const wpi::Twine& value,
+                                          CS_Status* status) {
+  std::scoped_lock lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return;
+  }
+
+  // Guess it's string if we've set before get
+  if (prop->propKind == CS_PROP_NONE) prop->propKind = CS_PROP_STRING;
+
+  if (prop->propKind != CS_PROP_STRING) {
+    *status = CS_WRONG_PROPERTY_TYPE;
+    return;
+  }
+
+  UpdatePropertyValue(property, true, 0, value);
+}
+
+std::vector<std::string> PropertyContainer::GetEnumPropertyChoices(
+    int property, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status))
+    return std::vector<std::string>{};
+  std::scoped_lock lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return std::vector<std::string>{};
+  }
+  if (prop->propKind != CS_PROP_ENUM) {
+    *status = CS_WRONG_PROPERTY_TYPE;
+    return std::vector<std::string>{};
+  }
+  return prop->enumChoices;
+}
+
+std::unique_ptr<PropertyImpl> PropertyContainer::CreateEmptyProperty(
+    const wpi::Twine& name) const {
+  return std::make_unique<PropertyImpl>(name);
+}
+
+bool PropertyContainer::CacheProperties(CS_Status* status) const {
+  // Doesn't need to do anything.
+  m_properties_cached = true;
+  return true;
+}
+
+bool PropertyContainer::SetPropertiesJson(const wpi::json& config,
+                                          wpi::Logger& logger,
+                                          wpi::StringRef logName,
+                                          CS_Status* status) {
+  for (auto&& prop : config) {
+    std::string name;
+    try {
+      name = prop.at("name").get<std::string>();
+    } catch (const wpi::json::exception& e) {
+      WPI_WARNING(logger,
+                  logName << ": SetConfigJson: could not read property name: "
+                          << e.what());
+      continue;
+    }
+    int n = GetPropertyIndex(name);
+    try {
+      auto& v = prop.at("value");
+      if (v.is_string()) {
+        std::string val = v.get<std::string>();
+        WPI_INFO(logger, logName << ": SetConfigJson: setting property '"
+                                 << name << "' to '" << val << '\'');
+        SetStringProperty(n, val, status);
+      } else if (v.is_boolean()) {
+        bool val = v.get<bool>();
+        WPI_INFO(logger, logName << ": SetConfigJson: setting property '"
+                                 << name << "' to " << val);
+        SetProperty(n, val, status);
+      } else {
+        int val = v.get<int>();
+        WPI_INFO(logger, logName << ": SetConfigJson: setting property '"
+                                 << name << "' to " << val);
+        SetProperty(n, val, status);
+      }
+    } catch (const wpi::json::exception& e) {
+      WPI_WARNING(logger,
+                  logName << ": SetConfigJson: could not read property value: "
+                          << e.what());
+      continue;
+    }
+  }
+
+  return true;
+}
+
+wpi::json PropertyContainer::GetPropertiesJsonObject(CS_Status* status) {
+  wpi::json j;
+  wpi::SmallVector<int, 32> propVec;
+  for (int p : EnumerateProperties(propVec, status)) {
+    wpi::json prop;
+    wpi::SmallString<128> strBuf;
+    prop.emplace("name", GetPropertyName(p, strBuf, status));
+    switch (GetPropertyKind(p)) {
+      case CS_PROP_BOOLEAN:
+        prop.emplace("value", static_cast<bool>(GetProperty(p, status)));
+        break;
+      case CS_PROP_INTEGER:
+      case CS_PROP_ENUM:
+        prop.emplace("value", GetProperty(p, status));
+        break;
+      case CS_PROP_STRING:
+        prop.emplace("value", GetStringProperty(p, strBuf, status));
+        break;
+      default:
+        continue;
+    }
+    j.emplace_back(prop);
+  }
+
+  return j;
+}
diff --git a/cscore/src/main/native/cpp/PropertyContainer.h b/cscore/src/main/native/cpp/PropertyContainer.h
new file mode 100644
index 0000000..9bbb9c7
--- /dev/null
+++ b/cscore/src/main/native/cpp/PropertyContainer.h
@@ -0,0 +1,128 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_PROPERTYCONTAINER_H_
+#define CSCORE_PROPERTYCONTAINER_H_
+
+#include <atomic>
+#include <cstddef>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringMap.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/mutex.h>
+
+#include "PropertyImpl.h"
+#include "cscore_cpp.h"
+
+namespace wpi {
+class Logger;
+class json;
+}  // namespace wpi
+
+namespace cs {
+
+class PropertyContainer {
+ public:
+  virtual ~PropertyContainer() = default;
+
+  int GetPropertyIndex(const wpi::Twine& name) const;
+  wpi::ArrayRef<int> EnumerateProperties(wpi::SmallVectorImpl<int>& vec,
+                                         CS_Status* status) const;
+  CS_PropertyKind GetPropertyKind(int property) const;
+  wpi::StringRef GetPropertyName(int property, wpi::SmallVectorImpl<char>& buf,
+                                 CS_Status* status) const;
+  int GetProperty(int property, CS_Status* status) const;
+  virtual void SetProperty(int property, int value, CS_Status* status);
+  int GetPropertyMin(int property, CS_Status* status) const;
+  int GetPropertyMax(int property, CS_Status* status) const;
+  int GetPropertyStep(int property, CS_Status* status) const;
+  int GetPropertyDefault(int property, CS_Status* status) const;
+  wpi::StringRef GetStringProperty(int property,
+                                   wpi::SmallVectorImpl<char>& buf,
+                                   CS_Status* status) const;
+  virtual void SetStringProperty(int property, const wpi::Twine& value,
+                                 CS_Status* status);
+  std::vector<std::string> GetEnumPropertyChoices(int property,
+                                                  CS_Status* status) const;
+
+  bool SetPropertiesJson(const wpi::json& config, wpi::Logger& logger,
+                         wpi::StringRef logName, CS_Status* status);
+  wpi::json GetPropertiesJsonObject(CS_Status* status);
+
+ protected:
+  // Get a property; must be called with m_mutex held.
+  PropertyImpl* GetProperty(int property) {
+    if (property <= 0 || static_cast<size_t>(property) > m_propertyData.size())
+      return nullptr;
+    return m_propertyData[property - 1].get();
+  }
+  const PropertyImpl* GetProperty(int property) const {
+    if (property <= 0 || static_cast<size_t>(property) > m_propertyData.size())
+      return nullptr;
+    return m_propertyData[property - 1].get();
+  }
+  // Create or update a property; must be called with m_mutex held.
+  // @tparam NewFunc functor that returns a std::unique_ptr<PropertyImpl>
+  // @tparam UpdateFunc functor that takes a PropertyImpl&.
+  template <typename NewFunc, typename UpdateFunc>
+  int CreateOrUpdateProperty(const wpi::Twine& name, NewFunc newFunc,
+                             UpdateFunc updateFunc) {
+    wpi::SmallVector<char, 64> nameBuf;
+    int& ndx = m_properties[name.toStringRef(nameBuf)];
+    if (ndx == 0) {
+      // create a new index
+      ndx = m_propertyData.size() + 1;
+      m_propertyData.emplace_back(newFunc());
+    } else {
+      // update existing
+      updateFunc(*GetProperty(ndx));
+    }
+    return ndx;
+  }
+  template <typename NewFunc>
+  int CreateProperty(const wpi::Twine& name, NewFunc newFunc) {
+    return CreateOrUpdateProperty(name, newFunc, [](PropertyImpl&) {});
+  }
+
+  // Create an "empty" property.  This is called by GetPropertyIndex to create
+  // properties that don't exist (as GetPropertyIndex can't fail).
+  // Note: called with m_mutex held.
+  // The default implementation simply creates a PropertyImpl object.
+  virtual std::unique_ptr<PropertyImpl> CreateEmptyProperty(
+      const wpi::Twine& name) const;
+
+  // Cache properties.  Implementations must return false and set status to
+  // CS_SOURCE_IS_DISCONNECTED if not possible to cache.
+  // The default implementation simply sets m_property_cached to true.
+  virtual bool CacheProperties(CS_Status* status) const;
+
+  virtual void NotifyPropertyCreated(int propIndex, PropertyImpl& prop) = 0;
+
+  // Update property value; must be called with m_mutex held.
+  virtual void UpdatePropertyValue(int property, bool setString, int value,
+                                   const wpi::Twine& valueStr) = 0;
+
+  // Whether CacheProperties() has been successful at least once (and thus
+  // should not be called again)
+  mutable std::atomic_bool m_properties_cached{false};
+
+  mutable wpi::mutex m_mutex;
+
+  // Cached properties (protected with m_mutex)
+  mutable std::vector<std::unique_ptr<PropertyImpl>> m_propertyData;
+  mutable wpi::StringMap<int> m_properties;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_PROPERTYCONTAINER_H_
diff --git a/cscore/src/main/native/cpp/PropertyImpl.cpp b/cscore/src/main/native/cpp/PropertyImpl.cpp
new file mode 100644
index 0000000..4f1602e
--- /dev/null
+++ b/cscore/src/main/native/cpp/PropertyImpl.cpp
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "PropertyImpl.h"
+
+using namespace cs;
+
+PropertyImpl::PropertyImpl(const wpi::Twine& name_) : name{name_.str()} {}
+PropertyImpl::PropertyImpl(const wpi::Twine& name_, CS_PropertyKind kind_,
+                           int step_, int defaultValue_, int value_)
+    : name{name_.str()},
+      propKind{kind_},
+      step{step_},
+      defaultValue{defaultValue_},
+      value{value_} {}
+PropertyImpl::PropertyImpl(const wpi::Twine& name_, CS_PropertyKind kind_,
+                           int minimum_, int maximum_, int step_,
+                           int defaultValue_, int value_)
+    : name{name_.str()},
+      propKind{kind_},
+      hasMinimum{true},
+      hasMaximum{true},
+      minimum{minimum_},
+      maximum{maximum_},
+      step{step_},
+      defaultValue{defaultValue_},
+      value{value_} {}
+
+void PropertyImpl::SetValue(int v) {
+  int oldValue = value;
+  if (hasMinimum && v < minimum)
+    value = minimum;
+  else if (hasMaximum && v > maximum)
+    value = maximum;
+  else
+    value = v;
+  bool wasValueSet = valueSet;
+  valueSet = true;
+  if (!wasValueSet || value != oldValue) changed();
+}
+
+void PropertyImpl::SetValue(const wpi::Twine& v) {
+  bool valueChanged = false;
+  std::string vStr = v.str();
+  if (valueStr != vStr) {
+    valueStr = vStr;
+    valueChanged = true;
+  }
+  bool wasValueSet = valueSet;
+  valueSet = true;
+  if (!wasValueSet || valueChanged) changed();
+}
+
+void PropertyImpl::SetDefaultValue(int v) {
+  if (hasMinimum && v < minimum)
+    defaultValue = minimum;
+  else if (hasMaximum && v > maximum)
+    defaultValue = maximum;
+  else
+    defaultValue = v;
+}
diff --git a/cscore/src/main/native/cpp/PropertyImpl.h b/cscore/src/main/native/cpp/PropertyImpl.h
new file mode 100644
index 0000000..d932132
--- /dev/null
+++ b/cscore/src/main/native/cpp/PropertyImpl.h
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_PROPERTYIMPL_H_
+#define CSCORE_PROPERTYIMPL_H_
+
+#include <string>
+#include <vector>
+
+#include <wpi/Signal.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+
+#include "cscore_c.h"
+
+namespace cs {
+
+// Property data
+class PropertyImpl {
+ public:
+  PropertyImpl() = default;
+  explicit PropertyImpl(const wpi::Twine& name_);
+  PropertyImpl(const wpi::Twine& name_, CS_PropertyKind kind_, int step_,
+               int defaultValue_, int value_);
+  PropertyImpl(const wpi::Twine& name_, CS_PropertyKind kind_, int minimum_,
+               int maximum_, int step_, int defaultValue_, int value_);
+  virtual ~PropertyImpl() = default;
+  PropertyImpl(const PropertyImpl& oth) = delete;
+  PropertyImpl& operator=(const PropertyImpl& oth) = delete;
+
+  void SetValue(int v);
+  void SetValue(const wpi::Twine& v);
+  void SetDefaultValue(int v);
+
+  std::string name;
+  CS_PropertyKind propKind{CS_PROP_NONE};
+  bool hasMinimum{false};
+  bool hasMaximum{false};
+  int minimum{0};
+  int maximum{100};
+  int step{1};
+  int defaultValue{0};
+  int value{0};
+  std::string valueStr;
+  std::vector<std::string> enumChoices;
+  bool valueSet{false};
+
+  // emitted when value changes
+  wpi::sig::Signal<> changed;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_PROPERTYIMPL_H_
diff --git a/cscore/src/main/native/cpp/RawSinkImpl.cpp b/cscore/src/main/native/cpp/RawSinkImpl.cpp
new file mode 100644
index 0000000..986378f
--- /dev/null
+++ b/cscore/src/main/native/cpp/RawSinkImpl.cpp
@@ -0,0 +1,199 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "RawSinkImpl.h"
+
+#include "Instance.h"
+#include "cscore.h"
+#include "cscore_raw.h"
+
+using namespace cs;
+
+RawSinkImpl::RawSinkImpl(const wpi::Twine& name, wpi::Logger& logger,
+                         Notifier& notifier, Telemetry& telemetry)
+    : SinkImpl{name, logger, notifier, telemetry} {
+  m_active = true;
+  // m_thread = std::thread(&RawSinkImpl::ThreadMain, this);
+}
+
+RawSinkImpl::RawSinkImpl(const wpi::Twine& name, wpi::Logger& logger,
+                         Notifier& notifier, Telemetry& telemetry,
+                         std::function<void(uint64_t time)> processFrame)
+    : SinkImpl{name, logger, notifier, telemetry} {}
+
+RawSinkImpl::~RawSinkImpl() { Stop(); }
+
+void RawSinkImpl::Stop() {
+  m_active = false;
+
+  // wake up any waiters by forcing an empty frame to be sent
+  if (auto source = GetSource()) source->Wakeup();
+
+  // join thread
+  if (m_thread.joinable()) m_thread.join();
+}
+
+uint64_t RawSinkImpl::GrabFrame(CS_RawFrame& image) {
+  SetEnabled(true);
+
+  auto source = GetSource();
+  if (!source) {
+    // Source disconnected; sleep for one second
+    std::this_thread::sleep_for(std::chrono::seconds(1));
+    return 0;
+  }
+
+  auto frame = source->GetNextFrame();  // blocks
+  if (!frame) {
+    // Bad frame; sleep for 20 ms so we don't consume all processor time.
+    std::this_thread::sleep_for(std::chrono::milliseconds(20));
+    return 0;  // signal error
+  }
+
+  return GrabFrameImpl(image, frame);
+}
+
+uint64_t RawSinkImpl::GrabFrame(CS_RawFrame& image, double timeout) {
+  SetEnabled(true);
+
+  auto source = GetSource();
+  if (!source) {
+    // Source disconnected; sleep for one second
+    std::this_thread::sleep_for(std::chrono::seconds(1));
+    return 0;
+  }
+
+  auto frame = source->GetNextFrame(timeout);  // blocks
+  if (!frame) {
+    // Bad frame; sleep for 20 ms so we don't consume all processor time.
+    std::this_thread::sleep_for(std::chrono::milliseconds(20));
+    return 0;  // signal error
+  }
+
+  return GrabFrameImpl(image, frame);
+}
+
+uint64_t RawSinkImpl::GrabFrameImpl(CS_RawFrame& rawFrame,
+                                    Frame& incomingFrame) {
+  Image* newImage = nullptr;
+
+  if (rawFrame.pixelFormat == CS_PixelFormat::CS_PIXFMT_UNKNOWN) {
+    // Always get incoming image directly on unknown
+    newImage = incomingFrame.GetExistingImage(0);
+  } else {
+    // Format is known, ask for it
+    auto width = rawFrame.width;
+    auto height = rawFrame.height;
+    auto pixelFormat =
+        static_cast<VideoMode::PixelFormat>(rawFrame.pixelFormat);
+    if (width <= 0 || height <= 0) {
+      width = incomingFrame.GetOriginalWidth();
+      height = incomingFrame.GetOriginalHeight();
+    }
+    newImage = incomingFrame.GetImage(width, height, pixelFormat);
+  }
+
+  if (!newImage) {
+    // Shouldn't happen, but just in case...
+    std::this_thread::sleep_for(std::chrono::milliseconds(20));
+    return 0;
+  }
+
+  CS_AllocateRawFrameData(&rawFrame, newImage->size());
+  rawFrame.height = newImage->height;
+  rawFrame.width = newImage->width;
+  rawFrame.pixelFormat = newImage->pixelFormat;
+  rawFrame.totalData = newImage->size();
+  std::copy(newImage->data(), newImage->data() + rawFrame.totalData,
+            rawFrame.data);
+
+  return incomingFrame.GetTime();
+}
+
+// Send HTTP response and a stream of JPG-frames
+void RawSinkImpl::ThreadMain() {
+  Enable();
+  while (m_active) {
+    auto source = GetSource();
+    if (!source) {
+      // Source disconnected; sleep for one second
+      std::this_thread::sleep_for(std::chrono::seconds(1));
+      continue;
+    }
+    SDEBUG4("waiting for frame");
+    Frame frame = source->GetNextFrame();  // blocks
+    if (!m_active) break;
+    if (!frame) {
+      // Bad frame; sleep for 10 ms so we don't consume all processor time.
+      std::this_thread::sleep_for(std::chrono::milliseconds(10));
+      continue;
+    }
+    // TODO m_processFrame();
+  }
+  Disable();
+}
+
+namespace cs {
+CS_Sink CreateRawSink(const wpi::Twine& name, CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  return inst.CreateSink(CS_SINK_RAW,
+                         std::make_shared<RawSinkImpl>(
+                             name, inst.logger, inst.notifier, inst.telemetry));
+}
+
+CS_Sink CreateRawSinkCallback(const wpi::Twine& name,
+                              std::function<void(uint64_t time)> processFrame,
+                              CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  return inst.CreateSink(CS_SINK_RAW, std::make_shared<RawSinkImpl>(
+                                          name, inst.logger, inst.notifier,
+                                          inst.telemetry, processFrame));
+}
+
+uint64_t GrabSinkFrame(CS_Sink sink, CS_RawFrame& image, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_RAW) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return static_cast<RawSinkImpl&>(*data->sink).GrabFrame(image);
+}
+
+uint64_t GrabSinkFrameTimeout(CS_Sink sink, CS_RawFrame& image, double timeout,
+                              CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_RAW) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return static_cast<RawSinkImpl&>(*data->sink).GrabFrame(image, timeout);
+}
+}  // namespace cs
+
+extern "C" {
+CS_Sink CS_CreateRawSink(const char* name, CS_Status* status) {
+  return cs::CreateRawSink(name, status);
+}
+
+CS_Sink CS_CreateRawSinkCallback(const char* name, void* data,
+                                 void (*processFrame)(void* data,
+                                                      uint64_t time),
+                                 CS_Status* status) {
+  return cs::CreateRawSinkCallback(
+      name, [=](uint64_t time) { processFrame(data, time); }, status);
+}
+
+uint64_t CS_GrabRawSinkFrame(CS_Sink sink, struct CS_RawFrame* image,
+                             CS_Status* status) {
+  return cs::GrabSinkFrame(sink, *image, status);
+}
+
+uint64_t CS_GrabRawSinkFrameTimeout(CS_Sink sink, struct CS_RawFrame* image,
+                                    double timeout, CS_Status* status) {
+  return cs::GrabSinkFrameTimeout(sink, *image, timeout, status);
+}
+}  // extern "C"
diff --git a/cscore/src/main/native/cpp/RawSinkImpl.h b/cscore/src/main/native/cpp/RawSinkImpl.h
new file mode 100644
index 0000000..3e69485
--- /dev/null
+++ b/cscore/src/main/native/cpp/RawSinkImpl.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_RAWSINKIMPL_H_
+#define CSCORE_RAWSINKIMPL_H_
+
+#include <stdint.h>
+
+#include <atomic>
+#include <functional>
+#include <thread>
+
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+
+#include "Frame.h"
+#include "SinkImpl.h"
+#include "cscore_raw.h"
+
+namespace cs {
+class SourceImpl;
+
+class RawSinkImpl : public SinkImpl {
+ public:
+  RawSinkImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+              Telemetry& telemetry);
+  RawSinkImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+              Telemetry& telemetry,
+              std::function<void(uint64_t time)> processFrame);
+  ~RawSinkImpl() override;
+
+  void Stop();
+
+  uint64_t GrabFrame(CS_RawFrame& frame);
+  uint64_t GrabFrame(CS_RawFrame& frame, double timeout);
+
+ private:
+  void ThreadMain();
+
+  uint64_t GrabFrameImpl(CS_RawFrame& rawFrame, Frame& incomingFrame);
+
+  std::atomic_bool m_active;  // set to false to terminate threads
+  std::thread m_thread;
+  std::function<void(uint64_t time)> m_processFrame;
+};
+}  // namespace cs
+
+#endif  // CSCORE_RAWSINKIMPL_H_
diff --git a/cscore/src/main/native/cpp/RawSourceImpl.cpp b/cscore/src/main/native/cpp/RawSourceImpl.cpp
new file mode 100644
index 0000000..e0dba2d
--- /dev/null
+++ b/cscore/src/main/native/cpp/RawSourceImpl.cpp
@@ -0,0 +1,83 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "RawSourceImpl.h"
+
+#include <wpi/timestamp.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "cscore_raw.h"
+
+using namespace cs;
+
+RawSourceImpl::RawSourceImpl(const wpi::Twine& name, wpi::Logger& logger,
+                             Notifier& notifier, Telemetry& telemetry,
+                             const VideoMode& mode)
+    : ConfigurableSourceImpl{name, logger, notifier, telemetry, mode} {}
+
+RawSourceImpl::~RawSourceImpl() {}
+
+void RawSourceImpl::PutFrame(const CS_RawFrame& image) {
+  int type;
+  switch (image.pixelFormat) {
+    case VideoMode::kYUYV:
+    case VideoMode::kRGB565:
+      type = CV_8UC2;
+      break;
+    case VideoMode::kBGR:
+      type = CV_8UC3;
+      break;
+    case VideoMode::kGray:
+    case VideoMode::kMJPEG:
+    default:
+      type = CV_8UC1;
+      break;
+  }
+  cv::Mat finalImage{image.height, image.width, type, image.data};
+  std::unique_ptr<Image> dest =
+      AllocImage(static_cast<VideoMode::PixelFormat>(image.pixelFormat),
+                 image.width, image.height, image.totalData);
+  finalImage.copyTo(dest->AsMat());
+
+  SourceImpl::PutFrame(std::move(dest), wpi::Now());
+}
+
+namespace cs {
+CS_Source CreateRawSource(const wpi::Twine& name, const VideoMode& mode,
+                          CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  return inst.CreateSource(CS_SOURCE_RAW, std::make_shared<RawSourceImpl>(
+                                              name, inst.logger, inst.notifier,
+                                              inst.telemetry, mode));
+}
+
+void PutSourceFrame(CS_Source source, const CS_RawFrame& image,
+                    CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_RAW) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<RawSourceImpl&>(*data->source).PutFrame(image);
+}
+}  // namespace cs
+
+extern "C" {
+CS_Source CS_CreateRawSource(const char* name, const CS_VideoMode* mode,
+                             CS_Status* status) {
+  return cs::CreateRawSource(name, static_cast<const cs::VideoMode&>(*mode),
+                             status);
+}
+
+void CS_PutRawSourceFrame(CS_Source source, const struct CS_RawFrame* image,
+                          CS_Status* status) {
+  return cs::PutSourceFrame(source, *image, status);
+}
+}  // extern "C"
diff --git a/cscore/src/main/native/cpp/RawSourceImpl.h b/cscore/src/main/native/cpp/RawSourceImpl.h
new file mode 100644
index 0000000..1fdc749
--- /dev/null
+++ b/cscore/src/main/native/cpp/RawSourceImpl.h
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_RAWSOURCEIMPL_H_
+#define CSCORE_RAWSOURCEIMPL_H_
+
+#include <atomic>
+#include <functional>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/Twine.h>
+
+#include "ConfigurableSourceImpl.h"
+#include "SourceImpl.h"
+#include "cscore_raw.h"
+
+namespace cs {
+
+class RawSourceImpl : public ConfigurableSourceImpl {
+ public:
+  RawSourceImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+                Telemetry& telemetry, const VideoMode& mode);
+  ~RawSourceImpl() override;
+
+  // Raw-specific functions
+  void PutFrame(const CS_RawFrame& image);
+
+ private:
+  std::atomic_bool m_connected{true};
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_RAWSOURCEIMPL_H_
diff --git a/cscore/src/main/native/cpp/SinkImpl.cpp b/cscore/src/main/native/cpp/SinkImpl.cpp
new file mode 100644
index 0000000..5d4235a
--- /dev/null
+++ b/cscore/src/main/native/cpp/SinkImpl.cpp
@@ -0,0 +1,173 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "SinkImpl.h"
+
+#include <wpi/json.h>
+
+#include "Instance.h"
+#include "Notifier.h"
+#include "SourceImpl.h"
+
+using namespace cs;
+
+SinkImpl::SinkImpl(const wpi::Twine& name, wpi::Logger& logger,
+                   Notifier& notifier, Telemetry& telemetry)
+    : m_logger(logger),
+      m_notifier(notifier),
+      m_telemetry(telemetry),
+      m_name{name.str()} {}
+
+SinkImpl::~SinkImpl() {
+  if (m_source) {
+    if (m_enabledCount > 0) m_source->DisableSink();
+    m_source->RemoveSink();
+  }
+}
+
+void SinkImpl::SetDescription(const wpi::Twine& description) {
+  std::scoped_lock lock(m_mutex);
+  m_description = description.str();
+}
+
+wpi::StringRef SinkImpl::GetDescription(wpi::SmallVectorImpl<char>& buf) const {
+  std::scoped_lock lock(m_mutex);
+  buf.append(m_description.begin(), m_description.end());
+  return wpi::StringRef{buf.data(), buf.size()};
+}
+
+void SinkImpl::Enable() {
+  std::scoped_lock lock(m_mutex);
+  ++m_enabledCount;
+  if (m_enabledCount == 1) {
+    if (m_source) m_source->EnableSink();
+    m_notifier.NotifySink(*this, CS_SINK_ENABLED);
+  }
+}
+
+void SinkImpl::Disable() {
+  std::scoped_lock lock(m_mutex);
+  --m_enabledCount;
+  if (m_enabledCount == 0) {
+    if (m_source) m_source->DisableSink();
+    m_notifier.NotifySink(*this, CS_SINK_DISABLED);
+  }
+}
+
+void SinkImpl::SetEnabled(bool enabled) {
+  std::scoped_lock lock(m_mutex);
+  if (enabled && m_enabledCount == 0) {
+    if (m_source) m_source->EnableSink();
+    m_enabledCount = 1;
+    m_notifier.NotifySink(*this, CS_SINK_ENABLED);
+  } else if (!enabled && m_enabledCount > 0) {
+    if (m_source) m_source->DisableSink();
+    m_enabledCount = 0;
+    m_notifier.NotifySink(*this, CS_SINK_DISABLED);
+  }
+}
+
+void SinkImpl::SetSource(std::shared_ptr<SourceImpl> source) {
+  {
+    std::scoped_lock lock(m_mutex);
+    if (m_source == source) return;
+    if (m_source) {
+      if (m_enabledCount > 0) m_source->DisableSink();
+      m_source->RemoveSink();
+    }
+    m_source = source;
+    if (m_source) {
+      m_source->AddSink();
+      if (m_enabledCount > 0) m_source->EnableSink();
+    }
+  }
+  SetSourceImpl(source);
+}
+
+std::string SinkImpl::GetError() const {
+  std::scoped_lock lock(m_mutex);
+  if (!m_source) return "no source connected";
+  return m_source->GetCurFrame().GetError();
+}
+
+wpi::StringRef SinkImpl::GetError(wpi::SmallVectorImpl<char>& buf) const {
+  std::scoped_lock lock(m_mutex);
+  if (!m_source) return "no source connected";
+  // Make a copy as it's shared data
+  wpi::StringRef error = m_source->GetCurFrame().GetError();
+  buf.clear();
+  buf.append(error.data(), error.data() + error.size());
+  return wpi::StringRef{buf.data(), buf.size()};
+}
+
+bool SinkImpl::SetConfigJson(wpi::StringRef config, CS_Status* status) {
+  wpi::json j;
+  try {
+    j = wpi::json::parse(config);
+  } catch (const wpi::json::parse_error& e) {
+    SWARNING("SetConfigJson: parse error at byte " << e.byte << ": "
+                                                   << e.what());
+    *status = CS_PROPERTY_WRITE_FAILED;
+    return false;
+  }
+  return SetConfigJson(j, status);
+}
+
+bool SinkImpl::SetConfigJson(const wpi::json& config, CS_Status* status) {
+  if (config.count("properties") != 0)
+    SetPropertiesJson(config.at("properties"), m_logger, GetName(), status);
+
+  return true;
+}
+
+std::string SinkImpl::GetConfigJson(CS_Status* status) {
+  std::string rv;
+  wpi::raw_string_ostream os(rv);
+  GetConfigJsonObject(status).dump(os, 4);
+  os.flush();
+  return rv;
+}
+
+wpi::json SinkImpl::GetConfigJsonObject(CS_Status* status) {
+  wpi::json j;
+
+  wpi::json props = GetPropertiesJsonObject(status);
+  if (props.is_array()) j.emplace("properties", props);
+
+  return j;
+}
+
+void SinkImpl::NotifyPropertyCreated(int propIndex, PropertyImpl& prop) {
+  m_notifier.NotifySinkProperty(*this, CS_SINK_PROPERTY_CREATED, prop.name,
+                                propIndex, prop.propKind, prop.value,
+                                prop.valueStr);
+  // also notify choices updated event for enum types
+  if (prop.propKind == CS_PROP_ENUM)
+    m_notifier.NotifySinkProperty(*this, CS_SINK_PROPERTY_CHOICES_UPDATED,
+                                  prop.name, propIndex, prop.propKind,
+                                  prop.value, wpi::Twine{});
+}
+
+void SinkImpl::UpdatePropertyValue(int property, bool setString, int value,
+                                   const wpi::Twine& valueStr) {
+  auto prop = GetProperty(property);
+  if (!prop) return;
+
+  if (setString)
+    prop->SetValue(valueStr);
+  else
+    prop->SetValue(value);
+
+  // Only notify updates after we've notified created
+  if (m_properties_cached) {
+    m_notifier.NotifySinkProperty(*this, CS_SINK_PROPERTY_VALUE_UPDATED,
+                                  prop->name, property, prop->propKind,
+                                  prop->value, prop->valueStr);
+  }
+}
+
+void SinkImpl::SetSourceImpl(std::shared_ptr<SourceImpl> source) {}
diff --git a/cscore/src/main/native/cpp/SinkImpl.h b/cscore/src/main/native/cpp/SinkImpl.h
new file mode 100644
index 0000000..7ad831f
--- /dev/null
+++ b/cscore/src/main/native/cpp/SinkImpl.h
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_SINKIMPL_H_
+#define CSCORE_SINKIMPL_H_
+
+#include <memory>
+#include <string>
+
+#include <wpi/Logger.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/mutex.h>
+
+#include "SourceImpl.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace cs {
+
+class Frame;
+class Notifier;
+class Telemetry;
+
+class SinkImpl : public PropertyContainer {
+ public:
+  explicit SinkImpl(const wpi::Twine& name, wpi::Logger& logger,
+                    Notifier& notifier, Telemetry& telemetry);
+  virtual ~SinkImpl();
+  SinkImpl(const SinkImpl& queue) = delete;
+  SinkImpl& operator=(const SinkImpl& queue) = delete;
+
+  wpi::StringRef GetName() const { return m_name; }
+
+  void SetDescription(const wpi::Twine& description);
+  wpi::StringRef GetDescription(wpi::SmallVectorImpl<char>& buf) const;
+
+  void Enable();
+  void Disable();
+  void SetEnabled(bool enabled);
+
+  void SetSource(std::shared_ptr<SourceImpl> source);
+
+  std::shared_ptr<SourceImpl> GetSource() const {
+    std::scoped_lock lock(m_mutex);
+    return m_source;
+  }
+
+  std::string GetError() const;
+  wpi::StringRef GetError(wpi::SmallVectorImpl<char>& buf) const;
+
+  bool SetConfigJson(wpi::StringRef config, CS_Status* status);
+  virtual bool SetConfigJson(const wpi::json& config, CS_Status* status);
+  std::string GetConfigJson(CS_Status* status);
+  virtual wpi::json GetConfigJsonObject(CS_Status* status);
+
+ protected:
+  // PropertyContainer implementation
+  void NotifyPropertyCreated(int propIndex, PropertyImpl& prop) override;
+  void UpdatePropertyValue(int property, bool setString, int value,
+                           const wpi::Twine& valueStr) override;
+
+  virtual void SetSourceImpl(std::shared_ptr<SourceImpl> source);
+
+ protected:
+  wpi::Logger& m_logger;
+  Notifier& m_notifier;
+  Telemetry& m_telemetry;
+
+ private:
+  std::string m_name;
+  std::string m_description;
+  std::shared_ptr<SourceImpl> m_source;
+  int m_enabledCount{0};
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_SINKIMPL_H_
diff --git a/cscore/src/main/native/cpp/SourceImpl.cpp b/cscore/src/main/native/cpp/SourceImpl.cpp
new file mode 100644
index 0000000..455b6cd
--- /dev/null
+++ b/cscore/src/main/native/cpp/SourceImpl.cpp
@@ -0,0 +1,527 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "SourceImpl.h"
+
+#include <algorithm>
+#include <cstring>
+
+#include <wpi/json.h>
+#include <wpi/timestamp.h>
+
+#include "Log.h"
+#include "Notifier.h"
+#include "Telemetry.h"
+
+using namespace cs;
+
+static constexpr size_t kMaxImagesAvail = 32;
+
+SourceImpl::SourceImpl(const wpi::Twine& name, wpi::Logger& logger,
+                       Notifier& notifier, Telemetry& telemetry)
+    : m_logger(logger),
+      m_notifier(notifier),
+      m_telemetry(telemetry),
+      m_name{name.str()} {
+  m_frame = Frame{*this, wpi::StringRef{}, 0};
+}
+
+SourceImpl::~SourceImpl() {
+  // Wake up anyone who is waiting.  This also clears the current frame,
+  // which is good because its destructor will call back into the class.
+  Wakeup();
+  // Set a flag so ReleaseFrame() doesn't re-add them to m_framesAvail.
+  // Put in a block so we destroy before the destructor ends.
+  {
+    m_destroyFrames = true;
+    auto frames = std::move(m_framesAvail);
+  }
+  // Everything else can clean up itself.
+}
+
+void SourceImpl::SetDescription(const wpi::Twine& description) {
+  std::scoped_lock lock(m_mutex);
+  m_description = description.str();
+}
+
+wpi::StringRef SourceImpl::GetDescription(
+    wpi::SmallVectorImpl<char>& buf) const {
+  std::scoped_lock lock(m_mutex);
+  buf.append(m_description.begin(), m_description.end());
+  return wpi::StringRef{buf.data(), buf.size()};
+}
+
+void SourceImpl::SetConnected(bool connected) {
+  bool wasConnected = m_connected.exchange(connected);
+  if (wasConnected && !connected)
+    m_notifier.NotifySource(*this, CS_SOURCE_DISCONNECTED);
+  else if (!wasConnected && connected)
+    m_notifier.NotifySource(*this, CS_SOURCE_CONNECTED);
+}
+
+uint64_t SourceImpl::GetCurFrameTime() {
+  std::unique_lock lock{m_frameMutex};
+  return m_frame.GetTime();
+}
+
+Frame SourceImpl::GetCurFrame() {
+  std::unique_lock lock{m_frameMutex};
+  return m_frame;
+}
+
+Frame SourceImpl::GetNextFrame() {
+  std::unique_lock lock{m_frameMutex};
+  auto oldTime = m_frame.GetTime();
+  m_frameCv.wait(lock, [=] { return m_frame.GetTime() != oldTime; });
+  return m_frame;
+}
+
+Frame SourceImpl::GetNextFrame(double timeout) {
+  std::unique_lock lock{m_frameMutex};
+  auto oldTime = m_frame.GetTime();
+  if (!m_frameCv.wait_for(
+          lock, std::chrono::milliseconds(static_cast<int>(timeout * 1000)),
+          [=] { return m_frame.GetTime() != oldTime; })) {
+    m_frame = Frame{*this, "timed out getting frame", wpi::Now()};
+  }
+  return m_frame;
+}
+
+void SourceImpl::Wakeup() {
+  {
+    std::scoped_lock lock{m_frameMutex};
+    m_frame = Frame{*this, wpi::StringRef{}, 0};
+  }
+  m_frameCv.notify_all();
+}
+
+void SourceImpl::SetBrightness(int brightness, CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+int SourceImpl::GetBrightness(CS_Status* status) const {
+  *status = CS_INVALID_HANDLE;
+  return 0;
+}
+
+void SourceImpl::SetWhiteBalanceAuto(CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+void SourceImpl::SetWhiteBalanceHoldCurrent(CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+void SourceImpl::SetWhiteBalanceManual(int value, CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+void SourceImpl::SetExposureAuto(CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+void SourceImpl::SetExposureHoldCurrent(CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+void SourceImpl::SetExposureManual(int value, CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+VideoMode SourceImpl::GetVideoMode(CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return VideoMode{};
+  std::scoped_lock lock(m_mutex);
+  return m_mode;
+}
+
+bool SourceImpl::SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                                CS_Status* status) {
+  auto mode = GetVideoMode(status);
+  if (!mode) return false;
+  mode.pixelFormat = pixelFormat;
+  return SetVideoMode(mode, status);
+}
+
+bool SourceImpl::SetResolution(int width, int height, CS_Status* status) {
+  auto mode = GetVideoMode(status);
+  if (!mode) return false;
+  mode.width = width;
+  mode.height = height;
+  return SetVideoMode(mode, status);
+}
+
+bool SourceImpl::SetFPS(int fps, CS_Status* status) {
+  auto mode = GetVideoMode(status);
+  if (!mode) return false;
+  mode.fps = fps;
+  return SetVideoMode(mode, status);
+}
+
+bool SourceImpl::SetConfigJson(wpi::StringRef config, CS_Status* status) {
+  wpi::json j;
+  try {
+    j = wpi::json::parse(config);
+  } catch (const wpi::json::parse_error& e) {
+    SWARNING("SetConfigJson: parse error at byte " << e.byte << ": "
+                                                   << e.what());
+    *status = CS_PROPERTY_WRITE_FAILED;
+    return false;
+  }
+  return SetConfigJson(j, status);
+}
+
+bool SourceImpl::SetConfigJson(const wpi::json& config, CS_Status* status) {
+  VideoMode mode;
+
+  // pixel format
+  if (config.count("pixel format") != 0) {
+    try {
+      auto str = config.at("pixel format").get<std::string>();
+      wpi::StringRef s(str);
+      if (s.equals_lower("mjpeg")) {
+        mode.pixelFormat = cs::VideoMode::kMJPEG;
+      } else if (s.equals_lower("yuyv")) {
+        mode.pixelFormat = cs::VideoMode::kYUYV;
+      } else if (s.equals_lower("rgb565")) {
+        mode.pixelFormat = cs::VideoMode::kRGB565;
+      } else if (s.equals_lower("bgr")) {
+        mode.pixelFormat = cs::VideoMode::kBGR;
+      } else if (s.equals_lower("gray")) {
+        mode.pixelFormat = cs::VideoMode::kGray;
+      } else {
+        SWARNING("SetConfigJson: could not understand pixel format value '"
+                 << str << '\'');
+      }
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read pixel format: " << e.what());
+    }
+  }
+
+  // width
+  if (config.count("width") != 0) {
+    try {
+      mode.width = config.at("width").get<unsigned int>();
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read width: " << e.what());
+    }
+  }
+
+  // height
+  if (config.count("height") != 0) {
+    try {
+      mode.height = config.at("height").get<unsigned int>();
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read height: " << e.what());
+    }
+  }
+
+  // fps
+  if (config.count("fps") != 0) {
+    try {
+      mode.fps = config.at("fps").get<unsigned int>();
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read fps: " << e.what());
+    }
+  }
+
+  // if all of video mode is set, use SetVideoMode, otherwise piecemeal it
+  if (mode.pixelFormat != VideoMode::kUnknown && mode.width != 0 &&
+      mode.height != 0 && mode.fps != 0) {
+    SINFO("SetConfigJson: setting video mode to pixelFormat "
+          << mode.pixelFormat << ", width " << mode.width << ", height "
+          << mode.height << ", fps " << mode.fps);
+    SetVideoMode(mode, status);
+  } else {
+    if (mode.pixelFormat != cs::VideoMode::kUnknown) {
+      SINFO("SetConfigJson: setting pixelFormat " << mode.pixelFormat);
+      SetPixelFormat(static_cast<cs::VideoMode::PixelFormat>(mode.pixelFormat),
+                     status);
+    }
+    if (mode.width != 0 && mode.height != 0) {
+      SINFO("SetConfigJson: setting width " << mode.width << ", height "
+                                            << mode.height);
+      SetResolution(mode.width, mode.height, status);
+    }
+    if (mode.fps != 0) {
+      SINFO("SetConfigJson: setting fps " << mode.fps);
+      SetFPS(mode.fps, status);
+    }
+  }
+
+  // brightness
+  if (config.count("brightness") != 0) {
+    try {
+      int val = config.at("brightness").get<int>();
+      SINFO("SetConfigJson: setting brightness to " << val);
+      SetBrightness(val, status);
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read brightness: " << e.what());
+    }
+  }
+
+  // white balance
+  if (config.count("white balance") != 0) {
+    try {
+      auto& setting = config.at("white balance");
+      if (setting.is_string()) {
+        auto str = setting.get<std::string>();
+        wpi::StringRef s(str);
+        if (s.equals_lower("auto")) {
+          SINFO("SetConfigJson: setting white balance to auto");
+          SetWhiteBalanceAuto(status);
+        } else if (s.equals_lower("hold")) {
+          SINFO("SetConfigJson: setting white balance to hold current");
+          SetWhiteBalanceHoldCurrent(status);
+        } else {
+          SWARNING("SetConfigJson: could not understand white balance value '"
+                   << str << '\'');
+        }
+      } else {
+        int val = setting.get<int>();
+        SINFO("SetConfigJson: setting white balance to " << val);
+        SetWhiteBalanceManual(val, status);
+      }
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read white balance: " << e.what());
+    }
+  }
+
+  // exposure
+  if (config.count("exposure") != 0) {
+    try {
+      auto& setting = config.at("exposure");
+      if (setting.is_string()) {
+        auto str = setting.get<std::string>();
+        wpi::StringRef s(str);
+        if (s.equals_lower("auto")) {
+          SINFO("SetConfigJson: setting exposure to auto");
+          SetExposureAuto(status);
+        } else if (s.equals_lower("hold")) {
+          SINFO("SetConfigJson: setting exposure to hold current");
+          SetExposureHoldCurrent(status);
+        } else {
+          SWARNING("SetConfigJson: could not understand exposure value '"
+                   << str << '\'');
+        }
+      } else {
+        int val = setting.get<int>();
+        SINFO("SetConfigJson: setting exposure to " << val);
+        SetExposureManual(val, status);
+      }
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read exposure: " << e.what());
+    }
+  }
+
+  // properties
+  if (config.count("properties") != 0)
+    SetPropertiesJson(config.at("properties"), m_logger, GetName(), status);
+
+  return true;
+}
+
+std::string SourceImpl::GetConfigJson(CS_Status* status) {
+  std::string rv;
+  wpi::raw_string_ostream os(rv);
+  GetConfigJsonObject(status).dump(os, 4);
+  os.flush();
+  return rv;
+}
+
+wpi::json SourceImpl::GetConfigJsonObject(CS_Status* status) {
+  wpi::json j;
+
+  // pixel format
+  wpi::StringRef pixelFormat;
+  switch (m_mode.pixelFormat) {
+    case VideoMode::kMJPEG:
+      pixelFormat = "mjpeg";
+      break;
+    case VideoMode::kYUYV:
+      pixelFormat = "yuyv";
+      break;
+    case VideoMode::kRGB565:
+      pixelFormat = "rgb565";
+      break;
+    case VideoMode::kBGR:
+      pixelFormat = "bgr";
+      break;
+    case VideoMode::kGray:
+      pixelFormat = "gray";
+      break;
+    default:
+      break;
+  }
+  if (!pixelFormat.empty()) j.emplace("pixel format", pixelFormat);
+
+  // width
+  if (m_mode.width != 0) j.emplace("width", m_mode.width);
+
+  // height
+  if (m_mode.height != 0) j.emplace("height", m_mode.height);
+
+  // fps
+  if (m_mode.fps != 0) j.emplace("fps", m_mode.fps);
+
+  // TODO: output brightness, white balance, and exposure?
+
+  // properties
+  wpi::json props = GetPropertiesJsonObject(status);
+  if (props.is_array()) j.emplace("properties", props);
+
+  return j;
+}
+
+std::vector<VideoMode> SourceImpl::EnumerateVideoModes(
+    CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status))
+    return std::vector<VideoMode>{};
+  std::scoped_lock lock(m_mutex);
+  return m_videoModes;
+}
+
+std::unique_ptr<Image> SourceImpl::AllocImage(
+    VideoMode::PixelFormat pixelFormat, int width, int height, size_t size) {
+  std::unique_ptr<Image> image;
+  {
+    std::scoped_lock lock{m_poolMutex};
+    // find the smallest existing frame that is at least big enough.
+    int found = -1;
+    for (size_t i = 0; i < m_imagesAvail.size(); ++i) {
+      // is it big enough?
+      if (m_imagesAvail[i] && m_imagesAvail[i]->capacity() >= size) {
+        // is it smaller than the last found?
+        if (found < 0 ||
+            m_imagesAvail[i]->capacity() < m_imagesAvail[found]->capacity()) {
+          // yes, update
+          found = i;
+        }
+      }
+    }
+
+    // if nothing found, allocate a new buffer
+    if (found < 0)
+      image.reset(new Image{size});
+    else
+      image = std::move(m_imagesAvail[found]);
+  }
+
+  // Initialize image
+  image->SetSize(size);
+  image->pixelFormat = pixelFormat;
+  image->width = width;
+  image->height = height;
+
+  return image;
+}
+
+void SourceImpl::PutFrame(VideoMode::PixelFormat pixelFormat, int width,
+                          int height, wpi::StringRef data, Frame::Time time) {
+  auto image = AllocImage(pixelFormat, width, height, data.size());
+
+  // Copy in image data
+  SDEBUG4("Copying data to "
+          << reinterpret_cast<const void*>(image->data()) << " from "
+          << reinterpret_cast<const void*>(data.data()) << " (" << data.size()
+          << " bytes)");
+  std::memcpy(image->data(), data.data(), data.size());
+
+  PutFrame(std::move(image), time);
+}
+
+void SourceImpl::PutFrame(std::unique_ptr<Image> image, Frame::Time time) {
+  // Update telemetry
+  m_telemetry.RecordSourceFrames(*this, 1);
+  m_telemetry.RecordSourceBytes(*this, static_cast<int>(image->size()));
+
+  // Update frame
+  {
+    std::scoped_lock lock{m_frameMutex};
+    m_frame = Frame{*this, std::move(image), time};
+  }
+
+  // Signal listeners
+  m_frameCv.notify_all();
+}
+
+void SourceImpl::PutError(const wpi::Twine& msg, Frame::Time time) {
+  // Update frame
+  {
+    std::scoped_lock lock{m_frameMutex};
+    m_frame = Frame{*this, msg, time};
+  }
+
+  // Signal listeners
+  m_frameCv.notify_all();
+}
+
+void SourceImpl::NotifyPropertyCreated(int propIndex, PropertyImpl& prop) {
+  m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CREATED, prop.name,
+                                  propIndex, prop.propKind, prop.value,
+                                  prop.valueStr);
+  // also notify choices updated event for enum types
+  if (prop.propKind == CS_PROP_ENUM)
+    m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CHOICES_UPDATED,
+                                    prop.name, propIndex, prop.propKind,
+                                    prop.value, wpi::Twine{});
+}
+
+void SourceImpl::UpdatePropertyValue(int property, bool setString, int value,
+                                     const wpi::Twine& valueStr) {
+  auto prop = GetProperty(property);
+  if (!prop) return;
+
+  if (setString)
+    prop->SetValue(valueStr);
+  else
+    prop->SetValue(value);
+
+  // Only notify updates after we've notified created
+  if (m_properties_cached) {
+    m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_VALUE_UPDATED,
+                                    prop->name, property, prop->propKind,
+                                    prop->value, prop->valueStr);
+  }
+}
+
+void SourceImpl::ReleaseImage(std::unique_ptr<Image> image) {
+  std::scoped_lock lock{m_poolMutex};
+  if (m_destroyFrames) return;
+  // Return the frame to the pool.  First try to find an empty slot, otherwise
+  // add it to the end.
+  auto it = std::find(m_imagesAvail.begin(), m_imagesAvail.end(), nullptr);
+  if (it != m_imagesAvail.end()) {
+    *it = std::move(image);
+  } else if (m_imagesAvail.size() > kMaxImagesAvail) {
+    // Replace smallest buffer; don't need to check for null because the above
+    // find would have found it.
+    auto it2 = std::min_element(
+        m_imagesAvail.begin(), m_imagesAvail.end(),
+        [](const std::unique_ptr<Image>& a, const std::unique_ptr<Image>& b) {
+          return a->capacity() < b->capacity();
+        });
+    if ((*it2)->capacity() < image->capacity()) *it2 = std::move(image);
+  } else {
+    m_imagesAvail.emplace_back(std::move(image));
+  }
+}
+
+std::unique_ptr<Frame::Impl> SourceImpl::AllocFrameImpl() {
+  std::scoped_lock lock{m_poolMutex};
+
+  if (m_framesAvail.empty()) return std::make_unique<Frame::Impl>(*this);
+
+  auto impl = std::move(m_framesAvail.back());
+  m_framesAvail.pop_back();
+  return impl;
+}
+
+void SourceImpl::ReleaseFrameImpl(std::unique_ptr<Frame::Impl> impl) {
+  std::scoped_lock lock{m_poolMutex};
+  if (m_destroyFrames) return;
+  m_framesAvail.push_back(std::move(impl));
+}
diff --git a/cscore/src/main/native/cpp/SourceImpl.h b/cscore/src/main/native/cpp/SourceImpl.h
new file mode 100644
index 0000000..d74d8fa
--- /dev/null
+++ b/cscore/src/main/native/cpp/SourceImpl.h
@@ -0,0 +1,202 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_SOURCEIMPL_H_
+#define CSCORE_SOURCEIMPL_H_
+
+#include <atomic>
+#include <cstddef>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/Logger.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+
+#include "Frame.h"
+#include "Handle.h"
+#include "Image.h"
+#include "PropertyContainer.h"
+#include "cscore_cpp.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace cs {
+
+class Notifier;
+class Telemetry;
+
+class SourceImpl : public PropertyContainer {
+  friend class Frame;
+
+ public:
+  SourceImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+             Telemetry& telemetry);
+  virtual ~SourceImpl();
+  SourceImpl(const SourceImpl& oth) = delete;
+  SourceImpl& operator=(const SourceImpl& oth) = delete;
+
+  virtual void Start() = 0;
+
+  wpi::StringRef GetName() const { return m_name; }
+
+  void SetDescription(const wpi::Twine& description);
+  wpi::StringRef GetDescription(wpi::SmallVectorImpl<char>& buf) const;
+
+  void SetConnectionStrategy(CS_ConnectionStrategy strategy) {
+    m_strategy = static_cast<int>(strategy);
+  }
+  bool IsEnabled() const {
+    return m_strategy == CS_CONNECTION_KEEP_OPEN ||
+           (m_strategy == CS_CONNECTION_AUTO_MANAGE && m_numSinksEnabled > 0);
+  }
+
+  // User-visible connection status
+  void SetConnected(bool connected);
+  bool IsConnected() const { return m_connected; }
+
+  // Functions to keep track of the overall number of sinks connected to this
+  // source.  Primarily used by sinks to determine if other sinks are using
+  // the same source.
+  int GetNumSinks() const { return m_numSinks; }
+  void AddSink() {
+    ++m_numSinks;
+    NumSinksChanged();
+  }
+  void RemoveSink() {
+    --m_numSinks;
+    NumSinksChanged();
+  }
+
+  // Functions to keep track of the number of sinks connected to this source
+  // that are "enabled", in other words, listening for new images.  Primarily
+  // used by sources to determine whether they should actually bother trying
+  // to get source frames.
+  int GetNumSinksEnabled() const { return m_numSinksEnabled; }
+
+  void EnableSink() {
+    ++m_numSinksEnabled;
+    NumSinksEnabledChanged();
+  }
+
+  void DisableSink() {
+    --m_numSinksEnabled;
+    NumSinksEnabledChanged();
+  }
+
+  // Gets the current frame time (without waiting for a new one).
+  uint64_t GetCurFrameTime();
+
+  // Gets the current frame (without waiting for a new one).
+  Frame GetCurFrame();
+
+  // Blocking function that waits for the next frame and returns it.
+  Frame GetNextFrame();
+
+  // Blocking function that waits for the next frame and returns it (with
+  // timeout in seconds).  If timeout expires, returns empty frame.
+  Frame GetNextFrame(double timeout);
+
+  // Force a wakeup of all GetNextFrame() callers by sending an empty frame.
+  void Wakeup();
+
+  // Standard common camera properties
+  virtual void SetBrightness(int brightness, CS_Status* status);
+  virtual int GetBrightness(CS_Status* status) const;
+  virtual void SetWhiteBalanceAuto(CS_Status* status);
+  virtual void SetWhiteBalanceHoldCurrent(CS_Status* status);
+  virtual void SetWhiteBalanceManual(int value, CS_Status* status);
+  virtual void SetExposureAuto(CS_Status* status);
+  virtual void SetExposureHoldCurrent(CS_Status* status);
+  virtual void SetExposureManual(int value, CS_Status* status);
+
+  // Video mode functions
+  VideoMode GetVideoMode(CS_Status* status) const;
+  virtual bool SetVideoMode(const VideoMode& mode, CS_Status* status) = 0;
+
+  // These have default implementations but can be overridden for custom
+  // or optimized behavior.
+  virtual bool SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                              CS_Status* status);
+  virtual bool SetResolution(int width, int height, CS_Status* status);
+  virtual bool SetFPS(int fps, CS_Status* status);
+
+  bool SetConfigJson(wpi::StringRef config, CS_Status* status);
+  virtual bool SetConfigJson(const wpi::json& config, CS_Status* status);
+  std::string GetConfigJson(CS_Status* status);
+  virtual wpi::json GetConfigJsonObject(CS_Status* status);
+
+  std::vector<VideoMode> EnumerateVideoModes(CS_Status* status) const;
+
+  std::unique_ptr<Image> AllocImage(VideoMode::PixelFormat pixelFormat,
+                                    int width, int height, size_t size);
+
+ protected:
+  void NotifyPropertyCreated(int propIndex, PropertyImpl& prop) override;
+  void UpdatePropertyValue(int property, bool setString, int value,
+                           const wpi::Twine& valueStr) override;
+
+  void PutFrame(VideoMode::PixelFormat pixelFormat, int width, int height,
+                wpi::StringRef data, Frame::Time time);
+  void PutFrame(std::unique_ptr<Image> image, Frame::Time time);
+  void PutError(const wpi::Twine& msg, Frame::Time time);
+
+  // Notification functions for corresponding atomics
+  virtual void NumSinksChanged() = 0;
+  virtual void NumSinksEnabledChanged() = 0;
+
+  std::atomic_int m_numSinks{0};
+
+ protected:
+  // Cached video modes (protected with m_mutex)
+  mutable std::vector<VideoMode> m_videoModes;
+  // Current video mode
+  mutable VideoMode m_mode;
+
+  wpi::Logger& m_logger;
+  Notifier& m_notifier;
+  Telemetry& m_telemetry;
+
+ private:
+  void ReleaseImage(std::unique_ptr<Image> image);
+  std::unique_ptr<Frame::Impl> AllocFrameImpl();
+  void ReleaseFrameImpl(std::unique_ptr<Frame::Impl> data);
+
+  std::string m_name;
+  std::string m_description;
+
+  std::atomic_int m_strategy{CS_CONNECTION_AUTO_MANAGE};
+  std::atomic_int m_numSinksEnabled{0};
+
+  wpi::mutex m_frameMutex;
+  wpi::condition_variable m_frameCv;
+
+  bool m_destroyFrames{false};
+
+  // Pool of frames/images to reduce malloc traffic.
+  wpi::mutex m_poolMutex;
+  std::vector<std::unique_ptr<Frame::Impl>> m_framesAvail;
+  std::vector<std::unique_ptr<Image>> m_imagesAvail;
+
+  std::atomic_bool m_connected{false};
+
+  // Most recent frame (returned to callers of GetNextFrame)
+  // Access protected by m_frameMutex.
+  // MUST be located below m_poolMutex as the Frame destructor calls back
+  // into SourceImpl::ReleaseImage, which locks m_poolMutex.
+  Frame m_frame;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_SOURCEIMPL_H_
diff --git a/cscore/src/main/native/cpp/Telemetry.cpp b/cscore/src/main/native/cpp/Telemetry.cpp
new file mode 100644
index 0000000..77130f6
--- /dev/null
+++ b/cscore/src/main/native/cpp/Telemetry.cpp
@@ -0,0 +1,136 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "Telemetry.h"
+
+#include <chrono>
+#include <limits>
+
+#include <wpi/DenseMap.h>
+#include <wpi/timestamp.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "Notifier.h"
+#include "SourceImpl.h"
+#include "cscore_cpp.h"
+
+using namespace cs;
+
+class Telemetry::Thread : public wpi::SafeThread {
+ public:
+  explicit Thread(Notifier& notifier) : m_notifier(notifier) {}
+
+  void Main();
+
+  Notifier& m_notifier;
+  wpi::DenseMap<std::pair<CS_Handle, int>, int64_t> m_user;
+  wpi::DenseMap<std::pair<CS_Handle, int>, int64_t> m_current;
+  double m_period = 0.0;
+  double m_elapsed = 0.0;
+  bool m_updated = false;
+  int64_t GetValue(CS_Handle handle, CS_TelemetryKind kind, CS_Status* status);
+};
+
+int64_t Telemetry::Thread::GetValue(CS_Handle handle, CS_TelemetryKind kind,
+                                    CS_Status* status) {
+  auto it = m_user.find(std::make_pair(handle, static_cast<int>(kind)));
+  if (it == m_user.end()) {
+    *status = CS_EMPTY_VALUE;
+    return 0;
+  }
+  return it->getSecond();
+}
+
+Telemetry::~Telemetry() {}
+
+void Telemetry::Start() { m_owner.Start(m_notifier); }
+
+void Telemetry::Stop() { m_owner.Stop(); }
+
+void Telemetry::Thread::Main() {
+  std::unique_lock lock(m_mutex);
+  auto prevTime = std::chrono::steady_clock::now();
+  while (m_active) {
+    double period = m_period;
+    if (period == 0) period = 1000.0;
+    auto timeoutTime = prevTime + std::chrono::duration<double>(period);
+    while (m_active && !m_updated) {
+      if (m_cond.wait_until(lock, timeoutTime) == std::cv_status::timeout)
+        break;
+    }
+    if (!m_active) break;
+    if (m_updated) {
+      m_updated = false;
+      continue;
+    }
+
+    // move to user and clear current, as we don't keep around old values
+    m_user = std::move(m_current);
+    m_current.clear();
+    auto curTime = std::chrono::steady_clock::now();
+    m_elapsed = std::chrono::duration<double>(curTime - prevTime).count();
+    prevTime = curTime;
+
+    // notify
+    m_notifier.NotifyTelemetryUpdated();
+  }
+}
+
+void Telemetry::SetPeriod(double seconds) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+  if (thr->m_period == seconds) return;  // no change
+  thr->m_period = seconds;
+  thr->m_updated = true;
+  thr->m_cond.notify_one();
+}
+
+double Telemetry::GetElapsedTime() {
+  auto thr = m_owner.GetThread();
+  if (!thr) return 0;
+  return thr->m_elapsed;
+}
+
+int64_t Telemetry::GetValue(CS_Handle handle, CS_TelemetryKind kind,
+                            CS_Status* status) {
+  auto thr = m_owner.GetThread();
+  if (!thr) {
+    *status = CS_TELEMETRY_NOT_ENABLED;
+    return 0;
+  }
+  return thr->GetValue(handle, kind, status);
+}
+
+double Telemetry::GetAverageValue(CS_Handle handle, CS_TelemetryKind kind,
+                                  CS_Status* status) {
+  auto thr = m_owner.GetThread();
+  if (!thr) {
+    *status = CS_TELEMETRY_NOT_ENABLED;
+    return 0;
+  }
+  if (thr->m_elapsed == 0) return 0.0;
+  return thr->GetValue(handle, kind, status) / thr->m_elapsed;
+}
+
+void Telemetry::RecordSourceBytes(const SourceImpl& source, int quantity) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+  auto handleData = Instance::GetInstance().FindSource(source);
+  thr->m_current[std::make_pair(Handle{handleData.first, Handle::kSource},
+                                static_cast<int>(CS_SOURCE_BYTES_RECEIVED))] +=
+      quantity;
+}
+
+void Telemetry::RecordSourceFrames(const SourceImpl& source, int quantity) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+  auto handleData = Instance::GetInstance().FindSource(source);
+  thr->m_current[std::make_pair(Handle{handleData.first, Handle::kSource},
+                                static_cast<int>(CS_SOURCE_FRAMES_RECEIVED))] +=
+      quantity;
+}
diff --git a/cscore/src/main/native/cpp/Telemetry.h b/cscore/src/main/native/cpp/Telemetry.h
new file mode 100644
index 0000000..8729704
--- /dev/null
+++ b/cscore/src/main/native/cpp/Telemetry.h
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_TELEMETRY_H_
+#define CSCORE_TELEMETRY_H_
+
+#include <wpi/SafeThread.h>
+
+#include "cscore_cpp.h"
+
+namespace cs {
+
+class Notifier;
+class SourceImpl;
+
+class Telemetry {
+  friend class TelemetryTest;
+
+ public:
+  explicit Telemetry(Notifier& notifier) : m_notifier(notifier) {}
+  ~Telemetry();
+
+  void Start();
+  void Stop();
+
+  // User interface
+  void SetPeriod(double seconds);
+  double GetElapsedTime();
+  int64_t GetValue(CS_Handle handle, CS_TelemetryKind kind, CS_Status* status);
+  double GetAverageValue(CS_Handle handle, CS_TelemetryKind kind,
+                         CS_Status* status);
+
+  // Telemetry events
+  void RecordSourceBytes(const SourceImpl& source, int quantity);
+  void RecordSourceFrames(const SourceImpl& source, int quantity);
+
+ private:
+  Notifier& m_notifier;
+
+  class Thread;
+  wpi::SafeThreadOwner<Thread> m_owner;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_TELEMETRY_H_
diff --git a/cscore/src/main/native/cpp/UnlimitedHandleResource.h b/cscore/src/main/native/cpp/UnlimitedHandleResource.h
new file mode 100644
index 0000000..200572c
--- /dev/null
+++ b/cscore/src/main/native/cpp/UnlimitedHandleResource.h
@@ -0,0 +1,186 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_UNLIMITEDHANDLERESOURCE_H_
+#define CSCORE_UNLIMITEDHANDLERESOURCE_H_
+
+#include <memory>
+#include <utility>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/SmallVector.h>
+#include <wpi/mutex.h>
+
+namespace cs {
+
+// The UnlimitedHandleResource class is a way to track handles. This version
+// allows an unlimted number of handles that are allocated sequentially. When
+// possible, indices are reused to save memory usage and keep the array length
+// down.
+// However, automatic array management has not been implemented, but might be in
+// the future.
+// Because we have to loop through the allocator, we must use a global mutex.
+//
+// THandle needs to have the following attributes:
+//  Type : enum or typedef
+//  kIndexMax : static, constexpr, or enum value for the maximum index value
+//  int GetTypedIndex() const : function that returns the index of the handle
+//  THandle(int index, HandleType[int] type) : constructor for index and type
+//
+// @tparam THandle The Handle Type
+// @tparam TStruct The struct type held by this resource
+// @tparam typeValue The type value stored in the handle
+// @tparam TMutex The mutex type to use
+template <typename THandle, typename TStruct, int typeValue,
+          typename TMutex = wpi::mutex>
+class UnlimitedHandleResource {
+ public:
+  UnlimitedHandleResource(const UnlimitedHandleResource&) = delete;
+  UnlimitedHandleResource operator=(const UnlimitedHandleResource&) = delete;
+  UnlimitedHandleResource() = default;
+
+  template <typename... Args>
+  THandle Allocate(Args&&... args);
+  THandle Allocate(std::shared_ptr<THandle> structure);
+
+  std::shared_ptr<TStruct> Get(THandle handle);
+
+  std::shared_ptr<TStruct> Free(THandle handle);
+
+  template <typename T>
+  wpi::ArrayRef<T> GetAll(wpi::SmallVectorImpl<T>& vec);
+
+  std::vector<std::shared_ptr<TStruct>> FreeAll();
+
+  // @param func functor with (THandle, const TStruct&) parameters
+  template <typename F>
+  void ForEach(F func);
+
+  // @pram func functor with (const TStruct&) parameter and bool return value
+  template <typename F>
+  std::pair<THandle, std::shared_ptr<TStruct>> FindIf(F func);
+
+ private:
+  THandle MakeHandle(size_t i) {
+    return THandle{static_cast<int>(i),
+                   static_cast<typename THandle::Type>(typeValue)};
+  }
+  std::vector<std::shared_ptr<TStruct>> m_structures;
+  TMutex m_handleMutex;
+};
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+template <typename... Args>
+THandle UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::Allocate(
+    Args&&... args) {
+#ifdef _MSC_VER  // work around VS2019 16.4.0 bug
+  std::scoped_lock<TMutex> lock(m_handleMutex);
+#else
+  std::scoped_lock sync(m_handleMutex);
+#endif
+  size_t i;
+  for (i = 0; i < m_structures.size(); i++) {
+    if (m_structures[i] == nullptr) {
+      m_structures[i] = std::make_shared<TStruct>(std::forward<Args>(args)...);
+      return MakeHandle(i);
+    }
+  }
+  if (i >= THandle::kIndexMax) return 0;
+
+  m_structures.emplace_back(
+      std::make_shared<TStruct>(std::forward<Args>(args)...));
+  return MakeHandle(i);
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+THandle UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::Allocate(
+    std::shared_ptr<THandle> structure) {
+  std::scoped_lock sync(m_handleMutex);
+  size_t i;
+  for (i = 0; i < m_structures.size(); i++) {
+    if (m_structures[i] == nullptr) {
+      m_structures[i] = structure;
+      return MakeHandle(i);
+    }
+  }
+  if (i >= THandle::kIndexMax) return 0;
+
+  m_structures.push_back(structure);
+  return MakeHandle(i);
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+inline std::shared_ptr<TStruct>
+UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::Get(
+    THandle handle) {
+  auto index =
+      handle.GetTypedIndex(static_cast<typename THandle::Type>(typeValue));
+  if (index < 0) return nullptr;
+  std::scoped_lock sync(m_handleMutex);
+  if (index >= static_cast<int>(m_structures.size())) return nullptr;
+  return m_structures[index];
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+inline std::shared_ptr<TStruct>
+UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::Free(
+    THandle handle) {
+  auto index =
+      handle.GetTypedIndex(static_cast<typename THandle::Type>(typeValue));
+  if (index < 0) return nullptr;
+  std::scoped_lock sync(m_handleMutex);
+  if (index >= static_cast<int>(m_structures.size())) return nullptr;
+  auto rv = std::move(m_structures[index]);
+  m_structures[index].reset();
+  return rv;
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+template <typename T>
+inline wpi::ArrayRef<T>
+UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::GetAll(
+    wpi::SmallVectorImpl<T>& vec) {
+  ForEach([&](THandle handle, const TStruct& data) { vec.push_back(handle); });
+  return vec;
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+inline std::vector<std::shared_ptr<TStruct>>
+UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::FreeAll() {
+  std::scoped_lock sync(m_handleMutex);
+  auto rv = std::move(m_structures);
+  m_structures.clear();
+  return rv;
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+template <typename F>
+inline void
+UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::ForEach(F func) {
+  std::scoped_lock sync(m_handleMutex);
+  for (size_t i = 0; i < m_structures.size(); i++) {
+    if (m_structures[i] != nullptr) func(MakeHandle(i), *(m_structures[i]));
+  }
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+template <typename F>
+inline std::pair<THandle, std::shared_ptr<TStruct>>
+UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::FindIf(F func) {
+  std::scoped_lock sync(m_handleMutex);
+  for (size_t i = 0; i < m_structures.size(); i++) {
+    auto& structure = m_structures[i];
+    if (structure != nullptr && func(*structure))
+      return std::make_pair(MakeHandle(i), structure);
+  }
+  return std::make_pair(0, nullptr);
+}
+
+}  // namespace cs
+
+#endif  // CSCORE_UNLIMITEDHANDLERESOURCE_H_
diff --git a/cscore/src/main/native/cpp/UsbCameraImplCommon.cpp b/cscore/src/main/native/cpp/UsbCameraImplCommon.cpp
new file mode 100644
index 0000000..2b3fb08
--- /dev/null
+++ b/cscore/src/main/native/cpp/UsbCameraImplCommon.cpp
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "cscore_c.h"  // NOLINT(build/include_order)
+
+#include "c_util.h"
+#include "cscore_cpp.h"
+
+using namespace cs;
+
+static void ConvertToC(CS_UsbCameraInfo* out, const UsbCameraInfo& in) {
+  out->dev = in.dev;
+  out->path = ConvertToC(in.path);
+  out->name = ConvertToC(in.name);
+  out->otherPaths = static_cast<char**>(
+      wpi::safe_malloc(in.otherPaths.size() * sizeof(char*)));
+  out->otherPathsCount = in.otherPaths.size();
+  for (size_t i = 0; i < in.otherPaths.size(); ++i)
+    out->otherPaths[i] = cs::ConvertToC(in.otherPaths[i]);
+  out->vendorId = in.vendorId;
+  out->productId = in.productId;
+}
+
+static void FreeUsbCameraInfo(CS_UsbCameraInfo* info) {
+  std::free(info->path);
+  std::free(info->name);
+  for (int i = 0; i < info->otherPathsCount; ++i)
+    std::free(info->otherPaths[i]);
+  std::free(info->otherPaths);
+}
+
+extern "C" {
+
+CS_Source CS_CreateUsbCameraDev(const char* name, int dev, CS_Status* status) {
+  return cs::CreateUsbCameraDev(name, dev, status);
+}
+
+CS_Source CS_CreateUsbCameraPath(const char* name, const char* path,
+                                 CS_Status* status) {
+  return cs::CreateUsbCameraPath(name, path, status);
+}
+
+char* CS_GetUsbCameraPath(CS_Source source, CS_Status* status) {
+  return ConvertToC(cs::GetUsbCameraPath(source, status));
+}
+
+CS_UsbCameraInfo* CS_GetUsbCameraInfo(CS_Source source, CS_Status* status) {
+  auto info = cs::GetUsbCameraInfo(source, status);
+  if (*status != CS_OK) return nullptr;
+  CS_UsbCameraInfo* out = static_cast<CS_UsbCameraInfo*>(
+      wpi::safe_malloc(sizeof(CS_UsbCameraInfo)));
+  ConvertToC(out, info);
+  return out;
+}
+
+CS_UsbCameraInfo* CS_EnumerateUsbCameras(int* count, CS_Status* status) {
+  auto cameras = cs::EnumerateUsbCameras(status);
+  CS_UsbCameraInfo* out = static_cast<CS_UsbCameraInfo*>(
+      wpi::safe_malloc(cameras.size() * sizeof(CS_UsbCameraInfo)));
+  *count = cameras.size();
+  for (size_t i = 0; i < cameras.size(); ++i) ConvertToC(&out[i], cameras[i]);
+  return out;
+}
+
+void CS_FreeEnumeratedUsbCameras(CS_UsbCameraInfo* cameras, int count) {
+  if (!cameras) return;
+  for (int i = 0; i < count; ++i) FreeUsbCameraInfo(&cameras[i]);
+  std::free(cameras);
+}
+
+void CS_FreeUsbCameraInfo(CS_UsbCameraInfo* info) {
+  if (!info) return;
+  FreeUsbCameraInfo(info);
+  std::free(info);
+}
+
+}  // extern "C"
diff --git a/cscore/src/main/native/cpp/c_util.h b/cscore/src/main/native/cpp/c_util.h
new file mode 100644
index 0000000..f985fe2
--- /dev/null
+++ b/cscore/src/main/native/cpp/c_util.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_C_UTIL_H_
+#define CSCORE_C_UTIL_H_
+
+#include <cstdlib>
+#include <cstring>
+
+#include <wpi/MemAlloc.h>
+#include <wpi/StringRef.h>
+
+namespace cs {
+
+inline char* ConvertToC(wpi::StringRef in) {
+  char* out = static_cast<char*>(wpi::safe_malloc(in.size() + 1));
+  std::memmove(out, in.data(), in.size());
+  out[in.size()] = '\0';
+  return out;
+}
+
+}  // namespace cs
+
+#endif  // CSCORE_C_UTIL_H_
diff --git a/cscore/src/main/native/cpp/cscore_c.cpp b/cscore/src/main/native/cpp/cscore_c.cpp
new file mode 100644
index 0000000..321572e
--- /dev/null
+++ b/cscore/src/main/native/cpp/cscore_c.cpp
@@ -0,0 +1,463 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "cscore_c.h"
+
+#include <cstddef>
+#include <cstdlib>
+
+#include <opencv2/core/core.hpp>
+#include <wpi/MemAlloc.h>
+#include <wpi/SmallString.h>
+
+#include "c_util.h"
+#include "cscore_cpp.h"
+#include "cscore_raw.h"
+
+extern "C" {
+
+CS_PropertyKind CS_GetPropertyKind(CS_Property property, CS_Status* status) {
+  return cs::GetPropertyKind(property, status);
+}
+
+char* CS_GetPropertyName(CS_Property property, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetPropertyName(property, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+int CS_GetProperty(CS_Property property, CS_Status* status) {
+  return cs::GetProperty(property, status);
+}
+
+void CS_SetProperty(CS_Property property, int value, CS_Status* status) {
+  return cs::SetProperty(property, value, status);
+}
+
+int CS_GetPropertyMin(CS_Property property, CS_Status* status) {
+  return cs::GetPropertyMin(property, status);
+}
+
+int CS_GetPropertyMax(CS_Property property, CS_Status* status) {
+  return cs::GetPropertyMax(property, status);
+}
+
+int CS_GetPropertyStep(CS_Property property, CS_Status* status) {
+  return cs::GetPropertyStep(property, status);
+}
+
+int CS_GetPropertyDefault(CS_Property property, CS_Status* status) {
+  return cs::GetPropertyDefault(property, status);
+}
+
+char* CS_GetStringProperty(CS_Property property, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetStringProperty(property, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+void CS_SetStringProperty(CS_Property property, const char* value,
+                          CS_Status* status) {
+  return cs::SetStringProperty(property, value, status);
+}
+
+char** CS_GetEnumPropertyChoices(CS_Property property, int* count,
+                                 CS_Status* status) {
+  auto choices = cs::GetEnumPropertyChoices(property, status);
+  char** out =
+      static_cast<char**>(wpi::safe_malloc(choices.size() * sizeof(char*)));
+  *count = choices.size();
+  for (size_t i = 0; i < choices.size(); ++i)
+    out[i] = cs::ConvertToC(choices[i]);
+  return out;
+}
+
+CS_SourceKind CS_GetSourceKind(CS_Source source, CS_Status* status) {
+  return cs::GetSourceKind(source, status);
+}
+
+char* CS_GetSourceName(CS_Source source, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSourceName(source, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+char* CS_GetSourceDescription(CS_Source source, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSourceDescription(source, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+uint64_t CS_GetSourceLastFrameTime(CS_Source source, CS_Status* status) {
+  return cs::GetSourceLastFrameTime(source, status);
+}
+
+void CS_SetSourceConnectionStrategy(CS_Source source,
+                                    CS_ConnectionStrategy strategy,
+                                    CS_Status* status) {
+  cs::SetSourceConnectionStrategy(source, strategy, status);
+}
+
+CS_Bool CS_IsSourceConnected(CS_Source source, CS_Status* status) {
+  return cs::IsSourceConnected(source, status);
+}
+
+CS_Bool CS_IsSourceEnabled(CS_Source source, CS_Status* status) {
+  return cs::IsSourceEnabled(source, status);
+}
+
+CS_Property CS_GetSourceProperty(CS_Source source, const char* name,
+                                 CS_Status* status) {
+  return cs::GetSourceProperty(source, name, status);
+}
+
+CS_Property* CS_EnumerateSourceProperties(CS_Source source, int* count,
+                                          CS_Status* status) {
+  wpi::SmallVector<CS_Property, 32> buf;
+  auto vec = cs::EnumerateSourceProperties(source, buf, status);
+  CS_Property* out = static_cast<CS_Property*>(
+      wpi::safe_malloc(vec.size() * sizeof(CS_Property)));
+  *count = vec.size();
+  std::copy(vec.begin(), vec.end(), out);
+  return out;
+}
+
+void CS_GetSourceVideoMode(CS_Source source, CS_VideoMode* mode,
+                           CS_Status* status) {
+  *mode = cs::GetSourceVideoMode(source, status);
+}
+
+CS_Bool CS_SetSourceVideoMode(CS_Source source, const CS_VideoMode* mode,
+                              CS_Status* status) {
+  return cs::SetSourceVideoMode(
+      source, static_cast<const cs::VideoMode&>(*mode), status);
+}
+
+CS_Bool CS_SetSourceVideoModeDiscrete(CS_Source source,
+                                      enum CS_PixelFormat pixelFormat,
+                                      int width, int height, int fps,
+                                      CS_Status* status) {
+  return cs::SetSourceVideoMode(
+      source,
+      cs::VideoMode{static_cast<cs::VideoMode::PixelFormat>(
+                        static_cast<int>(pixelFormat)),
+                    width, height, fps},
+      status);
+}
+
+CS_Bool CS_SetSourcePixelFormat(CS_Source source,
+                                enum CS_PixelFormat pixelFormat,
+                                CS_Status* status) {
+  return cs::SetSourcePixelFormat(
+      source,
+      static_cast<cs::VideoMode::PixelFormat>(static_cast<int>(pixelFormat)),
+      status);
+}
+
+CS_Bool CS_SetSourceResolution(CS_Source source, int width, int height,
+                               CS_Status* status) {
+  return cs::SetSourceResolution(source, width, height, status);
+}
+
+CS_Bool CS_SetSourceFPS(CS_Source source, int fps, CS_Status* status) {
+  return cs::SetSourceFPS(source, fps, status);
+}
+
+CS_Bool CS_SetSourceConfigJson(CS_Source source, const char* config,
+                               CS_Status* status) {
+  return cs::SetSourceConfigJson(source, config, status);
+}
+
+char* CS_GetSourceConfigJson(CS_Source source, CS_Status* status) {
+  return cs::ConvertToC(cs::GetSourceConfigJson(source, status));
+}
+
+CS_VideoMode* CS_EnumerateSourceVideoModes(CS_Source source, int* count,
+                                           CS_Status* status) {
+  auto vec = cs::EnumerateSourceVideoModes(source, status);
+  CS_VideoMode* out = static_cast<CS_VideoMode*>(
+      wpi::safe_malloc(vec.size() * sizeof(CS_VideoMode)));
+  *count = vec.size();
+  std::copy(vec.begin(), vec.end(), out);
+  return out;
+}
+
+CS_Sink* CS_EnumerateSourceSinks(CS_Source source, int* count,
+                                 CS_Status* status) {
+  wpi::SmallVector<CS_Sink, 32> buf;
+  auto handles = cs::EnumerateSourceSinks(source, buf, status);
+  CS_Sink* sinks =
+      static_cast<CS_Sink*>(wpi::safe_malloc(handles.size() * sizeof(CS_Sink)));
+  *count = handles.size();
+  std::copy(handles.begin(), handles.end(), sinks);
+  return sinks;
+}
+
+CS_Source CS_CopySource(CS_Source source, CS_Status* status) {
+  return cs::CopySource(source, status);
+}
+
+void CS_ReleaseSource(CS_Source source, CS_Status* status) {
+  return cs::ReleaseSource(source, status);
+}
+
+void CS_SetCameraBrightness(CS_Source source, int brightness,
+                            CS_Status* status) {
+  return cs::SetCameraBrightness(source, brightness, status);
+}
+
+int CS_GetCameraBrightness(CS_Source source, CS_Status* status) {
+  return cs::GetCameraBrightness(source, status);
+}
+
+void CS_SetCameraWhiteBalanceAuto(CS_Source source, CS_Status* status) {
+  return cs::SetCameraWhiteBalanceAuto(source, status);
+}
+
+void CS_SetCameraWhiteBalanceHoldCurrent(CS_Source source, CS_Status* status) {
+  return cs::SetCameraWhiteBalanceHoldCurrent(source, status);
+}
+
+void CS_SetCameraWhiteBalanceManual(CS_Source source, int value,
+                                    CS_Status* status) {
+  return cs::SetCameraWhiteBalanceManual(source, value, status);
+}
+
+void CS_SetCameraExposureAuto(CS_Source source, CS_Status* status) {
+  return cs::SetCameraExposureAuto(source, status);
+}
+
+void CS_SetCameraExposureHoldCurrent(CS_Source source, CS_Status* status) {
+  return cs::SetCameraExposureHoldCurrent(source, status);
+}
+
+void CS_SetCameraExposureManual(CS_Source source, int value,
+                                CS_Status* status) {
+  return cs::SetCameraExposureManual(source, value, status);
+}
+
+CS_SinkKind CS_GetSinkKind(CS_Sink sink, CS_Status* status) {
+  return cs::GetSinkKind(sink, status);
+}
+
+char* CS_GetSinkName(CS_Sink sink, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSinkName(sink, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+char* CS_GetSinkDescription(CS_Sink sink, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSinkDescription(sink, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+CS_Property CS_GetSinkProperty(CS_Sink sink, const char* name,
+                               CS_Status* status) {
+  return cs::GetSinkProperty(sink, name, status);
+}
+
+CS_Property* CS_EnumerateSinkProperties(CS_Sink sink, int* count,
+                                        CS_Status* status) {
+  wpi::SmallVector<CS_Property, 32> buf;
+  auto vec = cs::EnumerateSinkProperties(sink, buf, status);
+  CS_Property* out = static_cast<CS_Property*>(
+      wpi::safe_malloc(vec.size() * sizeof(CS_Property)));
+  *count = vec.size();
+  std::copy(vec.begin(), vec.end(), out);
+  return out;
+}
+
+CS_Bool CS_SetSinkConfigJson(CS_Sink sink, const char* config,
+                             CS_Status* status) {
+  return cs::SetSinkConfigJson(sink, config, status);
+}
+
+char* CS_GetSinkConfigJson(CS_Sink sink, CS_Status* status) {
+  return cs::ConvertToC(cs::GetSinkConfigJson(sink, status));
+}
+
+void CS_SetSinkSource(CS_Sink sink, CS_Source source, CS_Status* status) {
+  return cs::SetSinkSource(sink, source, status);
+}
+
+CS_Source CS_GetSinkSource(CS_Sink sink, CS_Status* status) {
+  return cs::GetSinkSource(sink, status);
+}
+
+CS_Property CS_GetSinkSourceProperty(CS_Sink sink, const char* name,
+                                     CS_Status* status) {
+  return cs::GetSinkSourceProperty(sink, name, status);
+}
+
+CS_Sink CS_CopySink(CS_Sink sink, CS_Status* status) {
+  return cs::CopySink(sink, status);
+}
+
+void CS_ReleaseSink(CS_Sink sink, CS_Status* status) {
+  return cs::ReleaseSink(sink, status);
+}
+
+void CS_SetListenerOnStart(void (*onStart)(void* data), void* data) {
+  cs::SetListenerOnStart([=]() { onStart(data); });
+}
+
+void CS_SetListenerOnExit(void (*onExit)(void* data), void* data) {
+  cs::SetListenerOnExit([=]() { onExit(data); });
+}
+
+CS_Listener CS_AddListener(void* data,
+                           void (*callback)(void* data, const CS_Event* event),
+                           int eventMask, int immediateNotify,
+                           CS_Status* status) {
+  return cs::AddListener(
+      [=](const cs::RawEvent& rawEvent) {
+        CS_Event event;
+        event.kind = static_cast<CS_EventKind>(static_cast<int>(rawEvent.kind));
+        event.source = rawEvent.sourceHandle;
+        event.sink = rawEvent.sinkHandle;
+        event.name = rawEvent.name.c_str();
+        event.mode = rawEvent.mode;
+        event.property = rawEvent.propertyHandle;
+        event.propertyKind = rawEvent.propertyKind;
+        event.value = rawEvent.value;
+        event.valueStr = rawEvent.valueStr.c_str();
+        callback(data, &event);
+      },
+      eventMask, immediateNotify, status);
+}
+
+void CS_RemoveListener(CS_Listener handle, CS_Status* status) {
+  return cs::RemoveListener(handle, status);
+}
+
+int CS_NotifierDestroyed(void) { return cs::NotifierDestroyed(); }
+
+void CS_SetTelemetryPeriod(double seconds) { cs::SetTelemetryPeriod(seconds); }
+
+double CS_GetTelemetryElapsedTime(void) {
+  return cs::GetTelemetryElapsedTime();
+}
+
+int64_t CS_GetTelemetryValue(CS_Handle handle, CS_TelemetryKind kind,
+                             CS_Status* status) {
+  return cs::GetTelemetryValue(handle, kind, status);
+}
+
+double CS_GetTelemetryAverageValue(CS_Handle handle, CS_TelemetryKind kind,
+                                   CS_Status* status) {
+  return cs::GetTelemetryAverageValue(handle, kind, status);
+}
+
+void CS_SetLogger(CS_LogFunc func, unsigned int min_level) {
+  cs::SetLogger(func, min_level);
+}
+
+void CS_SetDefaultLogger(unsigned int min_level) {
+  cs::SetDefaultLogger(min_level);
+}
+
+void CS_Shutdown(void) { cs::Shutdown(); }
+
+CS_Source* CS_EnumerateSources(int* count, CS_Status* status) {
+  wpi::SmallVector<CS_Source, 32> buf;
+  auto handles = cs::EnumerateSourceHandles(buf, status);
+  CS_Source* sources = static_cast<CS_Source*>(
+      wpi::safe_malloc(handles.size() * sizeof(CS_Source)));
+  *count = handles.size();
+  std::copy(handles.begin(), handles.end(), sources);
+  return sources;
+}
+
+void CS_ReleaseEnumeratedSources(CS_Source* sources, int count) {
+  if (!sources) return;
+  for (int i = 0; i < count; ++i) {
+    CS_Status status = 0;
+    if (sources[i] != 0) cs::ReleaseSource(sources[i], &status);
+  }
+  std::free(sources);
+}
+
+CS_Sink* CS_EnumerateSinks(int* count, CS_Status* status) {
+  wpi::SmallVector<CS_Sink, 32> buf;
+  auto handles = cs::EnumerateSinkHandles(buf, status);
+  CS_Sink* sinks =
+      static_cast<CS_Sink*>(wpi::safe_malloc(handles.size() * sizeof(CS_Sink)));
+  *count = handles.size();
+  std::copy(handles.begin(), handles.end(), sinks);
+  return sinks;
+}
+
+void CS_ReleaseEnumeratedSinks(CS_Sink* sinks, int count) {
+  if (!sinks) return;
+  for (int i = 0; i < count; ++i) {
+    CS_Status status = 0;
+    if (sinks[i] != 0) cs::ReleaseSink(sinks[i], &status);
+  }
+  std::free(sinks);
+}
+
+void CS_FreeString(char* str) { std::free(str); }
+
+void CS_FreeEnumPropertyChoices(char** choices, int count) {
+  if (!choices) return;
+  for (int i = 0; i < count; ++i) std::free(choices[i]);
+  std::free(choices);
+}
+
+void CS_FreeEnumeratedProperties(CS_Property* properties, int count) {
+  std::free(properties);
+}
+
+void CS_FreeEnumeratedVideoModes(CS_VideoMode* modes, int count) {
+  std::free(modes);
+}
+
+char* CS_GetHostname() { return cs::ConvertToC(cs::GetHostname()); }
+
+char** CS_GetNetworkInterfaces(int* count) {
+  auto interfaces = cs::GetNetworkInterfaces();
+  char** out =
+      static_cast<char**>(wpi::safe_malloc(interfaces.size() * sizeof(char*)));
+  *count = interfaces.size();
+  for (size_t i = 0; i < interfaces.size(); ++i)
+    out[i] = cs::ConvertToC(interfaces[i]);
+  return out;
+}
+
+void CS_FreeNetworkInterfaces(char** interfaces, int count) {
+  if (!interfaces) return;
+  for (int i = 0; i < count; ++i) std::free(interfaces[i]);
+  std::free(interfaces);
+}
+
+void CS_AllocateRawFrameData(CS_RawFrame* frame, int requestedSize) {
+  if (frame->dataLength >= requestedSize) return;
+  if (frame->data) {
+    frame->data =
+        static_cast<char*>(wpi::safe_realloc(frame->data, requestedSize));
+  } else {
+    frame->data = static_cast<char*>(wpi::safe_malloc(requestedSize));
+  }
+  frame->dataLength = requestedSize;
+}
+
+void CS_FreeRawFrameData(CS_RawFrame* frame) {
+  if (frame->data) {
+    std::free(frame->data);
+    frame->data = nullptr;
+    frame->dataLength = 0;
+  }
+}
+
+}  // extern "C"
diff --git a/cscore/src/main/native/cpp/cscore_cpp.cpp b/cscore/src/main/native/cpp/cscore_cpp.cpp
new file mode 100644
index 0000000..d49fb04
--- /dev/null
+++ b/cscore/src/main/native/cpp/cscore_cpp.cpp
@@ -0,0 +1,765 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "cscore_cpp.h"
+
+#include <wpi/SmallString.h>
+#include <wpi/hostname.h>
+#include <wpi/json.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "Log.h"
+#include "NetworkListener.h"
+#include "Notifier.h"
+#include "PropertyContainer.h"
+#include "SinkImpl.h"
+#include "SourceImpl.h"
+#include "Telemetry.h"
+
+using namespace cs;
+
+static std::shared_ptr<PropertyContainer> GetPropertyContainer(
+    CS_Property propertyHandle, int* propertyIndex, CS_Status* status) {
+  std::shared_ptr<PropertyContainer> container;
+  Handle handle{propertyHandle};
+  if (handle.IsType(Handle::kProperty)) {
+    int i = handle.GetParentIndex();
+    auto data = Instance::GetInstance().GetSource(Handle{i, Handle::kSource});
+    if (!data) {
+      *status = CS_INVALID_HANDLE;
+      return nullptr;
+    }
+    container = data->source;
+  } else if (handle.IsType(Handle::kSinkProperty)) {
+    int i = handle.GetParentIndex();
+    auto data = Instance::GetInstance().GetSink(Handle{i, Handle::kSink});
+    if (!data) {
+      *status = CS_INVALID_HANDLE;
+      return nullptr;
+    }
+    container = data->sink;
+  } else {
+    *status = CS_INVALID_HANDLE;
+    return nullptr;
+  }
+  *propertyIndex = handle.GetIndex();
+  return container;
+}
+
+namespace cs {
+
+//
+// Property Functions
+//
+
+CS_PropertyKind GetPropertyKind(CS_Property property, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return CS_PROP_NONE;
+  return container->GetPropertyKind(propertyIndex);
+}
+
+std::string GetPropertyName(CS_Property property, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return std::string{};
+  return container->GetPropertyName(propertyIndex, buf, status);
+}
+
+wpi::StringRef GetPropertyName(CS_Property property,
+                               wpi::SmallVectorImpl<char>& buf,
+                               CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return wpi::StringRef{};
+  return container->GetPropertyName(propertyIndex, buf, status);
+}
+
+int GetProperty(CS_Property property, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return false;
+  return container->GetProperty(propertyIndex, status);
+}
+
+void SetProperty(CS_Property property, int value, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return;
+  container->SetProperty(propertyIndex, value, status);
+}
+
+int GetPropertyMin(CS_Property property, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return 0.0;
+  return container->GetPropertyMin(propertyIndex, status);
+}
+
+int GetPropertyMax(CS_Property property, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return 0.0;
+  return container->GetPropertyMax(propertyIndex, status);
+}
+
+int GetPropertyStep(CS_Property property, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return 0.0;
+  return container->GetPropertyStep(propertyIndex, status);
+}
+
+int GetPropertyDefault(CS_Property property, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return 0.0;
+  return container->GetPropertyDefault(propertyIndex, status);
+}
+
+std::string GetStringProperty(CS_Property property, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return std::string{};
+  return container->GetStringProperty(propertyIndex, buf, status);
+}
+
+wpi::StringRef GetStringProperty(CS_Property property,
+                                 wpi::SmallVectorImpl<char>& buf,
+                                 CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return wpi::StringRef{};
+  return container->GetStringProperty(propertyIndex, buf, status);
+}
+
+void SetStringProperty(CS_Property property, const wpi::Twine& value,
+                       CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return;
+  container->SetStringProperty(propertyIndex, value, status);
+}
+
+std::vector<std::string> GetEnumPropertyChoices(CS_Property property,
+                                                CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return std::vector<std::string>{};
+  return container->GetEnumPropertyChoices(propertyIndex, status);
+}
+
+//
+// Source Functions
+//
+
+CS_SourceKind GetSourceKind(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return CS_SOURCE_UNKNOWN;
+  }
+  return data->kind;
+}
+
+std::string GetSourceName(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return data->source->GetName();
+}
+
+wpi::StringRef GetSourceName(CS_Source source, wpi::SmallVectorImpl<char>& buf,
+                             CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::StringRef{};
+  }
+  return data->source->GetName();
+}
+
+std::string GetSourceDescription(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  wpi::SmallString<128> buf;
+  return data->source->GetDescription(buf);
+}
+
+wpi::StringRef GetSourceDescription(CS_Source source,
+                                    wpi::SmallVectorImpl<char>& buf,
+                                    CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::StringRef{};
+  }
+  return data->source->GetDescription(buf);
+}
+
+uint64_t GetSourceLastFrameTime(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return data->source->GetCurFrameTime();
+}
+
+void SetSourceConnectionStrategy(CS_Source source,
+                                 CS_ConnectionStrategy strategy,
+                                 CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetConnectionStrategy(strategy);
+}
+
+bool IsSourceConnected(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->IsConnected();
+}
+
+bool IsSourceEnabled(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->IsEnabled();
+}
+
+CS_Property GetSourceProperty(CS_Source source, const wpi::Twine& name,
+                              CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  int property = data->source->GetPropertyIndex(name);
+  if (property < 0) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return Handle{source, property, Handle::kProperty};
+}
+
+wpi::ArrayRef<CS_Property> EnumerateSourceProperties(
+    CS_Source source, wpi::SmallVectorImpl<CS_Property>& vec,
+    CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  wpi::SmallVector<int, 32> properties_buf;
+  for (auto property :
+       data->source->EnumerateProperties(properties_buf, status))
+    vec.push_back(Handle{source, property, Handle::kProperty});
+  return vec;
+}
+
+VideoMode GetSourceVideoMode(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return VideoMode{};
+  }
+  return data->source->GetVideoMode(status);
+}
+
+bool SetSourceVideoMode(CS_Source source, const VideoMode& mode,
+                        CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->SetVideoMode(mode, status);
+}
+
+bool SetSourcePixelFormat(CS_Source source, VideoMode::PixelFormat pixelFormat,
+                          CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->SetPixelFormat(pixelFormat, status);
+}
+
+bool SetSourceResolution(CS_Source source, int width, int height,
+                         CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->SetResolution(width, height, status);
+}
+
+bool SetSourceFPS(CS_Source source, int fps, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->SetFPS(fps, status);
+}
+
+bool SetSourceConfigJson(CS_Source source, wpi::StringRef config,
+                         CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->SetConfigJson(config, status);
+}
+
+bool SetSourceConfigJson(CS_Source source, const wpi::json& config,
+                         CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->SetConfigJson(config, status);
+}
+
+std::string GetSourceConfigJson(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return data->source->GetConfigJson(status);
+}
+
+wpi::json GetSourceConfigJsonObject(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::json{};
+  }
+  return data->source->GetConfigJsonObject(status);
+}
+
+std::vector<VideoMode> EnumerateSourceVideoModes(CS_Source source,
+                                                 CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::vector<VideoMode>{};
+  }
+  return data->source->EnumerateVideoModes(status);
+}
+
+wpi::ArrayRef<CS_Sink> EnumerateSourceSinks(CS_Source source,
+                                            wpi::SmallVectorImpl<CS_Sink>& vec,
+                                            CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  auto data = inst.GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::ArrayRef<CS_Sink>{};
+  }
+  return inst.EnumerateSourceSinks(source, vec);
+}
+
+CS_Source CopySource(CS_Source source, CS_Status* status) {
+  if (source == 0) return 0;
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  data->refCount++;
+  return source;
+}
+
+void ReleaseSource(CS_Source source, CS_Status* status) {
+  if (source == 0) return;
+  auto& inst = Instance::GetInstance();
+  auto data = inst.GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  if (data->refCount-- == 0) inst.DestroySource(source);
+}
+
+//
+// Camera Source Common Property Fuctions
+//
+
+void SetCameraBrightness(CS_Source source, int brightness, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetBrightness(brightness, status);
+}
+
+int GetCameraBrightness(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return data->source->GetBrightness(status);
+}
+
+void SetCameraWhiteBalanceAuto(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetWhiteBalanceAuto(status);
+}
+
+void SetCameraWhiteBalanceHoldCurrent(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetWhiteBalanceHoldCurrent(status);
+}
+
+void SetCameraWhiteBalanceManual(CS_Source source, int value,
+                                 CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetWhiteBalanceManual(value, status);
+}
+
+void SetCameraExposureAuto(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetExposureAuto(status);
+}
+
+void SetCameraExposureHoldCurrent(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetExposureHoldCurrent(status);
+}
+
+void SetCameraExposureManual(CS_Source source, int value, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetExposureManual(value, status);
+}
+
+//
+// Sink Functions
+//
+
+CS_SinkKind GetSinkKind(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return CS_SINK_UNKNOWN;
+  }
+  return data->kind;
+}
+
+std::string GetSinkName(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return data->sink->GetName();
+}
+
+wpi::StringRef GetSinkName(CS_Sink sink, wpi::SmallVectorImpl<char>& buf,
+                           CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::StringRef{};
+  }
+  return data->sink->GetName();
+}
+
+std::string GetSinkDescription(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  wpi::SmallString<128> buf;
+  return data->sink->GetDescription(buf);
+}
+
+wpi::StringRef GetSinkDescription(CS_Sink sink, wpi::SmallVectorImpl<char>& buf,
+                                  CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::StringRef{};
+  }
+  return data->sink->GetDescription(buf);
+}
+
+CS_Property GetSinkProperty(CS_Sink sink, const wpi::Twine& name,
+                            CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  int property = data->sink->GetPropertyIndex(name);
+  if (property < 0) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return Handle{sink, property, Handle::kSinkProperty};
+}
+
+wpi::ArrayRef<CS_Property> EnumerateSinkProperties(
+    CS_Sink sink, wpi::SmallVectorImpl<CS_Property>& vec, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  wpi::SmallVector<int, 32> properties_buf;
+  for (auto property : data->sink->EnumerateProperties(properties_buf, status))
+    vec.push_back(Handle{sink, property, Handle::kSinkProperty});
+  return vec;
+}
+
+bool SetSinkConfigJson(CS_Sink sink, wpi::StringRef config, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->sink->SetConfigJson(config, status);
+}
+
+bool SetSinkConfigJson(CS_Sink sink, const wpi::json& config,
+                       CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->sink->SetConfigJson(config, status);
+}
+
+std::string GetSinkConfigJson(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return data->sink->GetConfigJson(status);
+}
+
+wpi::json GetSinkConfigJsonObject(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::json{};
+  }
+  return data->sink->GetConfigJsonObject(status);
+}
+
+void SetSinkSource(CS_Sink sink, CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  if (source == 0) {
+    data->sink->SetSource(nullptr);
+  } else {
+    auto sourceData = Instance::GetInstance().GetSource(source);
+    if (!sourceData) {
+      *status = CS_INVALID_HANDLE;
+      return;
+    }
+    data->sink->SetSource(sourceData->source);
+  }
+  data->sourceHandle.store(source);
+  Instance::GetInstance().notifier.NotifySinkSourceChanged(
+      data->sink->GetName(), sink, source);
+}
+
+CS_Source GetSinkSource(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return data->sourceHandle.load();
+}
+
+CS_Property GetSinkSourceProperty(CS_Sink sink, const wpi::Twine& name,
+                                  CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return GetSourceProperty(data->sourceHandle.load(), name, status);
+}
+
+CS_Sink CopySink(CS_Sink sink, CS_Status* status) {
+  if (sink == 0) return 0;
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  data->refCount++;
+  return sink;
+}
+
+void ReleaseSink(CS_Sink sink, CS_Status* status) {
+  if (sink == 0) return;
+  auto& inst = Instance::GetInstance();
+  auto data = inst.GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  if (data->refCount-- == 0) inst.DestroySink(sink);
+}
+
+//
+// Listener Functions
+//
+
+void SetListenerOnStart(std::function<void()> onStart) {
+  Instance::GetInstance().notifier.SetOnStart(onStart);
+}
+
+void SetListenerOnExit(std::function<void()> onExit) {
+  Instance::GetInstance().notifier.SetOnExit(onExit);
+}
+
+CS_Listener AddListener(std::function<void(const RawEvent& event)> callback,
+                        int eventMask, bool immediateNotify,
+                        CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  int uid = inst.notifier.AddListener(callback, eventMask);
+  if ((eventMask & CS_NETWORK_INTERFACES_CHANGED) != 0) {
+    // start network interface event listener
+    inst.networkListener.Start();
+    if (immediateNotify) inst.notifier.NotifyNetworkInterfacesChanged();
+  }
+  if (immediateNotify) {
+    // TODO
+  }
+  return Handle{uid, Handle::kListener};
+}
+
+void RemoveListener(CS_Listener handle, CS_Status* status) {
+  int uid = Handle{handle}.GetTypedIndex(Handle::kListener);
+  if (uid < 0) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  Instance::GetInstance().notifier.RemoveListener(uid);
+}
+
+bool NotifierDestroyed() { return Notifier::destroyed(); }
+
+//
+// Telemetry Functions
+//
+void SetTelemetryPeriod(double seconds) {
+  auto& inst = Instance::GetInstance();
+  inst.telemetry.Start();
+  inst.telemetry.SetPeriod(seconds);
+}
+
+double GetTelemetryElapsedTime() {
+  return Instance::GetInstance().telemetry.GetElapsedTime();
+}
+
+int64_t GetTelemetryValue(CS_Handle handle, CS_TelemetryKind kind,
+                          CS_Status* status) {
+  return Instance::GetInstance().telemetry.GetValue(handle, kind, status);
+}
+
+double GetTelemetryAverageValue(CS_Handle handle, CS_TelemetryKind kind,
+                                CS_Status* status) {
+  return Instance::GetInstance().telemetry.GetAverageValue(handle, kind,
+                                                           status);
+}
+
+//
+// Logging Functions
+//
+void SetLogger(LogFunc func, unsigned int min_level) {
+  auto& logger = Instance::GetInstance().logger;
+  logger.SetLogger(func);
+  logger.set_min_level(min_level);
+}
+
+void SetDefaultLogger(unsigned int min_level) {
+  auto& inst = Instance::GetInstance();
+  inst.SetDefaultLogger();
+  inst.logger.set_min_level(min_level);
+}
+
+//
+// Shutdown Function
+//
+void Shutdown() { Instance::GetInstance().Shutdown(); }
+
+//
+// Utility Functions
+//
+
+wpi::ArrayRef<CS_Source> EnumerateSourceHandles(
+    wpi::SmallVectorImpl<CS_Source>& vec, CS_Status* status) {
+  return Instance::GetInstance().EnumerateSourceHandles(vec);
+}
+
+wpi::ArrayRef<CS_Sink> EnumerateSinkHandles(wpi::SmallVectorImpl<CS_Sink>& vec,
+                                            CS_Status* status) {
+  return Instance::GetInstance().EnumerateSinkHandles(vec);
+}
+
+std::string GetHostname() { return wpi::GetHostname(); }
+
+}  // namespace cs
diff --git a/cscore/src/main/native/cpp/cscore_oo.cpp b/cscore/src/main/native/cpp/cscore_oo.cpp
new file mode 100644
index 0000000..f42ed5a
--- /dev/null
+++ b/cscore/src/main/native/cpp/cscore_oo.cpp
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "cscore_oo.h"
+
+#include <wpi/json.h>
+
+using namespace cs;
+
+wpi::json VideoSource::GetConfigJsonObject() const {
+  m_status = 0;
+  return GetSourceConfigJsonObject(m_handle, &m_status);
+}
+
+wpi::json VideoSink::GetConfigJsonObject() const {
+  m_status = 0;
+  return GetSinkConfigJsonObject(m_handle, &m_status);
+}
+
+std::vector<VideoProperty> VideoSource::EnumerateProperties() const {
+  wpi::SmallVector<CS_Property, 32> handles_buf;
+  CS_Status status = 0;
+  auto handles = EnumerateSourceProperties(m_handle, handles_buf, &status);
+
+  std::vector<VideoProperty> properties;
+  properties.reserve(handles.size());
+  for (CS_Property handle : handles)
+    properties.emplace_back(VideoProperty{handle});
+  return properties;
+}
+
+std::vector<VideoSink> VideoSource::EnumerateSinks() {
+  wpi::SmallVector<CS_Sink, 16> handles_buf;
+  CS_Status status = 0;
+  auto handles = EnumerateSourceSinks(m_handle, handles_buf, &status);
+
+  std::vector<VideoSink> sinks;
+  sinks.reserve(handles.size());
+  for (int handle : handles) sinks.emplace_back(VideoSink{handle});
+  return sinks;
+}
+
+std::vector<VideoSource> VideoSource::EnumerateSources() {
+  wpi::SmallVector<CS_Source, 16> handles_buf;
+  CS_Status status = 0;
+  auto handles = ::cs::EnumerateSourceHandles(handles_buf, &status);
+
+  std::vector<VideoSource> sources;
+  sources.reserve(handles.size());
+  for (int handle : handles) sources.emplace_back(VideoSource{handle});
+  return sources;
+}
+
+std::vector<VideoProperty> VideoSink::EnumerateProperties() const {
+  wpi::SmallVector<CS_Property, 32> handles_buf;
+  CS_Status status = 0;
+  auto handles = EnumerateSinkProperties(m_handle, handles_buf, &status);
+
+  std::vector<VideoProperty> properties;
+  properties.reserve(handles.size());
+  for (CS_Property handle : handles)
+    properties.emplace_back(VideoProperty{handle});
+  return properties;
+}
+
+std::vector<VideoSink> VideoSink::EnumerateSinks() {
+  wpi::SmallVector<CS_Sink, 16> handles_buf;
+  CS_Status status = 0;
+  auto handles = ::cs::EnumerateSinkHandles(handles_buf, &status);
+
+  std::vector<VideoSink> sinks;
+  sinks.reserve(handles.size());
+  for (int handle : handles) sinks.emplace_back(VideoSink{handle});
+  return sinks;
+}
diff --git a/cscore/src/main/native/cpp/default_init_allocator.h b/cscore/src/main/native/cpp/default_init_allocator.h
new file mode 100644
index 0000000..089cac7
--- /dev/null
+++ b/cscore/src/main/native/cpp/default_init_allocator.h
@@ -0,0 +1,41 @@
+// From:
+// http://stackoverflow.com/questions/21028299/is-this-behavior-of-vectorresizesize-type-n-under-c11-and-boost-container
+// Credits: Casey and Howard Hinnant
+
+#ifndef CSCORE_DEFAULT_INIT_ALLOCATOR_H_
+#define CSCORE_DEFAULT_INIT_ALLOCATOR_H_
+
+#include <memory>
+#include <utility>
+
+namespace cs {
+
+// Allocator adaptor that interposes construct() calls to
+// convert value initialization into default initialization.
+template <typename T, typename A = std::allocator<T>>
+class default_init_allocator : public A {
+  using a_t = std::allocator_traits<A>;
+
+ public:
+  template <typename U>
+  struct rebind {
+    using other =
+        default_init_allocator<U, typename a_t::template rebind_alloc<U>>;
+  };
+
+  using A::A;
+
+  template <typename U>
+  void construct(U* ptr) noexcept(
+      std::is_nothrow_default_constructible<U>::value) {
+    ::new (static_cast<void*>(ptr)) U;
+  }
+  template <typename U, typename... Args>
+  void construct(U* ptr, Args&&... args) {
+    a_t::construct(static_cast<A&>(*this), ptr, std::forward<Args>(args)...);
+  }
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_DEFAULT_INIT_ALLOCATOR_H_
diff --git a/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp b/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp
new file mode 100644
index 0000000..52a0fea
--- /dev/null
+++ b/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp
@@ -0,0 +1,2030 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <exception>
+
+#include <opencv2/core/core.hpp>
+#include <wpi/SmallString.h>
+#include <wpi/jni_util.h>
+#include <wpi/raw_ostream.h>
+
+#include "cscore_cpp.h"
+#include "cscore_cv.h"
+#include "cscore_raw.h"
+#include "edu_wpi_cscore_CameraServerJNI.h"
+
+namespace cv {
+class Mat;
+}  // namespace cv
+
+using namespace wpi::java;
+
+//
+// Globals and load/unload
+//
+
+// Used for callback.
+static JavaVM* jvm = nullptr;
+static JClass usbCameraInfoCls;
+static JClass videoModeCls;
+static JClass videoEventCls;
+static JClass rawFrameCls;
+static JException videoEx;
+static JException nullPointerEx;
+static JException unsupportedEx;
+static JException exceptionEx;
+// Thread-attached environment for listener callbacks.
+static JNIEnv* listenerEnv = nullptr;
+
+static const JClassInit classes[] = {
+    {"edu/wpi/cscore/UsbCameraInfo", &usbCameraInfoCls},
+    {"edu/wpi/cscore/VideoMode", &videoModeCls},
+    {"edu/wpi/cscore/VideoEvent", &videoEventCls},
+    {"edu/wpi/cscore/raw/RawFrame", &rawFrameCls}};
+
+static const JExceptionInit exceptions[] = {
+    {"edu/wpi/cscore/VideoException", &videoEx},
+    {"java/lang/NullPointerException", &nullPointerEx},
+    {"java/lang/UnsupportedOperationException", &unsupportedEx},
+    {"java/lang/Exception", &exceptionEx}};
+
+static void ListenerOnStart() {
+  if (!jvm) return;
+  JNIEnv* env;
+  JavaVMAttachArgs args;
+  args.version = JNI_VERSION_1_2;
+  args.name = const_cast<char*>("CSListener");
+  args.group = nullptr;
+  if (jvm->AttachCurrentThreadAsDaemon(reinterpret_cast<void**>(&env), &args) !=
+      JNI_OK)
+    return;
+  if (!env || !env->functions) return;
+  listenerEnv = env;
+}
+
+static void ListenerOnExit() {
+  listenerEnv = nullptr;
+  if (!jvm) return;
+  jvm->DetachCurrentThread();
+}
+
+/// throw java exception
+static void ThrowJavaException(JNIEnv* env, const std::exception* e) {
+  wpi::SmallString<128> what;
+  jclass je = 0;
+
+  if (e) {
+    const char* exception_type = "std::exception";
+
+    if (dynamic_cast<const cv::Exception*>(e)) {
+      exception_type = "cv::Exception";
+      je = env->FindClass("org/opencv/core/CvException");
+    }
+
+    what = exception_type;
+    what += ": ";
+    what += e->what();
+  } else {
+    what = "unknown exception";
+  }
+
+  if (!je) je = exceptionEx;
+  env->ThrowNew(je, what.c_str());
+}
+
+extern "C" {
+
+JNIEXPORT jint JNICALL JNI_OnLoad(JavaVM* vm, void* reserved) {
+  jvm = vm;
+
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return JNI_ERR;
+
+  // Cache references to classes
+  for (auto& c : classes) {
+    *c.cls = JClass(env, c.name);
+    if (!*c.cls) return JNI_ERR;
+  }
+
+  for (auto& c : exceptions) {
+    *c.cls = JException(env, c.name);
+    if (!*c.cls) return JNI_ERR;
+  }
+
+  // Initial configuration of listener start/exit
+  cs::SetListenerOnStart(ListenerOnStart);
+  cs::SetListenerOnExit(ListenerOnExit);
+
+  return JNI_VERSION_1_6;
+}
+
+JNIEXPORT void JNICALL JNI_OnUnload(JavaVM* vm, void* reserved) {
+  cs::Shutdown();
+
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return;
+  // Delete global references
+  for (auto& c : classes) {
+    c.cls->free(env);
+  }
+  for (auto& c : exceptions) {
+    c.cls->free(env);
+  }
+  jvm = nullptr;
+}
+
+}  // extern "C"
+
+//
+// Helper class to create and clean up a global reference
+//
+template <typename T>
+class JCSGlobal {
+ public:
+  JCSGlobal(JNIEnv* env, T obj)
+      : m_obj(static_cast<T>(env->NewGlobalRef(obj))) {}
+  ~JCSGlobal() {
+    if (!jvm || cs::NotifierDestroyed()) return;
+    JNIEnv* env;
+    bool attached = false;
+    // don't attach and de-attach if already attached to a thread.
+    if (jvm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) ==
+        JNI_EDETACHED) {
+      if (jvm->AttachCurrentThread(reinterpret_cast<void**>(&env), nullptr) !=
+          JNI_OK)
+        return;
+      attached = true;
+    }
+    if (!env || !env->functions) return;
+    env->DeleteGlobalRef(m_obj);
+    if (attached) jvm->DetachCurrentThread();
+  }
+  operator T() { return m_obj; }
+  T obj() { return m_obj; }
+
+ private:
+  T m_obj;
+};
+
+static void ReportError(JNIEnv* env, CS_Status status) {
+  if (status == CS_OK) return;
+  wpi::SmallString<64> msg;
+  switch (status) {
+    case CS_PROPERTY_WRITE_FAILED:
+      msg = "property write failed";
+      break;
+    case CS_INVALID_HANDLE:
+      msg = "invalid handle";
+      break;
+    case CS_WRONG_HANDLE_SUBTYPE:
+      msg = "wrong handle subtype";
+      break;
+    case CS_INVALID_PROPERTY:
+      msg = "invalid property";
+      break;
+    case CS_WRONG_PROPERTY_TYPE:
+      msg = "wrong property type";
+      break;
+    case CS_READ_FAILED:
+      msg = "read failed";
+      break;
+    case CS_SOURCE_IS_DISCONNECTED:
+      msg = "source is disconnected";
+      break;
+    case CS_EMPTY_VALUE:
+      msg = "empty value";
+      break;
+    case CS_BAD_URL:
+      msg = "bad URL";
+      break;
+    case CS_TELEMETRY_NOT_ENABLED:
+      msg = "telemetry not enabled";
+      break;
+    default: {
+      wpi::raw_svector_ostream oss{msg};
+      oss << "unknown error code=" << status;
+      break;
+    }
+  }
+  videoEx.Throw(env, msg);
+}
+
+static inline bool CheckStatus(JNIEnv* env, CS_Status status) {
+  if (status != CS_OK) ReportError(env, status);
+  return status == CS_OK;
+}
+
+static jobject MakeJObject(JNIEnv* env, const cs::UsbCameraInfo& info) {
+  static jmethodID constructor = env->GetMethodID(
+      usbCameraInfoCls, "<init>",
+      "(ILjava/lang/String;Ljava/lang/String;[Ljava/lang/String;II)V");
+  JLocal<jstring> path(env, MakeJString(env, info.path));
+  JLocal<jstring> name(env, MakeJString(env, info.name));
+  JLocal<jobjectArray> otherPaths(env, MakeJStringArray(env, info.otherPaths));
+  return env->NewObject(usbCameraInfoCls, constructor,
+                        static_cast<jint>(info.dev), path.obj(), name.obj(),
+                        otherPaths.obj(), static_cast<jint>(info.vendorId),
+                        static_cast<jint>(info.productId));
+}
+
+static jobject MakeJObject(JNIEnv* env, const cs::VideoMode& videoMode) {
+  static jmethodID constructor =
+      env->GetMethodID(videoModeCls, "<init>", "(IIII)V");
+  return env->NewObject(
+      videoModeCls, constructor, static_cast<jint>(videoMode.pixelFormat),
+      static_cast<jint>(videoMode.width), static_cast<jint>(videoMode.height),
+      static_cast<jint>(videoMode.fps));
+}
+
+static jobject MakeJObject(JNIEnv* env, const cs::RawEvent& event) {
+  static jmethodID constructor =
+      env->GetMethodID(videoEventCls, "<init>",
+                       "(IIILjava/lang/String;IIIIIIILjava/lang/String;)V");
+  JLocal<jstring> name(env, MakeJString(env, event.name));
+  JLocal<jstring> valueStr(env, MakeJString(env, event.valueStr));
+  // clang-format off
+  return env->NewObject(
+      videoEventCls,
+      constructor,
+      static_cast<jint>(event.kind),
+      static_cast<jint>(event.sourceHandle),
+      static_cast<jint>(event.sinkHandle),
+      name.obj(),
+      static_cast<jint>(event.mode.pixelFormat),
+      static_cast<jint>(event.mode.width),
+      static_cast<jint>(event.mode.height),
+      static_cast<jint>(event.mode.fps),
+      static_cast<jint>(event.propertyHandle),
+      static_cast<jint>(event.propertyKind),
+      static_cast<jint>(event.value),
+      valueStr.obj());
+  // clang-format on
+}
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getPropertyKind
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getPropertyKind
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto val = cs::GetPropertyKind(property, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getPropertyName
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getPropertyName
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetPropertyName(property, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getProperty
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getProperty
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto val = cs::GetProperty(property, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setProperty
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setProperty
+  (JNIEnv* env, jclass, jint property, jint value)
+{
+  CS_Status status = 0;
+  cs::SetProperty(property, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getPropertyMin
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getPropertyMin
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto val = cs::GetPropertyMin(property, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getPropertyMax
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getPropertyMax
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto val = cs::GetPropertyMax(property, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getPropertyStep
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getPropertyStep
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto val = cs::GetPropertyStep(property, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getPropertyDefault
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getPropertyDefault
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto val = cs::GetPropertyDefault(property, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getStringProperty
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getStringProperty
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetStringProperty(property, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setStringProperty
+ * Signature: (ILjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setStringProperty
+  (JNIEnv* env, jclass, jint property, jstring value)
+{
+  if (!value) {
+    nullPointerEx.Throw(env, "value cannot be null");
+    return;
+  }
+  CS_Status status = 0;
+  cs::SetStringProperty(property, JStringRef{env, value}.str(), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getEnumPropertyChoices
+ * Signature: (I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getEnumPropertyChoices
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto arr = cs::GetEnumPropertyChoices(property, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJStringArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createUsbCameraDev
+ * Signature: (Ljava/lang/String;I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createUsbCameraDev
+  (JNIEnv* env, jclass, jstring name, jint dev)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateUsbCameraDev(JStringRef{env, name}.str(), dev, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createUsbCameraPath
+ * Signature: (Ljava/lang/String;Ljava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createUsbCameraPath
+  (JNIEnv* env, jclass, jstring name, jstring path)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  if (!path) {
+    nullPointerEx.Throw(env, "path cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateUsbCameraPath(JStringRef{env, name}.str(),
+                                     JStringRef{env, path}.str(), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createHttpCamera
+ * Signature: (Ljava/lang/String;Ljava/lang/String;I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createHttpCamera
+  (JNIEnv* env, jclass, jstring name, jstring url, jint kind)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  if (!url) {
+    nullPointerEx.Throw(env, "url cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateHttpCamera(
+      JStringRef{env, name}.str(), JStringRef{env, url}.str(),
+      static_cast<CS_HttpCameraKind>(kind), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createHttpCameraMulti
+ * Signature: (Ljava/lang/String;[Ljava/lang/Object;I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createHttpCameraMulti
+  (JNIEnv* env, jclass, jstring name, jobjectArray urls, jint kind)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  if (!urls) {
+    nullPointerEx.Throw(env, "urls cannot be null");
+    return 0;
+  }
+  size_t len = env->GetArrayLength(urls);
+  wpi::SmallVector<std::string, 8> vec;
+  vec.reserve(len);
+  for (size_t i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(urls, i))};
+    if (!elem) {
+      // TODO
+      return 0;
+    }
+    vec.push_back(JStringRef{env, elem}.str());
+  }
+  CS_Status status = 0;
+  auto val =
+      cs::CreateHttpCamera(JStringRef{env, name}.str(), vec,
+                           static_cast<CS_HttpCameraKind>(kind), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerCvJNI
+ * Method:    createCvSource
+ * Signature: (Ljava/lang/String;IIII)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerCvJNI_createCvSource
+  (JNIEnv* env, jclass, jstring name, jint pixelFormat, jint width, jint height,
+   jint fps)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateCvSource(
+      JStringRef{env, name}.str(),
+      cs::VideoMode{static_cast<cs::VideoMode::PixelFormat>(pixelFormat),
+                    static_cast<int>(width), static_cast<int>(height),
+                    static_cast<int>(fps)},
+      &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createRawSource
+ * Signature: (Ljava/lang/String;IIII)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createRawSource
+  (JNIEnv* env, jclass, jstring name, jint pixelFormat, jint width, jint height,
+   jint fps)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateRawSource(
+      JStringRef{env, name}.str(),
+      cs::VideoMode{static_cast<cs::VideoMode::PixelFormat>(pixelFormat),
+                    static_cast<int>(width), static_cast<int>(height),
+                    static_cast<int>(fps)},
+      &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceKind
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceKind
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSourceKind(source, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceName
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceName
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSourceName(source, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceDescription
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceDescription
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSourceDescription(source, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceLastFrameTime
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceLastFrameTime
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSourceLastFrameTime(source, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceConnectionStrategy
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceConnectionStrategy
+  (JNIEnv* env, jclass, jint source, jint strategy)
+{
+  CS_Status status = 0;
+  cs::SetSourceConnectionStrategy(
+      source, static_cast<CS_ConnectionStrategy>(strategy), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    isSourceConnected
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_isSourceConnected
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::IsSourceConnected(source, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    isSourceEnabled
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_isSourceEnabled
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::IsSourceEnabled(source, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceProperty
+ * Signature: (ILjava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceProperty
+  (JNIEnv* env, jclass, jint source, jstring name)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val =
+      cs::GetSourceProperty(source, JStringRef{env, name}.str(), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateSourceProperties
+ * Signature: (I)[I
+ */
+JNIEXPORT jintArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateSourceProperties
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  wpi::SmallVector<CS_Property, 32> buf;
+  auto arr = cs::EnumerateSourceProperties(source, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJIntArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceVideoMode
+ * Signature: (I)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceVideoMode
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSourceVideoMode(source, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJObject(env, val);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceVideoMode
+ * Signature: (IIIII)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceVideoMode
+  (JNIEnv* env, jclass, jint source, jint pixelFormat, jint width, jint height,
+   jint fps)
+{
+  CS_Status status = 0;
+  auto val = cs::SetSourceVideoMode(
+      source,
+      cs::VideoMode(static_cast<cs::VideoMode::PixelFormat>(pixelFormat), width,
+                    height, fps),
+      &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourcePixelFormat
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourcePixelFormat
+  (JNIEnv* env, jclass, jint source, jint pixelFormat)
+{
+  CS_Status status = 0;
+  auto val = cs::SetSourcePixelFormat(
+      source, static_cast<cs::VideoMode::PixelFormat>(pixelFormat), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceResolution
+ * Signature: (III)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceResolution
+  (JNIEnv* env, jclass, jint source, jint width, jint height)
+{
+  CS_Status status = 0;
+  auto val = cs::SetSourceResolution(source, width, height, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceFPS
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceFPS
+  (JNIEnv* env, jclass, jint source, jint fps)
+{
+  CS_Status status = 0;
+  auto val = cs::SetSourceFPS(source, fps, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceConfigJson
+ * Signature: (ILjava/lang/String;)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceConfigJson
+  (JNIEnv* env, jclass, jint source, jstring config)
+{
+  CS_Status status = 0;
+  auto val = cs::SetSourceConfigJson(source, JStringRef{env, config}, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceConfigJson
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceConfigJson
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSourceConfigJson(source, &status);
+  CheckStatus(env, status);
+  return MakeJString(env, val);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateSourceVideoModes
+ * Signature: (I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateSourceVideoModes
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto arr = cs::EnumerateSourceVideoModes(source, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  jobjectArray jarr = env->NewObjectArray(arr.size(), videoModeCls, nullptr);
+  if (!jarr) return nullptr;
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> jelem{env, MakeJObject(env, arr[i])};
+    env->SetObjectArrayElement(jarr, i, jelem);
+  }
+  return jarr;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateSourceSinks
+ * Signature: (I)[I
+ */
+JNIEXPORT jintArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateSourceSinks
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  wpi::SmallVector<CS_Sink, 16> buf;
+  auto arr = cs::EnumerateSourceSinks(source, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJIntArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    copySource
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_copySource
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::CopySource(source, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    releaseSource
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_releaseSource
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  cs::ReleaseSource(source, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraBrightness
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraBrightness
+  (JNIEnv* env, jclass, jint source, jint brightness)
+{
+  CS_Status status = 0;
+  cs::SetCameraBrightness(source, brightness, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getCameraBrightness
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getCameraBrightness
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::GetCameraBrightness(source, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraWhiteBalanceAuto
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraWhiteBalanceAuto
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  cs::SetCameraWhiteBalanceAuto(source, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraWhiteBalanceHoldCurrent
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraWhiteBalanceHoldCurrent
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  cs::SetCameraWhiteBalanceHoldCurrent(source, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraWhiteBalanceManual
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraWhiteBalanceManual
+  (JNIEnv* env, jclass, jint source, jint value)
+{
+  CS_Status status = 0;
+  cs::SetCameraWhiteBalanceManual(source, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraExposureAuto
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraExposureAuto
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  cs::SetCameraExposureAuto(source, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraExposureHoldCurrent
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraExposureHoldCurrent
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  cs::SetCameraExposureHoldCurrent(source, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraExposureManual
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraExposureManual
+  (JNIEnv* env, jclass, jint source, jint value)
+{
+  CS_Status status = 0;
+  cs::SetCameraExposureManual(source, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getUsbCameraPath
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getUsbCameraPath
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto str = cs::GetUsbCameraPath(source, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getUsbCameraInfo
+ * Signature: (I)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getUsbCameraInfo
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto info = cs::GetUsbCameraInfo(source, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJObject(env, info);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getHttpCameraKind
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getHttpCameraKind
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto kind = cs::GetHttpCameraKind(source, &status);
+  if (!CheckStatus(env, status)) return 0;
+  return kind;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setHttpCameraUrls
+ * Signature: (I[Ljava/lang/Object;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setHttpCameraUrls
+  (JNIEnv* env, jclass, jint source, jobjectArray urls)
+{
+  if (!urls) {
+    nullPointerEx.Throw(env, "urls cannot be null");
+    return;
+  }
+  size_t len = env->GetArrayLength(urls);
+  wpi::SmallVector<std::string, 8> vec;
+  vec.reserve(len);
+  for (size_t i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(urls, i))};
+    if (!elem) {
+      // TODO
+      return;
+    }
+    vec.push_back(JStringRef{env, elem}.str());
+  }
+  CS_Status status = 0;
+  cs::SetHttpCameraUrls(source, vec, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getHttpCameraUrls
+ * Signature: (I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getHttpCameraUrls
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto arr = cs::GetHttpCameraUrls(source, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJStringArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerCvJNI
+ * Method:    putSourceFrame
+ * Signature: (IJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerCvJNI_putSourceFrame
+  (JNIEnv* env, jclass, jint source, jlong imageNativeObj)
+{
+  try {
+    cv::Mat& image = *((cv::Mat*)imageNativeObj);
+    CS_Status status = 0;
+    cs::PutSourceFrame(source, image, &status);
+    CheckStatus(env, status);
+  } catch (const std::exception& e) {
+    ThrowJavaException(env, &e);
+  } catch (...) {
+    ThrowJavaException(env, 0);
+  }
+}
+
+// int width, int height, int pixelFormat, int totalData
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    putRawSourceFrameBB
+ * Signature: (ILjava/lang/Object;IIII)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_putRawSourceFrameBB
+  (JNIEnv* env, jclass, jint source, jobject byteBuffer, jint width,
+   jint height, jint pixelFormat, jint totalData)
+{
+  CS_RawFrame rawFrame;
+  rawFrame.data =
+      reinterpret_cast<char*>(env->GetDirectBufferAddress(byteBuffer));
+  rawFrame.totalData = totalData;
+  rawFrame.pixelFormat = pixelFormat;
+  rawFrame.width = width;
+  rawFrame.height = height;
+  CS_Status status = 0;
+  cs::PutSourceFrame(source, rawFrame, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    putRawSourceFrame
+ * Signature: (IJIIII)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_putRawSourceFrame
+  (JNIEnv* env, jclass, jint source, jlong ptr, jint width, jint height,
+   jint pixelFormat, jint totalData)
+{
+  CS_RawFrame rawFrame;
+  rawFrame.data = reinterpret_cast<char*>(static_cast<intptr_t>(ptr));
+  rawFrame.totalData = totalData;
+  rawFrame.pixelFormat = pixelFormat;
+  rawFrame.width = width;
+  rawFrame.height = height;
+  CS_Status status = 0;
+  cs::PutSourceFrame(source, rawFrame, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    notifySourceError
+ * Signature: (ILjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_notifySourceError
+  (JNIEnv* env, jclass, jint source, jstring msg)
+{
+  if (!msg) {
+    nullPointerEx.Throw(env, "msg cannot be null");
+    return;
+  }
+  CS_Status status = 0;
+  cs::NotifySourceError(source, JStringRef{env, msg}.str(), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceConnected
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceConnected
+  (JNIEnv* env, jclass, jint source, jboolean connected)
+{
+  CS_Status status = 0;
+  cs::SetSourceConnected(source, connected, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceDescription
+ * Signature: (ILjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceDescription
+  (JNIEnv* env, jclass, jint source, jstring description)
+{
+  if (!description) {
+    nullPointerEx.Throw(env, "description cannot be null");
+    return;
+  }
+  CS_Status status = 0;
+  cs::SetSourceDescription(source, JStringRef{env, description}.str(), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createSourceProperty
+ * Signature: (ILjava/lang/String;IIIIII)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createSourceProperty
+  (JNIEnv* env, jclass, jint source, jstring name, jint kind, jint minimum,
+   jint maximum, jint step, jint defaultValue, jint value)
+{
+  CS_Status status = 0;
+  auto val = cs::CreateSourceProperty(
+      source, JStringRef{env, name}.str(), static_cast<CS_PropertyKind>(kind),
+      minimum, maximum, step, defaultValue, value, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceEnumPropertyChoices
+ * Signature: (II[Ljava/lang/Object;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceEnumPropertyChoices
+  (JNIEnv* env, jclass, jint source, jint property, jobjectArray choices)
+{
+  if (!choices) {
+    nullPointerEx.Throw(env, "choices cannot be null");
+    return;
+  }
+  size_t len = env->GetArrayLength(choices);
+  wpi::SmallVector<std::string, 8> vec;
+  vec.reserve(len);
+  for (size_t i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(choices, i))};
+    if (!elem) {
+      // TODO
+      return;
+    }
+    vec.push_back(JStringRef{env, elem}.str());
+  }
+  CS_Status status = 0;
+  cs::SetSourceEnumPropertyChoices(source, property, vec, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createMjpegServer
+ * Signature: (Ljava/lang/String;Ljava/lang/String;I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createMjpegServer
+  (JNIEnv* env, jclass, jstring name, jstring listenAddress, jint port)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  if (!listenAddress) {
+    nullPointerEx.Throw(env, "listenAddress cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateMjpegServer(JStringRef{env, name}.str(),
+                                   JStringRef{env, listenAddress}.str(), port,
+                                   &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerCvJNI
+ * Method:    createCvSink
+ * Signature: (Ljava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerCvJNI_createCvSink
+  (JNIEnv* env, jclass, jstring name)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateCvSink(JStringRef{env, name}.str(), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createRawSink
+ * Signature: (Ljava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createRawSink
+  (JNIEnv* env, jclass, jstring name)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateRawSink(JStringRef{env, name}.str(), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkKind
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkKind
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSinkKind(sink, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkName
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkName
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSinkName(sink, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkDescription
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkDescription
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSinkDescription(sink, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkProperty
+ * Signature: (ILjava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkProperty
+  (JNIEnv* env, jclass, jint sink, jstring name)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::GetSinkProperty(sink, JStringRef{env, name}.str(), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateSinkProperties
+ * Signature: (I)[I
+ */
+JNIEXPORT jintArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateSinkProperties
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  wpi::SmallVector<CS_Property, 32> buf;
+  auto arr = cs::EnumerateSinkProperties(source, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJIntArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSinkConfigJson
+ * Signature: (ILjava/lang/String;)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSinkConfigJson
+  (JNIEnv* env, jclass, jint source, jstring config)
+{
+  CS_Status status = 0;
+  auto val = cs::SetSinkConfigJson(source, JStringRef{env, config}, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkConfigJson
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkConfigJson
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSinkConfigJson(source, &status);
+  CheckStatus(env, status);
+  return MakeJString(env, val);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSinkSource
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSinkSource
+  (JNIEnv* env, jclass, jint sink, jint source)
+{
+  CS_Status status = 0;
+  cs::SetSinkSource(sink, source, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkSourceProperty
+ * Signature: (ILjava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkSourceProperty
+  (JNIEnv* env, jclass, jint sink, jstring name)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val =
+      cs::GetSinkSourceProperty(sink, JStringRef{env, name}.str(), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkSource
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkSource
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSinkSource(sink, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    copySink
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_copySink
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  auto val = cs::CopySink(sink, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    releaseSink
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_releaseSink
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  cs::ReleaseSink(sink, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getMjpegServerListenAddress
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getMjpegServerListenAddress
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  auto str = cs::GetMjpegServerListenAddress(sink, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getMjpegServerPort
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getMjpegServerPort
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  auto val = cs::GetMjpegServerPort(sink, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSinkDescription
+ * Signature: (ILjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSinkDescription
+  (JNIEnv* env, jclass, jint sink, jstring description)
+{
+  if (!description) {
+    nullPointerEx.Throw(env, "description cannot be null");
+    return;
+  }
+  CS_Status status = 0;
+  cs::SetSinkDescription(sink, JStringRef{env, description}.str(), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerCvJNI
+ * Method:    grabSinkFrame
+ * Signature: (IJ)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_cscore_CameraServerCvJNI_grabSinkFrame
+  (JNIEnv* env, jclass, jint sink, jlong imageNativeObj)
+{
+  try {
+    cv::Mat& image = *((cv::Mat*)imageNativeObj);
+    CS_Status status = 0;
+    auto rv = cs::GrabSinkFrame(sink, image, &status);
+    CheckStatus(env, status);
+    return rv;
+  } catch (const std::exception& e) {
+    ThrowJavaException(env, &e);
+    return 0;
+  } catch (...) {
+    ThrowJavaException(env, 0);
+    return 0;
+  }
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerCvJNI
+ * Method:    grabSinkFrameTimeout
+ * Signature: (IJD)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_cscore_CameraServerCvJNI_grabSinkFrameTimeout
+  (JNIEnv* env, jclass, jint sink, jlong imageNativeObj, jdouble timeout)
+{
+  try {
+    cv::Mat& image = *((cv::Mat*)imageNativeObj);
+    CS_Status status = 0;
+    auto rv = cs::GrabSinkFrameTimeout(sink, image, timeout, &status);
+    CheckStatus(env, status);
+    return rv;
+  } catch (const std::exception& e) {
+    ThrowJavaException(env, &e);
+    return 0;
+  } catch (...) {
+    ThrowJavaException(env, 0);
+    return 0;
+  }
+}
+
+static void SetRawFrameData(JNIEnv* env, jobject rawFrameObj,
+                            jobject byteBuffer, bool didChangeDataPtr,
+                            const CS_RawFrame& frame) {
+  static jmethodID setMethod =
+      env->GetMethodID(rawFrameCls, "setData", "(Ljava/nio/ByteBuffer;JIIII)V");
+  jlong framePtr = static_cast<jlong>(reinterpret_cast<intptr_t>(frame.data));
+
+  if (didChangeDataPtr) {
+    byteBuffer = env->NewDirectByteBuffer(frame.data, frame.dataLength);
+  }
+
+  env->CallVoidMethod(
+      rawFrameObj, setMethod, byteBuffer, framePtr,
+      static_cast<jint>(frame.totalData), static_cast<jint>(frame.width),
+      static_cast<jint>(frame.height), static_cast<jint>(frame.pixelFormat));
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    grabRawSinkFrameImpl
+ * Signature: (ILjava/lang/Object;JLjava/lang/Object;III)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_grabRawSinkFrameImpl
+  (JNIEnv* env, jclass, jint sink, jobject rawFrameObj, jlong rawFramePtr,
+   jobject byteBuffer, jint width, jint height, jint pixelFormat)
+{
+  CS_RawFrame* ptr =
+      reinterpret_cast<CS_RawFrame*>(static_cast<intptr_t>(rawFramePtr));
+  auto origDataPtr = ptr->data;
+  ptr->width = width;
+  ptr->height = height;
+  ptr->pixelFormat = pixelFormat;
+  CS_Status status = 0;
+  auto rv = cs::GrabSinkFrame(static_cast<CS_Sink>(sink), *ptr, &status);
+  if (!CheckStatus(env, status)) {
+    return 0;
+  }
+  SetRawFrameData(env, rawFrameObj, byteBuffer, origDataPtr != ptr->data, *ptr);
+  return rv;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    grabRawSinkFrameTimeoutImpl
+ * Signature: (ILjava/lang/Object;JLjava/lang/Object;IIID)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_grabRawSinkFrameTimeoutImpl
+  (JNIEnv* env, jclass, jint sink, jobject rawFrameObj, jlong rawFramePtr,
+   jobject byteBuffer, jint width, jint height, jint pixelFormat,
+   jdouble timeout)
+{
+  CS_RawFrame* ptr =
+      reinterpret_cast<CS_RawFrame*>(static_cast<intptr_t>(rawFramePtr));
+  auto origDataPtr = ptr->data;
+  ptr->width = width;
+  ptr->height = height;
+  ptr->pixelFormat = pixelFormat;
+  CS_Status status = 0;
+  auto rv = cs::GrabSinkFrameTimeout(static_cast<CS_Sink>(sink), *ptr, timeout,
+                                     &status);
+  if (!CheckStatus(env, status)) {
+    return 0;
+  }
+  SetRawFrameData(env, rawFrameObj, byteBuffer, origDataPtr != ptr->data, *ptr);
+  return rv;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkError
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkError
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSinkError(sink, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSinkEnabled
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSinkEnabled
+  (JNIEnv* env, jclass, jint sink, jboolean enabled)
+{
+  CS_Status status = 0;
+  cs::SetSinkEnabled(sink, enabled, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    addListener
+ * Signature: (Ljava/lang/Object;IZ)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_addListener
+  (JNIEnv* envouter, jclass, jobject listener, jint eventMask,
+   jboolean immediateNotify)
+{
+  if (!listener) {
+    nullPointerEx.Throw(envouter, "listener cannot be null");
+    return 0;
+  }
+  // the shared pointer to the weak global will keep it around until the
+  // entry listener is destroyed
+  auto listener_global =
+      std::make_shared<JCSGlobal<jobject>>(envouter, listener);
+
+  // cls is a temporary here; cannot be used within callback functor
+  jclass cls = envouter->GetObjectClass(listener);
+  if (!cls) return 0;
+
+  // method ids, on the other hand, are safe to retain
+  jmethodID mid = envouter->GetMethodID(cls, "accept", "(Ljava/lang/Object;)V");
+  if (!mid) return 0;
+
+  CS_Status status = 0;
+  CS_Listener handle = cs::AddListener(
+      [=](const cs::RawEvent& event) {
+        JNIEnv* env = listenerEnv;
+        if (!env || !env->functions) return;
+
+        // get the handler
+        auto handler = listener_global->obj();
+
+        // convert into the appropriate Java type
+        JLocal<jobject> jobj{env, MakeJObject(env, event)};
+        if (env->ExceptionCheck()) {
+          env->ExceptionDescribe();
+          env->ExceptionClear();
+          return;
+        }
+        if (!jobj) return;
+
+        env->CallVoidMethod(handler, mid, jobj.obj());
+        if (env->ExceptionCheck()) {
+          env->ExceptionDescribe();
+          env->ExceptionClear();
+        }
+      },
+      eventMask, immediateNotify != JNI_FALSE, &status);
+  CheckStatus(envouter, status);
+  return handle;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    removeListener
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_removeListener
+  (JNIEnv* env, jclass, jint handle)
+{
+  CS_Status status = 0;
+  cs::RemoveListener(handle, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setTelemetryPeriod
+ * Signature: (D)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setTelemetryPeriod
+  (JNIEnv* env, jclass, jdouble seconds)
+{
+  cs::SetTelemetryPeriod(seconds);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getTelemetryElapsedTime
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getTelemetryElapsedTime
+  (JNIEnv* env, jclass)
+{
+  return cs::GetTelemetryElapsedTime();
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getTelemetryValue
+ * Signature: (II)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getTelemetryValue
+  (JNIEnv* env, jclass, jint handle, jint kind)
+{
+  CS_Status status = 0;
+  auto val = cs::GetTelemetryValue(handle, static_cast<CS_TelemetryKind>(kind),
+                                   &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getTelemetryAverageValue
+ * Signature: (II)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getTelemetryAverageValue
+  (JNIEnv* env, jclass, jint handle, jint kind)
+{
+  CS_Status status = 0;
+  auto val = cs::GetTelemetryAverageValue(
+      handle, static_cast<CS_TelemetryKind>(kind), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateUsbCameras
+ * Signature: ()[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateUsbCameras
+  (JNIEnv* env, jclass)
+{
+  CS_Status status = 0;
+  auto arr = cs::EnumerateUsbCameras(&status);
+  if (!CheckStatus(env, status)) return nullptr;
+  jobjectArray jarr =
+      env->NewObjectArray(arr.size(), usbCameraInfoCls, nullptr);
+  if (!jarr) return nullptr;
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> jelem{env, MakeJObject(env, arr[i])};
+    env->SetObjectArrayElement(jarr, i, jelem);
+  }
+  return jarr;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateSources
+ * Signature: ()[I
+ */
+JNIEXPORT jintArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateSources
+  (JNIEnv* env, jclass)
+{
+  CS_Status status = 0;
+  wpi::SmallVector<CS_Source, 16> buf;
+  auto arr = cs::EnumerateSourceHandles(buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJIntArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateSinks
+ * Signature: ()[I
+ */
+JNIEXPORT jintArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateSinks
+  (JNIEnv* env, jclass)
+{
+  CS_Status status = 0;
+  wpi::SmallVector<CS_Sink, 16> buf;
+  auto arr = cs::EnumerateSinkHandles(buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJIntArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getHostname
+ * Signature: ()Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getHostname
+  (JNIEnv* env, jclass)
+{
+  return MakeJString(env, cs::GetHostname());
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getNetworkInterfaces
+ * Signature: ()[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getNetworkInterfaces
+  (JNIEnv* env, jclass)
+{
+  return MakeJStringArray(env, cs::GetNetworkInterfaces());
+}
+
+}  // extern "C"
+
+namespace {
+
+struct LogMessage {
+ public:
+  LogMessage(unsigned int level, const char* file, unsigned int line,
+             const char* msg)
+      : m_level(level), m_file(file), m_line(line), m_msg(msg) {}
+
+  void CallJava(JNIEnv* env, jobject func, jmethodID mid) {
+    JLocal<jstring> file{env, MakeJString(env, m_file)};
+    JLocal<jstring> msg{env, MakeJString(env, m_msg)};
+    env->CallVoidMethod(func, mid, (jint)m_level, file.obj(), (jint)m_line,
+                        msg.obj());
+  }
+
+  static const char* GetName() { return "CSLogger"; }
+  static JavaVM* GetJVM() { return jvm; }
+
+ private:
+  unsigned int m_level;
+  const char* m_file;
+  unsigned int m_line;
+  std::string m_msg;
+};
+
+typedef JSingletonCallbackManager<LogMessage> LoggerJNI;
+
+}  // namespace
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setLogger
+ * Signature: (Ljava/lang/Object;I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setLogger
+  (JNIEnv* env, jclass, jobject func, jint minLevel)
+{
+  if (!func) {
+    nullPointerEx.Throw(env, "func cannot be null");
+    return;
+  }
+  // cls is a temporary here; cannot be used within callback functor
+  jclass cls = env->GetObjectClass(func);
+  if (!cls) return;
+
+  // method ids, on the other hand, are safe to retain
+  jmethodID mid = env->GetMethodID(cls, "apply",
+                                   "(ILjava/lang/String;ILjava/lang/String;)V");
+  if (!mid) return;
+
+  auto& logger = LoggerJNI::GetInstance();
+  logger.Start();
+  logger.SetFunc(env, func, mid);
+
+  cs::SetLogger(
+      [](unsigned int level, const char* file, unsigned int line,
+         const char* msg) {
+        LoggerJNI::GetInstance().Send(level, file, line, msg);
+      },
+      minLevel);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    allocateRawFrame
+ * Signature: ()J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_allocateRawFrame
+  (JNIEnv*, jclass)
+{
+  cs::RawFrame* rawFrame = new cs::RawFrame{};
+  intptr_t rawFrameIntPtr = reinterpret_cast<intptr_t>(rawFrame);
+  return static_cast<jlong>(rawFrameIntPtr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    freeRawFrame
+ * Signature: (J)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_freeRawFrame
+  (JNIEnv*, jclass, jlong rawFrame)
+{
+  cs::RawFrame* ptr =
+      reinterpret_cast<cs::RawFrame*>(static_cast<intptr_t>(rawFrame));
+  delete ptr;
+}
+
+}  // extern "C"
diff --git a/cscore/src/main/native/include/cscore.h b/cscore/src/main/native/include/cscore.h
new file mode 100644
index 0000000..eff3856
--- /dev/null
+++ b/cscore/src/main/native/include/cscore.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CSCORE_H_
+#define CSCORE_CSCORE_H_
+
+/* C API */
+#include "cscore_c.h"
+
+#ifdef __cplusplus
+/* C++ API */
+#include "cscore_cpp.h"
+#include "cscore_oo.h"
+#endif /* __cplusplus */
+
+#endif  // CSCORE_CSCORE_H_
diff --git a/cscore/src/main/native/include/cscore_c.h b/cscore/src/main/native/include/cscore_c.h
new file mode 100644
index 0000000..24e30b4
--- /dev/null
+++ b/cscore/src/main/native/include/cscore_c.h
@@ -0,0 +1,504 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CSCORE_C_H_
+#define CSCORE_CSCORE_C_H_
+
+#include <stdint.h>
+
+#ifdef __cplusplus
+#include <cstddef>
+#else
+#include <stddef.h>
+#endif
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @defgroup cscore_c_api cscore C API
+ *
+ * Handle-based interface for C.
+ *
+ * <p>Sources and sinks are reference counted internally to the library.
+ * Any time a source or sink handle is returned or provided to a callback,
+ * the reference count is incremented.
+ *
+ * <p>Calling CS_ReleaseSource() or CS_ReleaseSink() decrements the reference
+ * count, and when the reference count reaches zero, the object is destroyed.
+ *
+ * <p>Connecting a source to a sink increments the reference count of the
+ * source, and when the sink is destroyed (its reference count reaches zero),
+ * the source reference count is decremented.
+ *
+ * @{
+ */
+
+/**
+ * @defgroup cscore_typedefs Typedefs
+ * @{
+ */
+typedef int CS_Bool;
+typedef int CS_Status;
+
+typedef int CS_Handle;
+typedef CS_Handle CS_Property;
+typedef CS_Handle CS_Listener;
+typedef CS_Handle CS_Sink;
+typedef CS_Handle CS_Source;
+/** @} */
+
+/**
+ * Status values
+ */
+enum CS_StatusValue {
+  CS_PROPERTY_WRITE_FAILED = 2000,
+  CS_OK = 0,
+  CS_INVALID_HANDLE = -2000,  // handle was invalid (does not exist)
+  CS_WRONG_HANDLE_SUBTYPE = -2001,
+  CS_INVALID_PROPERTY = -2002,
+  CS_WRONG_PROPERTY_TYPE = -2003,
+  CS_READ_FAILED = -2004,
+  CS_SOURCE_IS_DISCONNECTED = -2005,
+  CS_EMPTY_VALUE = -2006,
+  CS_BAD_URL = -2007,
+  CS_TELEMETRY_NOT_ENABLED = -2008,
+  CS_UNSUPPORTED_MODE = -2009
+};
+
+/**
+ * Logging levels
+ */
+enum CS_LogLevel {
+  CS_LOG_CRITICAL = 50,
+  CS_LOG_ERROR = 40,
+  CS_LOG_WARNING = 30,
+  CS_LOG_INFO = 20,
+  CS_LOG_DEBUG = 10,
+  CS_LOG_DEBUG1 = 9,
+  CS_LOG_DEBUG2 = 8,
+  CS_LOG_DEBUG3 = 7,
+  CS_LOG_DEBUG4 = 6
+};
+
+/**
+ * Pixel formats
+ */
+enum CS_PixelFormat {
+  CS_PIXFMT_UNKNOWN = 0,
+  CS_PIXFMT_MJPEG,
+  CS_PIXFMT_YUYV,
+  CS_PIXFMT_RGB565,
+  CS_PIXFMT_BGR,
+  CS_PIXFMT_GRAY
+};
+
+/**
+ * Video mode
+ */
+typedef struct CS_VideoMode {
+  int pixelFormat;
+  int width;
+  int height;
+  int fps;
+} CS_VideoMode;
+
+/**
+ * Property kinds
+ */
+enum CS_PropertyKind {
+  CS_PROP_NONE = 0,
+  CS_PROP_BOOLEAN = 1,
+  CS_PROP_INTEGER = 2,
+  CS_PROP_STRING = 4,
+  CS_PROP_ENUM = 8
+};
+
+/**
+ * Source kinds
+ */
+enum CS_SourceKind {
+  CS_SOURCE_UNKNOWN = 0,
+  CS_SOURCE_USB = 1,
+  CS_SOURCE_HTTP = 2,
+  CS_SOURCE_CV = 4,
+  CS_SOURCE_RAW = 8,
+};
+
+/**
+ * HTTP Camera kinds
+ */
+enum CS_HttpCameraKind {
+  CS_HTTP_UNKNOWN = 0,
+  CS_HTTP_MJPGSTREAMER = 1,
+  CS_HTTP_CSCORE = 2,
+  CS_HTTP_AXIS = 3
+};
+
+/**
+ * Sink kinds
+ */
+enum CS_SinkKind {
+  CS_SINK_UNKNOWN = 0,
+  CS_SINK_MJPEG = 2,
+  CS_SINK_CV = 4,
+  CS_SINK_RAW = 8
+};
+
+/**
+ * Listener event kinds
+ */
+enum CS_EventKind {
+  CS_SOURCE_CREATED = 0x0001,
+  CS_SOURCE_DESTROYED = 0x0002,
+  CS_SOURCE_CONNECTED = 0x0004,
+  CS_SOURCE_DISCONNECTED = 0x0008,
+  CS_SOURCE_VIDEOMODES_UPDATED = 0x0010,
+  CS_SOURCE_VIDEOMODE_CHANGED = 0x0020,
+  CS_SOURCE_PROPERTY_CREATED = 0x0040,
+  CS_SOURCE_PROPERTY_VALUE_UPDATED = 0x0080,
+  CS_SOURCE_PROPERTY_CHOICES_UPDATED = 0x0100,
+  CS_SINK_SOURCE_CHANGED = 0x0200,
+  CS_SINK_CREATED = 0x0400,
+  CS_SINK_DESTROYED = 0x0800,
+  CS_SINK_ENABLED = 0x1000,
+  CS_SINK_DISABLED = 0x2000,
+  CS_NETWORK_INTERFACES_CHANGED = 0x4000,
+  CS_TELEMETRY_UPDATED = 0x8000,
+  CS_SINK_PROPERTY_CREATED = 0x10000,
+  CS_SINK_PROPERTY_VALUE_UPDATED = 0x20000,
+  CS_SINK_PROPERTY_CHOICES_UPDATED = 0x40000
+};
+
+/**
+ * Telemetry kinds
+ */
+enum CS_TelemetryKind {
+  CS_SOURCE_BYTES_RECEIVED = 1,
+  CS_SOURCE_FRAMES_RECEIVED = 2
+};
+
+/** Connection strategy */
+enum CS_ConnectionStrategy {
+  /**
+   * Automatically connect or disconnect based on whether any sinks are
+   * connected to this source.  This is the default behavior.
+   */
+  CS_CONNECTION_AUTO_MANAGE = 0,
+
+  /**
+   * Try to keep the connection open regardless of whether any sinks are
+   * connected.
+   */
+  CS_CONNECTION_KEEP_OPEN,
+
+  /**
+   * Never open the connection.  If this is set when the connection is open,
+   * close the connection.
+   */
+  CS_CONNECTION_FORCE_CLOSE
+};
+
+/**
+ * Listener event
+ */
+struct CS_Event {
+  enum CS_EventKind kind;
+
+  // Valid for CS_SOURCE_* and CS_SINK_* respectively
+  CS_Source source;
+  CS_Sink sink;
+
+  // Source/sink/property name
+  const char* name;
+
+  // Fields for CS_SOURCE_VIDEOMODE_CHANGED event
+  CS_VideoMode mode;
+
+  // Fields for CS_SOURCE_PROPERTY_* events
+  CS_Property property;
+  enum CS_PropertyKind propertyKind;
+  int value;
+  const char* valueStr;
+};
+
+/**
+ * USB camera infomation
+ */
+typedef struct CS_UsbCameraInfo {
+  int dev;
+  char* path;
+  char* name;
+  int otherPathsCount;
+  char** otherPaths;
+  int vendorId;
+  int productId;
+} CS_UsbCameraInfo;
+
+/**
+ * @defgroup cscore_property_cfunc Property Functions
+ * @{
+ */
+enum CS_PropertyKind CS_GetPropertyKind(CS_Property property,
+                                        CS_Status* status);
+char* CS_GetPropertyName(CS_Property property, CS_Status* status);
+int CS_GetProperty(CS_Property property, CS_Status* status);
+void CS_SetProperty(CS_Property property, int value, CS_Status* status);
+int CS_GetPropertyMin(CS_Property property, CS_Status* status);
+int CS_GetPropertyMax(CS_Property property, CS_Status* status);
+int CS_GetPropertyStep(CS_Property property, CS_Status* status);
+int CS_GetPropertyDefault(CS_Property property, CS_Status* status);
+char* CS_GetStringProperty(CS_Property property, CS_Status* status);
+void CS_SetStringProperty(CS_Property property, const char* value,
+                          CS_Status* status);
+char** CS_GetEnumPropertyChoices(CS_Property property, int* count,
+                                 CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_source_create_cfunc Source Creation Functions
+ * @{
+ */
+CS_Source CS_CreateUsbCameraDev(const char* name, int dev, CS_Status* status);
+CS_Source CS_CreateUsbCameraPath(const char* name, const char* path,
+                                 CS_Status* status);
+CS_Source CS_CreateHttpCamera(const char* name, const char* url,
+                              enum CS_HttpCameraKind kind, CS_Status* status);
+CS_Source CS_CreateHttpCameraMulti(const char* name, const char** urls,
+                                   int count, enum CS_HttpCameraKind kind,
+                                   CS_Status* status);
+CS_Source CS_CreateCvSource(const char* name, const CS_VideoMode* mode,
+                            CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_source_cfunc Source Functions
+ * @{
+ */
+enum CS_SourceKind CS_GetSourceKind(CS_Source source, CS_Status* status);
+char* CS_GetSourceName(CS_Source source, CS_Status* status);
+char* CS_GetSourceDescription(CS_Source source, CS_Status* status);
+uint64_t CS_GetSourceLastFrameTime(CS_Source source, CS_Status* status);
+void CS_SetSourceConnectionStrategy(CS_Source source,
+                                    enum CS_ConnectionStrategy strategy,
+                                    CS_Status* status);
+CS_Bool CS_IsSourceConnected(CS_Source source, CS_Status* status);
+CS_Bool CS_IsSourceEnabled(CS_Source source, CS_Status* status);
+CS_Property CS_GetSourceProperty(CS_Source source, const char* name,
+                                 CS_Status* status);
+CS_Property* CS_EnumerateSourceProperties(CS_Source source, int* count,
+                                          CS_Status* status);
+void CS_GetSourceVideoMode(CS_Source source, CS_VideoMode* mode,
+                           CS_Status* status);
+CS_Bool CS_SetSourceVideoMode(CS_Source source, const CS_VideoMode* mode,
+                              CS_Status* status);
+CS_Bool CS_SetSourceVideoModeDiscrete(CS_Source source,
+                                      enum CS_PixelFormat pixelFormat,
+                                      int width, int height, int fps,
+                                      CS_Status* status);
+CS_Bool CS_SetSourcePixelFormat(CS_Source source,
+                                enum CS_PixelFormat pixelFormat,
+                                CS_Status* status);
+CS_Bool CS_SetSourceResolution(CS_Source source, int width, int height,
+                               CS_Status* status);
+CS_Bool CS_SetSourceFPS(CS_Source source, int fps, CS_Status* status);
+CS_Bool CS_SetSourceConfigJson(CS_Source source, const char* config,
+                               CS_Status* status);
+char* CS_GetSourceConfigJson(CS_Source source, CS_Status* status);
+CS_VideoMode* CS_EnumerateSourceVideoModes(CS_Source source, int* count,
+                                           CS_Status* status);
+CS_Sink* CS_EnumerateSourceSinks(CS_Source source, int* count,
+                                 CS_Status* status);
+CS_Source CS_CopySource(CS_Source source, CS_Status* status);
+void CS_ReleaseSource(CS_Source source, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_source_prop_cfunc Camera Source Common Property Fuctions
+ * @{
+ */
+void CS_SetCameraBrightness(CS_Source source, int brightness,
+                            CS_Status* status);
+int CS_GetCameraBrightness(CS_Source source, CS_Status* status);
+void CS_SetCameraWhiteBalanceAuto(CS_Source source, CS_Status* status);
+void CS_SetCameraWhiteBalanceHoldCurrent(CS_Source source, CS_Status* status);
+void CS_SetCameraWhiteBalanceManual(CS_Source source, int value,
+                                    CS_Status* status);
+void CS_SetCameraExposureAuto(CS_Source source, CS_Status* status);
+void CS_SetCameraExposureHoldCurrent(CS_Source source, CS_Status* status);
+void CS_SetCameraExposureManual(CS_Source source, int value, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_usbcamera_cfunc UsbCamera Source Functions
+ * @{
+ */
+char* CS_GetUsbCameraPath(CS_Source source, CS_Status* status);
+CS_UsbCameraInfo* CS_GetUsbCameraInfo(CS_Source source, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_httpcamera_cfunc HttpCamera Source Functions
+ * @{
+ */
+enum CS_HttpCameraKind CS_GetHttpCameraKind(CS_Source source,
+                                            CS_Status* status);
+void CS_SetHttpCameraUrls(CS_Source source, const char** urls, int count,
+                          CS_Status* status);
+char** CS_GetHttpCameraUrls(CS_Source source, int* count, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_opencv_source_cfunc OpenCV Source Functions
+ * @{
+ */
+void CS_NotifySourceError(CS_Source source, const char* msg, CS_Status* status);
+void CS_SetSourceConnected(CS_Source source, CS_Bool connected,
+                           CS_Status* status);
+void CS_SetSourceDescription(CS_Source source, const char* description,
+                             CS_Status* status);
+CS_Property CS_CreateSourceProperty(CS_Source source, const char* name,
+                                    enum CS_PropertyKind kind, int minimum,
+                                    int maximum, int step, int defaultValue,
+                                    int value, CS_Status* status);
+void CS_SetSourceEnumPropertyChoices(CS_Source source, CS_Property property,
+                                     const char** choices, int count,
+                                     CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_sink_create_cfunc Sink Creation Functions
+ * @{
+ */
+CS_Sink CS_CreateMjpegServer(const char* name, const char* listenAddress,
+                             int port, CS_Status* status);
+CS_Sink CS_CreateCvSink(const char* name, CS_Status* status);
+CS_Sink CS_CreateCvSinkCallback(const char* name, void* data,
+                                void (*processFrame)(void* data, uint64_t time),
+                                CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_sink_cfunc Sink Functions
+ * @{
+ */
+enum CS_SinkKind CS_GetSinkKind(CS_Sink sink, CS_Status* status);
+char* CS_GetSinkName(CS_Sink sink, CS_Status* status);
+char* CS_GetSinkDescription(CS_Sink sink, CS_Status* status);
+CS_Property CS_GetSinkProperty(CS_Sink sink, const char* name,
+                               CS_Status* status);
+CS_Property* CS_EnumerateSinkProperties(CS_Sink sink, int* count,
+                                        CS_Status* status);
+void CS_SetSinkSource(CS_Sink sink, CS_Source source, CS_Status* status);
+CS_Property CS_GetSinkSourceProperty(CS_Sink sink, const char* name,
+                                     CS_Status* status);
+CS_Bool CS_SetSinkConfigJson(CS_Sink sink, const char* config,
+                             CS_Status* status);
+char* CS_GetSinkConfigJson(CS_Sink sink, CS_Status* status);
+CS_Source CS_GetSinkSource(CS_Sink sink, CS_Status* status);
+CS_Sink CS_CopySink(CS_Sink sink, CS_Status* status);
+void CS_ReleaseSink(CS_Sink sink, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_mjpegserver_cfunc MjpegServer Sink Functions
+ * @{
+ */
+char* CS_GetMjpegServerListenAddress(CS_Sink sink, CS_Status* status);
+int CS_GetMjpegServerPort(CS_Sink sink, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_opencv_sink_cfunc OpenCV Sink Functions
+ * @{
+ */
+void CS_SetSinkDescription(CS_Sink sink, const char* description,
+                           CS_Status* status);
+char* CS_GetSinkError(CS_Sink sink, CS_Status* status);
+void CS_SetSinkEnabled(CS_Sink sink, CS_Bool enabled, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_listener_cfunc Listener Functions
+ * @{
+ */
+void CS_SetListenerOnStart(void (*onStart)(void* data), void* data);
+void CS_SetListenerOnExit(void (*onExit)(void* data), void* data);
+CS_Listener CS_AddListener(
+    void* data, void (*callback)(void* data, const struct CS_Event* event),
+    int eventMask, int immediateNotify, CS_Status* status);
+
+void CS_RemoveListener(CS_Listener handle, CS_Status* status);
+/** @} */
+
+int CS_NotifierDestroyed(void);
+
+/**
+ * @defgroup cscore_telemetry_cfunc Telemetry Functions
+ * @{
+ */
+void CS_SetTelemetryPeriod(double seconds);
+double CS_GetTelemetryElapsedTime(void);
+int64_t CS_GetTelemetryValue(CS_Handle handle, enum CS_TelemetryKind kind,
+                             CS_Status* status);
+double CS_GetTelemetryAverageValue(CS_Handle handle, enum CS_TelemetryKind kind,
+                                   CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_logging_cfunc Logging Functions
+ * @{
+ */
+typedef void (*CS_LogFunc)(unsigned int level, const char* file,
+                           unsigned int line, const char* msg);
+void CS_SetLogger(CS_LogFunc func, unsigned int min_level);
+void CS_SetDefaultLogger(unsigned int min_level);
+/** @} */
+
+/**
+ * @defgroup cscore_shutdown_cfunc Library Shutdown Function
+ * @{
+ */
+void CS_Shutdown(void);
+/** @} */
+
+/**
+ * @defgroup cscore_utility_cfunc Utility Functions
+ * @{
+ */
+
+CS_UsbCameraInfo* CS_EnumerateUsbCameras(int* count, CS_Status* status);
+void CS_FreeEnumeratedUsbCameras(CS_UsbCameraInfo* cameras, int count);
+
+CS_Source* CS_EnumerateSources(int* count, CS_Status* status);
+void CS_ReleaseEnumeratedSources(CS_Source* sources, int count);
+
+CS_Sink* CS_EnumerateSinks(int* count, CS_Status* status);
+void CS_ReleaseEnumeratedSinks(CS_Sink* sinks, int count);
+
+void CS_FreeString(char* str);
+void CS_FreeEnumPropertyChoices(char** choices, int count);
+void CS_FreeUsbCameraInfo(CS_UsbCameraInfo* info);
+void CS_FreeHttpCameraUrls(char** urls, int count);
+
+void CS_FreeEnumeratedProperties(CS_Property* properties, int count);
+void CS_FreeEnumeratedVideoModes(CS_VideoMode* modes, int count);
+
+char* CS_GetHostname();
+
+char** CS_GetNetworkInterfaces(int* count);
+void CS_FreeNetworkInterfaces(char** interfaces, int count);
+/** @} */
+
+/** @} */
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif  // CSCORE_CSCORE_C_H_
diff --git a/cscore/src/main/native/include/cscore_cpp.h b/cscore/src/main/native/include/cscore_cpp.h
new file mode 100644
index 0000000..c1ec024
--- /dev/null
+++ b/cscore/src/main/native/include/cscore_cpp.h
@@ -0,0 +1,440 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CSCORE_CPP_H_
+#define CSCORE_CSCORE_CPP_H_
+
+#include <stdint.h>
+
+#include <functional>
+#include <string>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+
+#include "cscore_c.h"
+
+#ifdef _WIN32
+// Disable uninitialized variable warnings
+#pragma warning(push)
+#pragma warning(disable : 26495)
+#endif
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+/** CameraServer (cscore) namespace */
+namespace cs {
+
+/**
+ * @defgroup cscore_cpp_api cscore C++ function API
+ *
+ * Handle-based interface for C++.  Users are encouraged to use the
+ * object oriented interface instead; this interface is intended for use
+ * in applications such as JNI which require handle-based access.
+ *
+ * @{
+ */
+
+/**
+ * USB camera information
+ */
+struct UsbCameraInfo {
+  /** Device number (e.g. N in '/dev/videoN' on Linux) */
+  int dev = -1;
+  /** Path to device if available (e.g. '/dev/video0' on Linux) */
+  std::string path;
+  /** Vendor/model name of the camera as provided by the USB driver */
+  std::string name;
+  /** Other path aliases to device (e.g. '/dev/v4l/by-id/...' etc on Linux) */
+  std::vector<std::string> otherPaths;
+  /** USB Vendor Id */
+  int vendorId = -1;
+  /** USB Product Id */
+  int productId = -1;
+};
+
+/**
+ * Video mode
+ */
+struct VideoMode : public CS_VideoMode {
+  enum PixelFormat {
+    kUnknown = CS_PIXFMT_UNKNOWN,
+    kMJPEG = CS_PIXFMT_MJPEG,
+    kYUYV = CS_PIXFMT_YUYV,
+    kRGB565 = CS_PIXFMT_RGB565,
+    kBGR = CS_PIXFMT_BGR,
+    kGray = CS_PIXFMT_GRAY
+  };
+  VideoMode() {
+    pixelFormat = 0;
+    width = 0;
+    height = 0;
+    fps = 0;
+  }
+  VideoMode(PixelFormat pixelFormat_, int width_, int height_, int fps_) {
+    pixelFormat = pixelFormat_;
+    width = width_;
+    height = height_;
+    fps = fps_;
+  }
+  explicit operator bool() const { return pixelFormat == kUnknown; }
+
+  bool operator==(const VideoMode& other) const {
+    return pixelFormat == other.pixelFormat && width == other.width &&
+           height == other.height && fps == other.fps;
+  }
+
+  bool operator!=(const VideoMode& other) const { return !(*this == other); }
+};
+
+/**
+ * Listener event
+ */
+struct RawEvent {
+  enum Kind {
+    kSourceCreated = CS_SOURCE_CREATED,
+    kSourceDestroyed = CS_SOURCE_DESTROYED,
+    kSourceConnected = CS_SOURCE_CONNECTED,
+    kSourceDisconnected = CS_SOURCE_DISCONNECTED,
+    kSourceVideoModesUpdated = CS_SOURCE_VIDEOMODES_UPDATED,
+    kSourceVideoModeChanged = CS_SOURCE_VIDEOMODE_CHANGED,
+    kSourcePropertyCreated = CS_SOURCE_PROPERTY_CREATED,
+    kSourcePropertyValueUpdated = CS_SOURCE_PROPERTY_VALUE_UPDATED,
+    kSourcePropertyChoicesUpdated = CS_SOURCE_PROPERTY_CHOICES_UPDATED,
+    kSinkSourceChanged = CS_SINK_SOURCE_CHANGED,
+    kSinkCreated = CS_SINK_CREATED,
+    kSinkDestroyed = CS_SINK_DESTROYED,
+    kSinkEnabled = CS_SINK_ENABLED,
+    kSinkDisabled = CS_SINK_DISABLED,
+    kNetworkInterfacesChanged = CS_NETWORK_INTERFACES_CHANGED,
+    kTelemetryUpdated = CS_TELEMETRY_UPDATED,
+    kSinkPropertyCreated = CS_SINK_PROPERTY_CREATED,
+    kSinkPropertyValueUpdated = CS_SINK_PROPERTY_VALUE_UPDATED,
+    kSinkPropertyChoicesUpdated = CS_SINK_PROPERTY_CHOICES_UPDATED
+  };
+
+  RawEvent() = default;
+  explicit RawEvent(RawEvent::Kind kind_) : kind{kind_} {}
+  RawEvent(const wpi::Twine& name_, CS_Handle handle_, RawEvent::Kind kind_)
+      : kind{kind_}, name{name_.str()} {
+    if (kind_ == kSinkCreated || kind_ == kSinkDestroyed ||
+        kind_ == kSinkEnabled || kind_ == kSinkDisabled)
+      sinkHandle = handle_;
+    else
+      sourceHandle = handle_;
+  }
+  RawEvent(const wpi::Twine& name_, CS_Source source_, const VideoMode& mode_)
+      : kind{kSourceVideoModeChanged},
+        sourceHandle{source_},
+        name{name_.str()},
+        mode{mode_} {}
+  RawEvent(const wpi::Twine& name_, CS_Source source_, RawEvent::Kind kind_,
+           CS_Property property_, CS_PropertyKind propertyKind_, int value_,
+           const wpi::Twine& valueStr_)
+      : kind{kind_},
+        sourceHandle{source_},
+        name{name_.str()},
+        propertyHandle{property_},
+        propertyKind{propertyKind_},
+        value{value_},
+        valueStr{valueStr_.str()} {}
+
+  Kind kind;
+
+  // Valid for kSource* and kSink* respectively
+  CS_Source sourceHandle = CS_INVALID_HANDLE;
+  CS_Sink sinkHandle = CS_INVALID_HANDLE;
+
+  // Source/sink/property name
+  std::string name;
+
+  // Fields for kSourceVideoModeChanged event
+  VideoMode mode;
+
+  // Fields for kSourceProperty* events
+  CS_Property propertyHandle;
+  CS_PropertyKind propertyKind;
+  int value;
+  std::string valueStr;
+};
+
+/**
+ * @defgroup cscore_property_func Property Functions
+ * @{
+ */
+CS_PropertyKind GetPropertyKind(CS_Property property, CS_Status* status);
+std::string GetPropertyName(CS_Property property, CS_Status* status);
+wpi::StringRef GetPropertyName(CS_Property property,
+                               wpi::SmallVectorImpl<char>& buf,
+                               CS_Status* status);
+int GetProperty(CS_Property property, CS_Status* status);
+void SetProperty(CS_Property property, int value, CS_Status* status);
+int GetPropertyMin(CS_Property property, CS_Status* status);
+int GetPropertyMax(CS_Property property, CS_Status* status);
+int GetPropertyStep(CS_Property property, CS_Status* status);
+int GetPropertyDefault(CS_Property property, CS_Status* status);
+std::string GetStringProperty(CS_Property property, CS_Status* status);
+wpi::StringRef GetStringProperty(CS_Property property,
+                                 wpi::SmallVectorImpl<char>& buf,
+                                 CS_Status* status);
+void SetStringProperty(CS_Property property, const wpi::Twine& value,
+                       CS_Status* status);
+std::vector<std::string> GetEnumPropertyChoices(CS_Property property,
+                                                CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_source_create_func Source Creation Functions
+ * @{
+ */
+CS_Source CreateUsbCameraDev(const wpi::Twine& name, int dev,
+                             CS_Status* status);
+CS_Source CreateUsbCameraPath(const wpi::Twine& name, const wpi::Twine& path,
+                              CS_Status* status);
+CS_Source CreateHttpCamera(const wpi::Twine& name, const wpi::Twine& url,
+                           CS_HttpCameraKind kind, CS_Status* status);
+CS_Source CreateHttpCamera(const wpi::Twine& name,
+                           wpi::ArrayRef<std::string> urls,
+                           CS_HttpCameraKind kind, CS_Status* status);
+CS_Source CreateCvSource(const wpi::Twine& name, const VideoMode& mode,
+                         CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_source_func Source Functions
+ * @{
+ */
+CS_SourceKind GetSourceKind(CS_Source source, CS_Status* status);
+std::string GetSourceName(CS_Source source, CS_Status* status);
+wpi::StringRef GetSourceName(CS_Source source, wpi::SmallVectorImpl<char>& buf,
+                             CS_Status* status);
+std::string GetSourceDescription(CS_Source source, CS_Status* status);
+wpi::StringRef GetSourceDescription(CS_Source source,
+                                    wpi::SmallVectorImpl<char>& buf,
+                                    CS_Status* status);
+uint64_t GetSourceLastFrameTime(CS_Source source, CS_Status* status);
+void SetSourceConnectionStrategy(CS_Source source,
+                                 CS_ConnectionStrategy strategy,
+                                 CS_Status* status);
+bool IsSourceConnected(CS_Source source, CS_Status* status);
+bool IsSourceEnabled(CS_Source source, CS_Status* status);
+CS_Property GetSourceProperty(CS_Source source, const wpi::Twine& name,
+                              CS_Status* status);
+wpi::ArrayRef<CS_Property> EnumerateSourceProperties(
+    CS_Source source, wpi::SmallVectorImpl<CS_Property>& vec,
+    CS_Status* status);
+VideoMode GetSourceVideoMode(CS_Source source, CS_Status* status);
+bool SetSourceVideoMode(CS_Source source, const VideoMode& mode,
+                        CS_Status* status);
+bool SetSourcePixelFormat(CS_Source source, VideoMode::PixelFormat pixelFormat,
+                          CS_Status* status);
+bool SetSourceResolution(CS_Source source, int width, int height,
+                         CS_Status* status);
+bool SetSourceFPS(CS_Source source, int fps, CS_Status* status);
+bool SetSourceConfigJson(CS_Source source, wpi::StringRef config,
+                         CS_Status* status);
+bool SetSourceConfigJson(CS_Source source, const wpi::json& config,
+                         CS_Status* status);
+std::string GetSourceConfigJson(CS_Source source, CS_Status* status);
+wpi::json GetSourceConfigJsonObject(CS_Source source, CS_Status* status);
+std::vector<VideoMode> EnumerateSourceVideoModes(CS_Source source,
+                                                 CS_Status* status);
+wpi::ArrayRef<CS_Sink> EnumerateSourceSinks(CS_Source source,
+                                            wpi::SmallVectorImpl<CS_Sink>& vec,
+                                            CS_Status* status);
+CS_Source CopySource(CS_Source source, CS_Status* status);
+void ReleaseSource(CS_Source source, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_camera_property_func Camera Source Common Property Fuctions
+ * @{
+ */
+void SetCameraBrightness(CS_Source source, int brightness, CS_Status* status);
+int GetCameraBrightness(CS_Source source, CS_Status* status);
+void SetCameraWhiteBalanceAuto(CS_Source source, CS_Status* status);
+void SetCameraWhiteBalanceHoldCurrent(CS_Source source, CS_Status* status);
+void SetCameraWhiteBalanceManual(CS_Source source, int value,
+                                 CS_Status* status);
+void SetCameraExposureAuto(CS_Source source, CS_Status* status);
+void SetCameraExposureHoldCurrent(CS_Source source, CS_Status* status);
+void SetCameraExposureManual(CS_Source source, int value, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_usbcamera_func UsbCamera Source Functions
+ * @{
+ */
+std::string GetUsbCameraPath(CS_Source source, CS_Status* status);
+UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_httpcamera_func HttpCamera Source Functions
+ * @{
+ */
+CS_HttpCameraKind GetHttpCameraKind(CS_Source source, CS_Status* status);
+void SetHttpCameraUrls(CS_Source source, wpi::ArrayRef<std::string> urls,
+                       CS_Status* status);
+std::vector<std::string> GetHttpCameraUrls(CS_Source source, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_opencv_source_func OpenCV Source Functions
+ * @{
+ */
+void NotifySourceError(CS_Source source, const wpi::Twine& msg,
+                       CS_Status* status);
+void SetSourceConnected(CS_Source source, bool connected, CS_Status* status);
+void SetSourceDescription(CS_Source source, const wpi::Twine& description,
+                          CS_Status* status);
+CS_Property CreateSourceProperty(CS_Source source, const wpi::Twine& name,
+                                 CS_PropertyKind kind, int minimum, int maximum,
+                                 int step, int defaultValue, int value,
+                                 CS_Status* status);
+void SetSourceEnumPropertyChoices(CS_Source source, CS_Property property,
+                                  wpi::ArrayRef<std::string> choices,
+                                  CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_sink_create_func Sink Creation Functions
+ * @{
+ */
+CS_Sink CreateMjpegServer(const wpi::Twine& name,
+                          const wpi::Twine& listenAddress, int port,
+                          CS_Status* status);
+CS_Sink CreateCvSink(const wpi::Twine& name, CS_Status* status);
+CS_Sink CreateCvSinkCallback(const wpi::Twine& name,
+                             std::function<void(uint64_t time)> processFrame,
+                             CS_Status* status);
+
+/** @} */
+
+/**
+ * @defgroup cscore_sink_func Sink Functions
+ * @{
+ */
+CS_SinkKind GetSinkKind(CS_Sink sink, CS_Status* status);
+std::string GetSinkName(CS_Sink sink, CS_Status* status);
+wpi::StringRef GetSinkName(CS_Sink sink, wpi::SmallVectorImpl<char>& buf,
+                           CS_Status* status);
+std::string GetSinkDescription(CS_Sink sink, CS_Status* status);
+wpi::StringRef GetSinkDescription(CS_Sink sink, wpi::SmallVectorImpl<char>& buf,
+                                  CS_Status* status);
+CS_Property GetSinkProperty(CS_Sink sink, const wpi::Twine& name,
+                            CS_Status* status);
+wpi::ArrayRef<CS_Property> EnumerateSinkProperties(
+    CS_Sink sink, wpi::SmallVectorImpl<CS_Property>& vec, CS_Status* status);
+void SetSinkSource(CS_Sink sink, CS_Source source, CS_Status* status);
+CS_Property GetSinkSourceProperty(CS_Sink sink, const wpi::Twine& name,
+                                  CS_Status* status);
+bool SetSinkConfigJson(CS_Sink sink, wpi::StringRef config, CS_Status* status);
+bool SetSinkConfigJson(CS_Sink sink, const wpi::json& config,
+                       CS_Status* status);
+std::string GetSinkConfigJson(CS_Sink sink, CS_Status* status);
+wpi::json GetSinkConfigJsonObject(CS_Sink sink, CS_Status* status);
+CS_Source GetSinkSource(CS_Sink sink, CS_Status* status);
+CS_Sink CopySink(CS_Sink sink, CS_Status* status);
+void ReleaseSink(CS_Sink sink, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_mjpegserver_func MjpegServer Sink Functions
+ * @{
+ */
+std::string GetMjpegServerListenAddress(CS_Sink sink, CS_Status* status);
+int GetMjpegServerPort(CS_Sink sink, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_opencv_sink_func OpenCV Sink Functions
+ * @{
+ */
+void SetSinkDescription(CS_Sink sink, const wpi::Twine& description,
+                        CS_Status* status);
+std::string GetSinkError(CS_Sink sink, CS_Status* status);
+wpi::StringRef GetSinkError(CS_Sink sink, wpi::SmallVectorImpl<char>& buf,
+                            CS_Status* status);
+void SetSinkEnabled(CS_Sink sink, bool enabled, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_listener_func Listener Functions
+ * @{
+ */
+void SetListenerOnStart(std::function<void()> onStart);
+void SetListenerOnExit(std::function<void()> onExit);
+
+CS_Listener AddListener(std::function<void(const RawEvent& event)> callback,
+                        int eventMask, bool immediateNotify, CS_Status* status);
+
+void RemoveListener(CS_Listener handle, CS_Status* status);
+/** @} */
+
+bool NotifierDestroyed();
+
+/**
+ * @defgroup cscore_telemetry_func Telemetry Functions
+ * @{
+ */
+void SetTelemetryPeriod(double seconds);
+double GetTelemetryElapsedTime();
+int64_t GetTelemetryValue(CS_Handle handle, CS_TelemetryKind kind,
+                          CS_Status* status);
+double GetTelemetryAverageValue(CS_Handle handle, CS_TelemetryKind kind,
+                                CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_logging_func Logging Functions
+ * @{
+ */
+using LogFunc = std::function<void(unsigned int level, const char* file,
+                                   unsigned int line, const char* msg)>;
+void SetLogger(LogFunc func, unsigned int min_level);
+void SetDefaultLogger(unsigned int min_level);
+/** @} */
+
+/**
+ * @defgroup cscore_shutdown_func Library Shutdown Function
+ * @{
+ */
+void Shutdown();
+/** @} */
+
+/**
+ * @defgroup cscore_utility_func Utility Functions
+ * @{
+ */
+std::vector<UsbCameraInfo> EnumerateUsbCameras(CS_Status* status);
+
+wpi::ArrayRef<CS_Source> EnumerateSourceHandles(
+    wpi::SmallVectorImpl<CS_Source>& vec, CS_Status* status);
+wpi::ArrayRef<CS_Sink> EnumerateSinkHandles(wpi::SmallVectorImpl<CS_Sink>& vec,
+                                            CS_Status* status);
+
+std::string GetHostname();
+
+std::vector<std::string> GetNetworkInterfaces();
+/** @} */
+
+/** @} */
+
+}  // namespace cs
+
+#ifdef _WIN32
+// Disable uninitialized variable warnings
+#pragma warning(pop)
+#endif
+
+#endif  // CSCORE_CSCORE_CPP_H_
diff --git a/cscore/src/main/native/include/cscore_cv.h b/cscore/src/main/native/include/cscore_cv.h
new file mode 100644
index 0000000..650399b
--- /dev/null
+++ b/cscore/src/main/native/include/cscore_cv.h
@@ -0,0 +1,209 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CSCORE_CV_H_
+#define CSCORE_CSCORE_CV_H_
+
+#include "cscore_c.h"
+
+#ifdef CSCORE_CSCORE_RAW_CV_H_
+#error "Cannot include both cscore_cv.h and cscore_raw_cv.h in the same file"
+#endif
+
+#ifdef __cplusplus
+#include "cscore_oo.h"  // NOLINT(build/include_order)
+
+#endif
+
+#if CV_VERSION_MAJOR < 4
+
+#ifdef __cplusplus
+extern "C" {  // NOLINT(build/include_order)
+#endif
+
+struct CvMat;
+
+void CS_PutSourceFrame(CS_Source source, struct CvMat* image,
+                       CS_Status* status);
+
+uint64_t CS_GrabSinkFrame(CS_Sink sink, struct CvMat* image, CS_Status* status);
+uint64_t CS_GrabSinkFrameTimeout(CS_Sink sink, struct CvMat* image,
+                                 double timeout, CS_Status* status);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif  // CV_VERSION_MAJOR < 4
+
+#ifdef __cplusplus
+
+#include "cscore_oo.h"
+
+namespace cv {
+class Mat;
+}  // namespace cv
+
+namespace cs {
+
+/**
+ * @defgroup cscore_cpp_opencv_special cscore C functions taking a cv::Mat*
+ *
+ * These are needed for specific interop implementations.
+ * @{
+ */
+extern "C" {
+uint64_t CS_GrabSinkFrameCpp(CS_Sink sink, cv::Mat* image, CS_Status* status);
+uint64_t CS_GrabSinkFrameTimeoutCpp(CS_Sink sink, cv::Mat* image,
+                                    double timeout, CS_Status* status);
+void CS_PutSourceFrameCpp(CS_Source source, cv::Mat* image, CS_Status* status);
+}  // extern "C"
+/** @} */
+
+void PutSourceFrame(CS_Source source, cv::Mat& image, CS_Status* status);
+uint64_t GrabSinkFrame(CS_Sink sink, cv::Mat& image, CS_Status* status);
+uint64_t GrabSinkFrameTimeout(CS_Sink sink, cv::Mat& image, double timeout,
+                              CS_Status* status);
+
+/**
+ * A source for user code to provide OpenCV images as video frames.
+ * These sources require the WPILib OpenCV builds.
+ * For an alternate OpenCV, include "cscore_raw_cv.h" instead, and
+ * include your Mat header before that header.
+ */
+class CvSource : public ImageSource {
+ public:
+  CvSource() = default;
+
+  /**
+   * Create an OpenCV source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param mode Video mode being generated
+   */
+  CvSource(const wpi::Twine& name, const VideoMode& mode);
+
+  /**
+   * Create an OpenCV source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param pixelFormat Pixel format
+   * @param width width
+   * @param height height
+   * @param fps fps
+   */
+  CvSource(const wpi::Twine& name, VideoMode::PixelFormat pixelFormat,
+           int width, int height, int fps);
+
+  /**
+   * Put an OpenCV image and notify sinks.
+   *
+   * <p>Only 8-bit single-channel or 3-channel (with BGR channel order) images
+   * are supported. If the format, depth or channel order is different, use
+   * cv::Mat::convertTo() and/or cv::cvtColor() to convert it first.
+   *
+   * @param image OpenCV image
+   */
+  void PutFrame(cv::Mat& image);
+};
+
+/**
+ * A sink for user code to accept video frames as OpenCV images.
+ * These sinks require the WPILib OpenCV builds.
+ * For an alternate OpenCV, include "cscore_raw_cv.h" instead, and
+ * include your Mat header before that header.
+ */
+class CvSink : public ImageSink {
+ public:
+  CvSink() = default;
+
+  /**
+   * Create a sink for accepting OpenCV images.
+   *
+   * <p>WaitForFrame() must be called on the created sink to get each new
+   * image.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   */
+  explicit CvSink(const wpi::Twine& name);
+
+  /**
+   * Create a sink for accepting OpenCV images in a separate thread.
+   *
+   * <p>A thread will be created that calls WaitForFrame() and calls the
+   * processFrame() callback each time a new frame arrives.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param processFrame Frame processing function; will be called with a
+   *        time=0 if an error occurred.  processFrame should call GetImage()
+   *        or GetError() as needed, but should not call (except in very
+   *        unusual circumstances) WaitForImage().
+   */
+  CvSink(const wpi::Twine& name,
+         std::function<void(uint64_t time)> processFrame);
+
+  /**
+   * Wait for the next frame and get the image.
+   * Times out (returning 0) after timeout seconds.
+   * The provided image will have three 8-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in the same time base as wpi::Now(),
+   *         and is in 1 us increments.
+   */
+  uint64_t GrabFrame(cv::Mat& image, double timeout = 0.225) const;
+
+  /**
+   * Wait for the next frame and get the image.  May block forever.
+   * The provided image will have three 8-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in the same time base as wpi::Now(),
+   *         and is in 1 us increments.
+   */
+  uint64_t GrabFrameNoTimeout(cv::Mat& image) const;
+};
+
+inline CvSource::CvSource(const wpi::Twine& name, const VideoMode& mode) {
+  m_handle = CreateCvSource(name, mode, &m_status);
+}
+
+inline CvSource::CvSource(const wpi::Twine& name, VideoMode::PixelFormat format,
+                          int width, int height, int fps) {
+  m_handle =
+      CreateCvSource(name, VideoMode{format, width, height, fps}, &m_status);
+}
+
+inline void CvSource::PutFrame(cv::Mat& image) {
+  m_status = 0;
+  PutSourceFrame(m_handle, image, &m_status);
+}
+
+inline CvSink::CvSink(const wpi::Twine& name) {
+  m_handle = CreateCvSink(name, &m_status);
+}
+
+inline CvSink::CvSink(const wpi::Twine& name,
+                      std::function<void(uint64_t time)> processFrame) {
+  m_handle = CreateCvSinkCallback(name, processFrame, &m_status);
+}
+
+inline uint64_t CvSink::GrabFrame(cv::Mat& image, double timeout) const {
+  m_status = 0;
+  return GrabSinkFrameTimeout(m_handle, image, timeout, &m_status);
+}
+
+inline uint64_t CvSink::GrabFrameNoTimeout(cv::Mat& image) const {
+  m_status = 0;
+  return GrabSinkFrame(m_handle, image, &m_status);
+}
+
+}  // namespace cs
+
+#endif
+
+#endif  // CSCORE_CSCORE_CV_H_
diff --git a/cscore/src/main/native/include/cscore_oo.h b/cscore/src/main/native/include/cscore_oo.h
new file mode 100644
index 0000000..5ab0f70
--- /dev/null
+++ b/cscore/src/main/native/include/cscore_oo.h
@@ -0,0 +1,1043 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CSCORE_OO_H_
+#define CSCORE_CSCORE_OO_H_
+
+#include <initializer_list>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include "cscore_cpp.h"
+
+namespace cs {
+
+/**
+ * @defgroup cscore_oo cscore C++ object-oriented API
+ *
+ * Recommended interface for C++, identical to Java API.
+ *
+ * <p>The classes are RAII and handle reference counting internally.
+ *
+ * @{
+ */
+
+// Forward declarations so friend declarations work correctly
+class ImageSource;
+class VideoEvent;
+class VideoSink;
+class VideoSource;
+
+/**
+ * A source or sink property.
+ */
+class VideoProperty {
+  friend class ImageSource;
+  friend class VideoEvent;
+  friend class VideoSink;
+  friend class VideoSource;
+
+ public:
+  enum Kind {
+    kNone = CS_PROP_NONE,
+    kBoolean = CS_PROP_BOOLEAN,
+    kInteger = CS_PROP_INTEGER,
+    kString = CS_PROP_STRING,
+    kEnum = CS_PROP_ENUM
+  };
+
+  VideoProperty() : m_status(0), m_handle(0), m_kind(kNone) {}
+
+  std::string GetName() const;
+
+  Kind GetKind() const { return m_kind; }
+
+  explicit operator bool() const { return m_kind != kNone; }
+
+  // Kind checkers
+  bool IsBoolean() const { return m_kind == kBoolean; }
+  bool IsInteger() const { return m_kind == kInteger; }
+  bool IsString() const { return m_kind == kString; }
+  bool IsEnum() const { return m_kind == kEnum; }
+
+  int Get() const;
+  void Set(int value);
+  int GetMin() const;
+  int GetMax() const;
+  int GetStep() const;
+  int GetDefault() const;
+
+  // String-specific functions
+  std::string GetString() const;
+  wpi::StringRef GetString(wpi::SmallVectorImpl<char>& buf) const;
+  void SetString(const wpi::Twine& value);
+
+  // Enum-specific functions
+  std::vector<std::string> GetChoices() const;
+
+  CS_Status GetLastStatus() const { return m_status; }
+
+ private:
+  explicit VideoProperty(CS_Property handle);
+  VideoProperty(CS_Property handle, Kind kind);
+
+  mutable CS_Status m_status;
+  CS_Property m_handle;
+  Kind m_kind;
+};
+
+/**
+ * A source for video that provides a sequence of frames.
+ */
+class VideoSource {
+  friend class VideoEvent;
+  friend class VideoSink;
+
+ public:
+  enum Kind {
+    kUnknown = CS_SOURCE_UNKNOWN,
+    kUsb = CS_SOURCE_USB,
+    kHttp = CS_SOURCE_HTTP,
+    kCv = CS_SOURCE_CV
+  };
+
+  /** Connection strategy.  Used for SetConnectionStrategy(). */
+  enum ConnectionStrategy {
+    /**
+     * Automatically connect or disconnect based on whether any sinks are
+     * connected to this source.  This is the default behavior.
+     */
+    kConnectionAutoManage = CS_CONNECTION_AUTO_MANAGE,
+
+    /**
+     * Try to keep the connection open regardless of whether any sinks are
+     * connected.
+     */
+    kConnectionKeepOpen = CS_CONNECTION_KEEP_OPEN,
+
+    /**
+     * Never open the connection.  If this is set when the connection is open,
+     * close the connection.
+     */
+    kConnectionForceClose = CS_CONNECTION_FORCE_CLOSE
+  };
+
+  VideoSource() noexcept : m_handle(0) {}
+  VideoSource(const VideoSource& source);
+  VideoSource(VideoSource&& other) noexcept;
+  VideoSource& operator=(VideoSource other) noexcept;
+  ~VideoSource();
+
+  explicit operator bool() const { return m_handle != 0; }
+
+  int GetHandle() const { return m_handle; }
+
+  bool operator==(const VideoSource& other) const {
+    return m_handle == other.m_handle;
+  }
+
+  bool operator!=(const VideoSource& other) const { return !(*this == other); }
+
+  /**
+   * Get the kind of the source.
+   */
+  Kind GetKind() const;
+
+  /**
+   * Get the name of the source.  The name is an arbitrary identifier
+   * provided when the source is created, and should be unique.
+   */
+  std::string GetName() const;
+
+  /**
+   * Get the source description.  This is source-kind specific.
+   */
+  std::string GetDescription() const;
+
+  /**
+   * Get the last time a frame was captured.
+   * This uses the same time base as wpi::Now().
+   *
+   * @return Time in 1 us increments.
+   */
+  uint64_t GetLastFrameTime() const;
+
+  /**
+   * Sets the connection strategy.  By default, the source will automatically
+   * connect or disconnect based on whether any sinks are connected.
+   *
+   * <p>This function is non-blocking; look for either a connection open or
+   * close event or call IsConnected() to determine the connection state.
+   *
+   * @param strategy connection strategy (auto, keep open, or force close)
+   */
+  void SetConnectionStrategy(ConnectionStrategy strategy);
+
+  /**
+   * Is the source currently connected to whatever is providing the images?
+   */
+  bool IsConnected() const;
+
+  /**
+   * Gets source enable status.  This is determined with a combination of
+   * connection strategy and the number of sinks connected.
+   *
+   * @return True if enabled, false otherwise.
+   */
+  bool IsEnabled() const;
+
+  /** Get a property.
+   *
+   * @param name Property name
+   * @return Property contents (of kind Property::kNone if no property with
+   *         the given name exists)
+   */
+  VideoProperty GetProperty(const wpi::Twine& name);
+
+  /**
+   * Enumerate all properties of this source.
+   */
+  std::vector<VideoProperty> EnumerateProperties() const;
+
+  /**
+   * Get the current video mode.
+   */
+  VideoMode GetVideoMode() const;
+
+  /**
+   * Set the video mode.
+   *
+   * @param mode Video mode
+   */
+  bool SetVideoMode(const VideoMode& mode);
+
+  /**
+   * Set the video mode.
+   *
+   * @param pixelFormat desired pixel format
+   * @param width desired width
+   * @param height desired height
+   * @param fps desired FPS
+   * @return True if set successfully
+   */
+  bool SetVideoMode(VideoMode::PixelFormat pixelFormat, int width, int height,
+                    int fps);
+
+  /**
+   * Set the pixel format.
+   *
+   * @param pixelFormat desired pixel format
+   * @return True if set successfully
+   */
+  bool SetPixelFormat(VideoMode::PixelFormat pixelFormat);
+
+  /**
+   * Set the resolution.
+   *
+   * @param width desired width
+   * @param height desired height
+   * @return True if set successfully
+   */
+  bool SetResolution(int width, int height);
+
+  /**
+   * Set the frames per second (FPS).
+   *
+   * @param fps desired FPS
+   * @return True if set successfully
+   */
+  bool SetFPS(int fps);
+
+  /**
+   * Set video mode and properties from a JSON configuration string.
+   *
+   * The format of the JSON input is:
+   *
+   * <pre>
+   * {
+   *     "pixel format": "MJPEG", "YUYV", etc
+   *     "width": video mode width
+   *     "height": video mode height
+   *     "fps": video mode fps
+   *     "brightness": percentage brightness
+   *     "white balance": "auto", "hold", or value
+   *     "exposure": "auto", "hold", or value
+   *     "properties": [
+   *         {
+   *             "name": property name
+   *             "value": property value
+   *         }
+   *     ]
+   * }
+   * </pre>
+   *
+   * @param config configuration
+   * @return True if set successfully
+   */
+  bool SetConfigJson(wpi::StringRef config);
+
+  /**
+   * Set video mode and properties from a JSON configuration object.
+   *
+   * @param config configuration
+   * @return True if set successfully
+   */
+  bool SetConfigJson(const wpi::json& config);
+
+  /**
+   * Get a JSON configuration string.
+   *
+   * @return JSON configuration string
+   */
+  std::string GetConfigJson() const;
+
+  /**
+   * Get a JSON configuration object.
+   *
+   * @return JSON configuration object
+   */
+  wpi::json GetConfigJsonObject() const;
+
+  /**
+   * Get the actual FPS.
+   *
+   * <p>SetTelemetryPeriod() must be called for this to be valid.
+   *
+   * @return Actual FPS averaged over the telemetry period.
+   */
+  double GetActualFPS() const;
+
+  /**
+   * Get the data rate (in bytes per second).
+   *
+   * <p>SetTelemetryPeriod() must be called for this to be valid.
+   *
+   * @return Data rate averaged over the telemetry period.
+   */
+  double GetActualDataRate() const;
+
+  /**
+   * Enumerate all known video modes for this source.
+   */
+  std::vector<VideoMode> EnumerateVideoModes() const;
+
+  CS_Status GetLastStatus() const { return m_status; }
+
+  /**
+   * Enumerate all sinks connected to this source.
+   *
+   * @return Vector of sinks.
+   */
+  std::vector<VideoSink> EnumerateSinks();
+
+  /**
+   * Enumerate all existing sources.
+   *
+   * @return Vector of sources.
+   */
+  static std::vector<VideoSource> EnumerateSources();
+
+  friend void swap(VideoSource& first, VideoSource& second) noexcept {
+    using std::swap;
+    swap(first.m_status, second.m_status);
+    swap(first.m_handle, second.m_handle);
+  }
+
+ protected:
+  explicit VideoSource(CS_Source handle) : m_handle(handle) {}
+
+  mutable CS_Status m_status = 0;
+  CS_Source m_handle;
+};
+
+/**
+ * A source that represents a video camera.
+ */
+class VideoCamera : public VideoSource {
+ public:
+  enum WhiteBalance {
+    kFixedIndoor = 3000,
+    kFixedOutdoor1 = 4000,
+    kFixedOutdoor2 = 5000,
+    kFixedFluorescent1 = 5100,
+    kFixedFlourescent2 = 5200
+  };
+
+  VideoCamera() = default;
+
+  /**
+   * Set the brightness, as a percentage (0-100).
+   */
+  void SetBrightness(int brightness);
+
+  /**
+   * Get the brightness, as a percentage (0-100).
+   */
+  int GetBrightness();
+
+  /**
+   * Set the white balance to auto.
+   */
+  void SetWhiteBalanceAuto();
+
+  /**
+   * Set the white balance to hold current.
+   */
+  void SetWhiteBalanceHoldCurrent();
+
+  /**
+   * Set the white balance to manual, with specified color temperature.
+   */
+  void SetWhiteBalanceManual(int value);
+
+  /**
+   * Set the exposure to auto aperature.
+   */
+  void SetExposureAuto();
+
+  /**
+   * Set the exposure to hold current.
+   */
+  void SetExposureHoldCurrent();
+
+  /**
+   * Set the exposure to manual, as a percentage (0-100).
+   */
+  void SetExposureManual(int value);
+
+ protected:
+  explicit VideoCamera(CS_Source handle) : VideoSource(handle) {}
+};
+
+/**
+ * A source that represents a USB camera.
+ */
+class UsbCamera : public VideoCamera {
+ public:
+  UsbCamera() = default;
+
+  /**
+   * Create a source for a USB camera based on device number.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param dev Device number (e.g. 0 for /dev/video0)
+   */
+  UsbCamera(const wpi::Twine& name, int dev);
+
+  /**
+   * Create a source for a USB camera based on device path.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param path Path to device (e.g. "/dev/video0" on Linux)
+   */
+  UsbCamera(const wpi::Twine& name, const wpi::Twine& path);
+
+  /**
+   * Enumerate USB cameras on the local system.
+   *
+   * @return Vector of USB camera information (one for each camera)
+   */
+  static std::vector<UsbCameraInfo> EnumerateUsbCameras();
+
+  /**
+   * Get the path to the device.
+   */
+  std::string GetPath() const;
+
+  /**
+   * Get the full camera information for the device.
+   */
+  UsbCameraInfo GetInfo() const;
+
+  /**
+   * Set how verbose the camera connection messages are.
+   *
+   * @param level 0=don't display Connecting message, 1=do display message
+   */
+  void SetConnectVerbose(int level);
+};
+
+/**
+ * A source that represents a MJPEG-over-HTTP (IP) camera.
+ */
+class HttpCamera : public VideoCamera {
+ public:
+  enum HttpCameraKind {
+    kUnknown = CS_HTTP_UNKNOWN,
+    kMJPGStreamer = CS_HTTP_MJPGSTREAMER,
+    kCSCore = CS_HTTP_CSCORE,
+    kAxis = CS_HTTP_AXIS
+  };
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param url Camera URL (e.g. "http://10.x.y.11/video/stream.mjpg")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  HttpCamera(const wpi::Twine& name, const wpi::Twine& url,
+             HttpCameraKind kind = kUnknown);
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param url Camera URL (e.g. "http://10.x.y.11/video/stream.mjpg")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  HttpCamera(const wpi::Twine& name, const char* url,
+             HttpCameraKind kind = kUnknown);
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param url Camera URL (e.g. "http://10.x.y.11/video/stream.mjpg")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  HttpCamera(const wpi::Twine& name, const std::string& url,
+             HttpCameraKind kind = kUnknown);
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param urls Array of Camera URLs
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  HttpCamera(const wpi::Twine& name, wpi::ArrayRef<std::string> urls,
+             HttpCameraKind kind = kUnknown);
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param urls Array of Camera URLs
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  template <typename T>
+  HttpCamera(const wpi::Twine& name, std::initializer_list<T> urls,
+             HttpCameraKind kind = kUnknown);
+
+  /**
+   * Get the kind of HTTP camera.
+   *
+   * <p>Autodetection can result in returning a different value than the camera
+   * was created with.
+   */
+  HttpCameraKind GetHttpCameraKind() const;
+
+  /**
+   * Change the URLs used to connect to the camera.
+   */
+  void SetUrls(wpi::ArrayRef<std::string> urls);
+
+  /**
+   * Change the URLs used to connect to the camera.
+   */
+  template <typename T>
+  void SetUrls(std::initializer_list<T> urls);
+
+  /**
+   * Get the URLs used to connect to the camera.
+   */
+  std::vector<std::string> GetUrls() const;
+};
+
+/**
+ * A source that represents an Axis IP camera.
+ */
+class AxisCamera : public HttpCamera {
+  static std::string HostToUrl(const wpi::Twine& host);
+  static std::vector<std::string> HostToUrl(wpi::ArrayRef<std::string> hosts);
+  template <typename T>
+  static std::vector<std::string> HostToUrl(std::initializer_list<T> hosts);
+
+ public:
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  AxisCamera(const wpi::Twine& name, const wpi::Twine& host);
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  AxisCamera(const wpi::Twine& name, const char* host);
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  AxisCamera(const wpi::Twine& name, const std::string& host);
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  AxisCamera(const wpi::Twine& name, wpi::StringRef host);
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param hosts Array of Camera host IPs/DNS names
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  AxisCamera(const wpi::Twine& name, wpi::ArrayRef<std::string> hosts);
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param hosts Array of Camera host IPs/DNS names
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  template <typename T>
+  AxisCamera(const wpi::Twine& name, std::initializer_list<T> hosts);
+};
+
+/**
+ * A base class for single image providing sources.
+ */
+class ImageSource : public VideoSource {
+ protected:
+  ImageSource() = default;
+
+ public:
+  /**
+   * Signal sinks that an error has occurred.  This should be called instead
+   * of NotifyFrame when an error occurs.
+   */
+  void NotifyError(const wpi::Twine& msg);
+
+  /**
+   * Set source connection status.  Defaults to true.
+   *
+   * @param connected True for connected, false for disconnected
+   */
+  void SetConnected(bool connected);
+
+  /**
+   * Set source description.
+   *
+   * @param description Description
+   */
+  void SetDescription(const wpi::Twine& description);
+
+  /**
+   * Create a property.
+   *
+   * @param name Property name
+   * @param kind Property kind
+   * @param minimum Minimum value
+   * @param maximum Maximum value
+   * @param step Step value
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  VideoProperty CreateProperty(const wpi::Twine& name, VideoProperty::Kind kind,
+                               int minimum, int maximum, int step,
+                               int defaultValue, int value);
+
+  /**
+   * Create an integer property.
+   *
+   * @param name Property name
+   * @param minimum Minimum value
+   * @param maximum Maximum value
+   * @param step Step value
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  VideoProperty CreateIntegerProperty(const wpi::Twine& name, int minimum,
+                                      int maximum, int step, int defaultValue,
+                                      int value);
+
+  /**
+   * Create a boolean property.
+   *
+   * @param name Property name
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  VideoProperty CreateBooleanProperty(const wpi::Twine& name, bool defaultValue,
+                                      bool value);
+
+  /**
+   * Create a string property.
+   *
+   * @param name Property name
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  VideoProperty CreateStringProperty(const wpi::Twine& name,
+                                     const wpi::Twine& value);
+
+  /**
+   * Configure enum property choices.
+   *
+   * @param property Property
+   * @param choices Choices
+   */
+  void SetEnumPropertyChoices(const VideoProperty& property,
+                              wpi::ArrayRef<std::string> choices);
+
+  /**
+   * Configure enum property choices.
+   *
+   * @param property Property
+   * @param choices Choices
+   */
+  template <typename T>
+  void SetEnumPropertyChoices(const VideoProperty& property,
+                              std::initializer_list<T> choices);
+};
+
+/**
+ * A sink for video that accepts a sequence of frames.
+ */
+class VideoSink {
+  friend class VideoEvent;
+  friend class VideoSource;
+
+ public:
+  enum Kind {
+    kUnknown = CS_SINK_UNKNOWN,
+    kMjpeg = CS_SINK_MJPEG,
+    kCv = CS_SINK_CV
+  };
+
+  VideoSink() noexcept : m_handle(0) {}
+  VideoSink(const VideoSink& sink);
+  VideoSink(VideoSink&& sink) noexcept;
+  VideoSink& operator=(VideoSink other) noexcept;
+  ~VideoSink();
+
+  explicit operator bool() const { return m_handle != 0; }
+
+  int GetHandle() const { return m_handle; }
+
+  bool operator==(const VideoSink& other) const {
+    return m_handle == other.m_handle;
+  }
+
+  bool operator!=(const VideoSink& other) const { return !(*this == other); }
+
+  /**
+   * Get the kind of the sink.
+   */
+  Kind GetKind() const;
+
+  /**
+   * Get the name of the sink.  The name is an arbitrary identifier
+   * provided when the sink is created, and should be unique.
+   */
+  std::string GetName() const;
+
+  /**
+   * Get the sink description.  This is sink-kind specific.
+   */
+  std::string GetDescription() const;
+
+  /**
+   * Get a property of the sink.
+   *
+   * @param name Property name
+   * @return Property (kind Property::kNone if no property with
+   *         the given name exists)
+   */
+  VideoProperty GetProperty(const wpi::Twine& name);
+
+  /**
+   * Enumerate all properties of this sink.
+   */
+  std::vector<VideoProperty> EnumerateProperties() const;
+
+  /**
+   * Set properties from a JSON configuration string.
+   *
+   * The format of the JSON input is:
+   *
+   * <pre>
+   * {
+   *     "properties": [
+   *         {
+   *             "name": property name
+   *             "value": property value
+   *         }
+   *     ]
+   * }
+   * </pre>
+   *
+   * @param config configuration
+   * @return True if set successfully
+   */
+  bool SetConfigJson(wpi::StringRef config);
+
+  /**
+   * Set properties from a JSON configuration object.
+   *
+   * @param config configuration
+   * @return True if set successfully
+   */
+  bool SetConfigJson(const wpi::json& config);
+
+  /**
+   * Get a JSON configuration string.
+   *
+   * @return JSON configuration string
+   */
+  std::string GetConfigJson() const;
+
+  /**
+   * Get a JSON configuration object.
+   *
+   * @return JSON configuration object
+   */
+  wpi::json GetConfigJsonObject() const;
+
+  /**
+   * Configure which source should provide frames to this sink.  Each sink
+   * can accept frames from only a single source, but a single source can
+   * provide frames to multiple clients.
+   *
+   * @param source Source
+   */
+  void SetSource(VideoSource source);
+
+  /**
+   * Get the connected source.
+   *
+   * @return Connected source (empty if none connected).
+   */
+  VideoSource GetSource() const;
+
+  /**
+   * Get a property of the associated source.
+   *
+   * @param name Property name
+   * @return Property (kind Property::kNone if no property with
+   *         the given name exists or no source connected)
+   */
+  VideoProperty GetSourceProperty(const wpi::Twine& name);
+
+  CS_Status GetLastStatus() const { return m_status; }
+
+  /**
+   * Enumerate all existing sinks.
+   *
+   * @return Vector of sinks.
+   */
+  static std::vector<VideoSink> EnumerateSinks();
+
+  friend void swap(VideoSink& first, VideoSink& second) noexcept {
+    using std::swap;
+    swap(first.m_status, second.m_status);
+    swap(first.m_handle, second.m_handle);
+  }
+
+ protected:
+  explicit VideoSink(CS_Sink handle) : m_handle(handle) {}
+
+  mutable CS_Status m_status = 0;
+  CS_Sink m_handle;
+};
+
+/**
+ * A sink that acts as a MJPEG-over-HTTP network server.
+ */
+class MjpegServer : public VideoSink {
+ public:
+  MjpegServer() = default;
+
+  /**
+   * Create a MJPEG-over-HTTP server sink.
+   *
+   * @param name Sink name (arbitrary unique identifier)
+   * @param listenAddress TCP listen address (empty string for all addresses)
+   * @param port TCP port number
+   */
+  MjpegServer(const wpi::Twine& name, const wpi::Twine& listenAddress,
+              int port);
+
+  /**
+   * Create a MJPEG-over-HTTP server sink.
+   *
+   * @param name Sink name (arbitrary unique identifier)
+   * @param port TCP port number
+   */
+  MjpegServer(const wpi::Twine& name, int port) : MjpegServer(name, "", port) {}
+
+  /**
+   * Get the listen address of the server.
+   */
+  std::string GetListenAddress() const;
+
+  /**
+   * Get the port number of the server.
+   */
+  int GetPort() const;
+
+  /**
+   * Set the stream resolution for clients that don't specify it.
+   *
+   * <p>It is not necessary to set this if it is the same as the source
+   * resolution.
+   *
+   * <p>Setting this different than the source resolution will result in
+   * increased CPU usage, particularly for MJPEG source cameras, as it will
+   * decompress, resize, and recompress the image, instead of using the
+   * camera's MJPEG image directly.
+   *
+   * @param width width, 0 for unspecified
+   * @param height height, 0 for unspecified
+   */
+  void SetResolution(int width, int height);
+
+  /**
+   * Set the stream frames per second (FPS) for clients that don't specify it.
+   *
+   * <p>It is not necessary to set this if it is the same as the source FPS.
+   *
+   * @param fps FPS, 0 for unspecified
+   */
+  void SetFPS(int fps);
+
+  /**
+   * Set the compression for clients that don't specify it.
+   *
+   * <p>Setting this will result in increased CPU usage for MJPEG source cameras
+   * as it will decompress and recompress the image instead of using the
+   * camera's MJPEG image directly.
+   *
+   * @param quality JPEG compression quality (0-100), -1 for unspecified
+   */
+  void SetCompression(int quality);
+
+  /**
+   * Set the default compression used for non-MJPEG sources.  If not set,
+   * 80 is used.  This function has no effect on MJPEG source cameras; use
+   * SetCompression() instead to force recompression of MJPEG source images.
+   *
+   * @param quality JPEG compression quality (0-100)
+   */
+  void SetDefaultCompression(int quality);
+};
+
+/**
+ * A base class for single image reading sinks.
+ */
+class ImageSink : public VideoSink {
+ protected:
+  ImageSink() = default;
+
+ public:
+  /**
+   * Set sink description.
+   *
+   * @param description Description
+   */
+  void SetDescription(const wpi::Twine& description);
+
+  /**
+   * Get error string.  Call this if WaitForFrame() returns 0 to determine
+   * what the error is.
+   */
+  std::string GetError() const;
+
+  /**
+   * Enable or disable getting new frames.
+   *
+   * <p>Disabling will cause processFrame (for callback-based CvSinks) to not
+   * be called and WaitForFrame() to not return.  This can be used to save
+   * processor resources when frames are not needed.
+   */
+  void SetEnabled(bool enabled);
+};
+
+/**
+ * An event generated by the library and provided to event listeners.
+ */
+class VideoEvent : public RawEvent {
+ public:
+  /**
+   * Get the source associated with the event (if any).
+   */
+  VideoSource GetSource() const;
+
+  /**
+   * Get the sink associated with the event (if any).
+   */
+  VideoSink GetSink() const;
+
+  /**
+   * Get the property associated with the event (if any).
+   */
+  VideoProperty GetProperty() const;
+};
+
+/**
+ * An event listener.  This calls back to a desigated callback function when
+ * an event matching the specified mask is generated by the library.
+ */
+class VideoListener {
+ public:
+  VideoListener() : m_handle(0) {}
+
+  /**
+   * Create an event listener.
+   *
+   * @param callback Callback function
+   * @param eventMask Bitmask of VideoEvent::Kind values
+   * @param immediateNotify Whether callback should be immediately called with
+   *        a representative set of events for the current library state.
+   */
+  VideoListener(std::function<void(const VideoEvent& event)> callback,
+                int eventMask, bool immediateNotify);
+
+  VideoListener(const VideoListener&) = delete;
+  VideoListener& operator=(const VideoListener&) = delete;
+  VideoListener(VideoListener&& other) noexcept;
+  VideoListener& operator=(VideoListener&& other) noexcept;
+  ~VideoListener();
+
+  friend void swap(VideoListener& first, VideoListener& second) noexcept {
+    using std::swap;
+    swap(first.m_handle, second.m_handle);
+  }
+
+ private:
+  CS_Listener m_handle;
+};
+
+/** @} */
+
+}  // namespace cs
+
+#include "cscore_oo.inl"
+
+#endif  // CSCORE_CSCORE_OO_H_
diff --git a/cscore/src/main/native/include/cscore_oo.inl b/cscore/src/main/native/include/cscore_oo.inl
new file mode 100644
index 0000000..ffd2b23
--- /dev/null
+++ b/cscore/src/main/native/include/cscore_oo.inl
@@ -0,0 +1,621 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_OO_INL_
+#define CSCORE_OO_INL_
+
+namespace cs {
+
+inline std::string VideoProperty::GetName() const {
+  m_status = 0;
+  return GetPropertyName(m_handle, &m_status);
+}
+
+inline int VideoProperty::Get() const {
+  m_status = 0;
+  return GetProperty(m_handle, &m_status);
+}
+
+inline void VideoProperty::Set(int value) {
+  m_status = 0;
+  SetProperty(m_handle, value, &m_status);
+}
+
+inline int VideoProperty::GetMin() const {
+  m_status = 0;
+  return GetPropertyMin(m_handle, &m_status);
+}
+
+inline int VideoProperty::GetMax() const {
+  m_status = 0;
+  return GetPropertyMax(m_handle, &m_status);
+}
+
+inline int VideoProperty::GetStep() const {
+  m_status = 0;
+  return GetPropertyStep(m_handle, &m_status);
+}
+
+inline int VideoProperty::GetDefault() const {
+  m_status = 0;
+  return GetPropertyDefault(m_handle, &m_status);
+}
+
+inline std::string VideoProperty::GetString() const {
+  m_status = 0;
+  return GetStringProperty(m_handle, &m_status);
+}
+
+inline wpi::StringRef VideoProperty::GetString(
+    wpi::SmallVectorImpl<char>& buf) const {
+  m_status = 0;
+  return GetStringProperty(m_handle, buf, &m_status);
+}
+
+inline void VideoProperty::SetString(const wpi::Twine& value) {
+  m_status = 0;
+  SetStringProperty(m_handle, value, &m_status);
+}
+
+inline std::vector<std::string> VideoProperty::GetChoices() const {
+  m_status = 0;
+  return GetEnumPropertyChoices(m_handle, &m_status);
+}
+
+inline VideoProperty::VideoProperty(CS_Property handle) : m_handle(handle) {
+  m_status = 0;
+  if (handle == 0)
+    m_kind = kNone;
+  else
+    m_kind =
+        static_cast<Kind>(static_cast<int>(GetPropertyKind(handle, &m_status)));
+}
+
+inline VideoProperty::VideoProperty(CS_Property handle, Kind kind)
+  : m_status(0), m_handle(handle), m_kind(kind) {}
+
+inline VideoSource::VideoSource(const VideoSource& source)
+    : m_handle(source.m_handle == 0 ? 0
+                                    : CopySource(source.m_handle, &m_status)) {}
+
+inline VideoSource::VideoSource(VideoSource&& other) noexcept : VideoSource() {
+  swap(*this, other);
+}
+
+inline VideoSource& VideoSource::operator=(VideoSource other) noexcept {
+  swap(*this, other);
+  return *this;
+}
+
+inline VideoSource::~VideoSource() {
+  m_status = 0;
+  if (m_handle != 0) ReleaseSource(m_handle, &m_status);
+}
+
+inline VideoSource::Kind VideoSource::GetKind() const {
+  m_status = 0;
+  return static_cast<VideoSource::Kind>(GetSourceKind(m_handle, &m_status));
+}
+
+inline std::string VideoSource::GetName() const {
+  m_status = 0;
+  return GetSourceName(m_handle, &m_status);
+}
+
+inline std::string VideoSource::GetDescription() const {
+  m_status = 0;
+  return GetSourceDescription(m_handle, &m_status);
+}
+
+inline uint64_t VideoSource::GetLastFrameTime() const {
+  m_status = 0;
+  return GetSourceLastFrameTime(m_handle, &m_status);
+}
+
+inline void VideoSource::SetConnectionStrategy(ConnectionStrategy strategy) {
+  m_status = 0;
+  SetSourceConnectionStrategy(
+      m_handle, static_cast<CS_ConnectionStrategy>(static_cast<int>(strategy)),
+      &m_status);
+}
+
+inline bool VideoSource::IsConnected() const {
+  m_status = 0;
+  return IsSourceConnected(m_handle, &m_status);
+}
+
+inline bool VideoSource::IsEnabled() const {
+  m_status = 0;
+  return IsSourceEnabled(m_handle, &m_status);
+}
+
+inline VideoProperty VideoSource::GetProperty(const wpi::Twine& name) {
+  m_status = 0;
+  return VideoProperty{GetSourceProperty(m_handle, name, &m_status)};
+}
+
+inline VideoMode VideoSource::GetVideoMode() const {
+  m_status = 0;
+  return GetSourceVideoMode(m_handle, &m_status);
+}
+
+inline bool VideoSource::SetVideoMode(const VideoMode& mode) {
+  m_status = 0;
+  return SetSourceVideoMode(m_handle, mode, &m_status);
+}
+
+inline bool VideoSource::SetVideoMode(VideoMode::PixelFormat pixelFormat,
+                                      int width, int height, int fps) {
+  m_status = 0;
+  return SetSourceVideoMode(
+      m_handle, VideoMode{pixelFormat, width, height, fps}, &m_status);
+}
+
+inline bool VideoSource::SetPixelFormat(VideoMode::PixelFormat pixelFormat) {
+  m_status = 0;
+  return SetSourcePixelFormat(m_handle, pixelFormat, &m_status);
+}
+
+inline bool VideoSource::SetResolution(int width, int height) {
+  m_status = 0;
+  return SetSourceResolution(m_handle, width, height, &m_status);
+}
+
+inline bool VideoSource::SetFPS(int fps) {
+  m_status = 0;
+  return SetSourceFPS(m_handle, fps, &m_status);
+}
+
+inline bool VideoSource::SetConfigJson(wpi::StringRef config) {
+  m_status = 0;
+  return SetSourceConfigJson(m_handle, config, &m_status);
+}
+
+inline bool VideoSource::SetConfigJson(const wpi::json& config) {
+  m_status = 0;
+  return SetSourceConfigJson(m_handle, config, &m_status);
+}
+
+inline std::string VideoSource::GetConfigJson() const {
+  m_status = 0;
+  return GetSourceConfigJson(m_handle, &m_status);
+}
+
+inline double VideoSource::GetActualFPS() const {
+  m_status = 0;
+  return cs::GetTelemetryAverageValue(m_handle, CS_SOURCE_FRAMES_RECEIVED,
+                                      &m_status);
+}
+
+inline double VideoSource::GetActualDataRate() const {
+  m_status = 0;
+  return cs::GetTelemetryAverageValue(m_handle, CS_SOURCE_BYTES_RECEIVED,
+                                      &m_status);
+}
+
+inline std::vector<VideoMode> VideoSource::EnumerateVideoModes() const {
+  CS_Status status = 0;
+  return EnumerateSourceVideoModes(m_handle, &status);
+}
+
+inline void VideoCamera::SetBrightness(int brightness) {
+  m_status = 0;
+  SetCameraBrightness(m_handle, brightness, &m_status);
+}
+
+inline int VideoCamera::GetBrightness() {
+  m_status = 0;
+  return GetCameraBrightness(m_handle, &m_status);
+}
+
+inline void VideoCamera::SetWhiteBalanceAuto() {
+  m_status = 0;
+  SetCameraWhiteBalanceAuto(m_handle, &m_status);
+}
+
+inline void VideoCamera::SetWhiteBalanceHoldCurrent() {
+  m_status = 0;
+  SetCameraWhiteBalanceHoldCurrent(m_handle, &m_status);
+}
+
+inline void VideoCamera::SetWhiteBalanceManual(int value) {
+  m_status = 0;
+  SetCameraWhiteBalanceManual(m_handle, value, &m_status);
+}
+
+inline void VideoCamera::SetExposureAuto() {
+  m_status = 0;
+  SetCameraExposureAuto(m_handle, &m_status);
+}
+
+inline void VideoCamera::SetExposureHoldCurrent() {
+  m_status = 0;
+  SetCameraExposureHoldCurrent(m_handle, &m_status);
+}
+
+inline void VideoCamera::SetExposureManual(int value) {
+  m_status = 0;
+  SetCameraExposureManual(m_handle, value, &m_status);
+}
+
+inline UsbCamera::UsbCamera(const wpi::Twine& name, int dev) {
+  m_handle = CreateUsbCameraDev(name, dev, &m_status);
+}
+
+inline UsbCamera::UsbCamera(const wpi::Twine& name, const wpi::Twine& path) {
+  m_handle = CreateUsbCameraPath(name, path, &m_status);
+}
+
+inline std::vector<UsbCameraInfo> UsbCamera::EnumerateUsbCameras() {
+  CS_Status status = 0;
+  return ::cs::EnumerateUsbCameras(&status);
+}
+
+inline std::string UsbCamera::GetPath() const {
+  m_status = 0;
+  return ::cs::GetUsbCameraPath(m_handle, &m_status);
+}
+
+inline UsbCameraInfo UsbCamera::GetInfo() const {
+  m_status = 0;
+  return ::cs::GetUsbCameraInfo(m_handle, &m_status);
+}
+
+inline void UsbCamera::SetConnectVerbose(int level) {
+  m_status = 0;
+  SetProperty(GetSourceProperty(m_handle, "connect_verbose", &m_status), level,
+              &m_status);
+}
+
+inline HttpCamera::HttpCamera(const wpi::Twine& name, const wpi::Twine& url,
+                              HttpCameraKind kind) {
+  m_handle = CreateHttpCamera(
+      name, url, static_cast<CS_HttpCameraKind>(static_cast<int>(kind)),
+      &m_status);
+}
+
+inline HttpCamera::HttpCamera(const wpi::Twine& name, const char* url,
+                              HttpCameraKind kind) {
+  m_handle = CreateHttpCamera(
+      name, url, static_cast<CS_HttpCameraKind>(static_cast<int>(kind)),
+      &m_status);
+}
+
+inline HttpCamera::HttpCamera(const wpi::Twine& name, const std::string& url,
+                              HttpCameraKind kind)
+    : HttpCamera(name, wpi::Twine{url}, kind) {}
+
+inline HttpCamera::HttpCamera(const wpi::Twine& name,
+                              wpi::ArrayRef<std::string> urls,
+                              HttpCameraKind kind) {
+  m_handle = CreateHttpCamera(
+      name, urls, static_cast<CS_HttpCameraKind>(static_cast<int>(kind)),
+      &m_status);
+}
+
+template <typename T>
+inline HttpCamera::HttpCamera(const wpi::Twine& name,
+                              std::initializer_list<T> urls,
+                              HttpCameraKind kind) {
+  std::vector<std::string> vec;
+  vec.reserve(urls.size());
+  for (const auto& url : urls) vec.emplace_back(url);
+  m_handle = CreateHttpCamera(
+      name, vec, static_cast<CS_HttpCameraKind>(static_cast<int>(kind)),
+      &m_status);
+}
+
+inline HttpCamera::HttpCameraKind HttpCamera::GetHttpCameraKind() const {
+  m_status = 0;
+  return static_cast<HttpCameraKind>(
+      static_cast<int>(::cs::GetHttpCameraKind(m_handle, &m_status)));
+}
+
+inline void HttpCamera::SetUrls(wpi::ArrayRef<std::string> urls) {
+  m_status = 0;
+  ::cs::SetHttpCameraUrls(m_handle, urls, &m_status);
+}
+
+template <typename T>
+inline void HttpCamera::SetUrls(std::initializer_list<T> urls) {
+  std::vector<std::string> vec;
+  vec.reserve(urls.size());
+  for (const auto& url : urls) vec.emplace_back(url);
+  m_status = 0;
+  ::cs::SetHttpCameraUrls(m_handle, vec, &m_status);
+}
+
+inline std::vector<std::string> HttpCamera::GetUrls() const {
+  m_status = 0;
+  return ::cs::GetHttpCameraUrls(m_handle, &m_status);
+}
+
+inline std::string AxisCamera::HostToUrl(const wpi::Twine& host) {
+  return ("http://" + host + "/mjpg/video.mjpg").str();
+}
+
+inline std::vector<std::string> AxisCamera::HostToUrl(
+    wpi::ArrayRef<std::string> hosts) {
+  std::vector<std::string> rv;
+  rv.reserve(hosts.size());
+  for (const auto& host : hosts)
+    rv.emplace_back(HostToUrl(wpi::StringRef{host}));
+  return rv;
+}
+
+template <typename T>
+inline std::vector<std::string> AxisCamera::HostToUrl(
+    std::initializer_list<T> hosts) {
+  std::vector<std::string> rv;
+  rv.reserve(hosts.size());
+  for (const auto& host : hosts)
+    rv.emplace_back(HostToUrl(wpi::StringRef{host}));
+  return rv;
+}
+
+inline AxisCamera::AxisCamera(const wpi::Twine& name, const wpi::Twine& host)
+    : HttpCamera(name, HostToUrl(host), kAxis) {}
+
+inline AxisCamera::AxisCamera(const wpi::Twine& name, const char* host)
+    : HttpCamera(name, HostToUrl(host), kAxis) {}
+
+inline AxisCamera::AxisCamera(const wpi::Twine& name, const std::string& host)
+    : HttpCamera(name, HostToUrl(wpi::Twine{host}), kAxis) {}
+
+inline AxisCamera::AxisCamera(const wpi::Twine& name, wpi::StringRef host)
+    : HttpCamera(name, HostToUrl(host), kAxis) {}
+
+inline AxisCamera::AxisCamera(const wpi::Twine& name,
+                              wpi::ArrayRef<std::string> hosts)
+    : HttpCamera(name, HostToUrl(hosts), kAxis) {}
+
+template <typename T>
+inline AxisCamera::AxisCamera(const wpi::Twine& name,
+                              std::initializer_list<T> hosts)
+    : HttpCamera(name, HostToUrl(hosts), kAxis) {}
+
+inline void ImageSource::NotifyError(const wpi::Twine& msg) {
+  m_status = 0;
+  NotifySourceError(m_handle, msg, &m_status);
+}
+
+inline void ImageSource::SetConnected(bool connected) {
+  m_status = 0;
+  SetSourceConnected(m_handle, connected, &m_status);
+}
+
+inline void ImageSource::SetDescription(const wpi::Twine& description) {
+  m_status = 0;
+  SetSourceDescription(m_handle, description, &m_status);
+}
+
+inline VideoProperty ImageSource::CreateProperty(const wpi::Twine& name,
+                                              VideoProperty::Kind kind,
+                                              int minimum, int maximum,
+                                              int step, int defaultValue,
+                                              int value) {
+  m_status = 0;
+  return VideoProperty{CreateSourceProperty(
+      m_handle, name, static_cast<CS_PropertyKind>(static_cast<int>(kind)),
+      minimum, maximum, step, defaultValue, value, &m_status)};
+}
+
+inline VideoProperty ImageSource::CreateIntegerProperty(const wpi::Twine& name,
+                                                    int minimum, int maximum,
+                                                    int step, int defaultValue,
+                                                    int value) {
+  m_status = 0;
+  return VideoProperty{CreateSourceProperty(
+      m_handle, name, static_cast<CS_PropertyKind>(static_cast<int>(VideoProperty::Kind::kInteger)),
+      minimum, maximum, step, defaultValue, value, &m_status)};
+}
+
+inline VideoProperty ImageSource::CreateBooleanProperty(const wpi::Twine& name,
+                                                     bool defaultValue,
+                                                     bool value) {
+  m_status = 0;
+  return VideoProperty{CreateSourceProperty(
+      m_handle, name, static_cast<CS_PropertyKind>(static_cast<int>(VideoProperty::Kind::kBoolean)),
+      0, 1, 1, defaultValue ? 1 : 0, value ? 1 : 0, &m_status)};
+}
+
+inline VideoProperty ImageSource::CreateStringProperty(const wpi::Twine& name,
+                                                    const wpi::Twine& value) {
+  m_status = 0;
+  auto prop = VideoProperty{CreateSourceProperty(
+      m_handle, name, static_cast<CS_PropertyKind>(static_cast<int>(VideoProperty::Kind::kString)),
+      0, 0, 0, 0, 0, &m_status)};
+  prop.SetString(value);
+  return prop;
+}
+
+
+inline void ImageSource::SetEnumPropertyChoices(
+    const VideoProperty& property, wpi::ArrayRef<std::string> choices) {
+  m_status = 0;
+  SetSourceEnumPropertyChoices(m_handle, property.m_handle, choices, &m_status);
+}
+
+template <typename T>
+inline void ImageSource::SetEnumPropertyChoices(const VideoProperty& property,
+                                             std::initializer_list<T> choices) {
+  std::vector<std::string> vec;
+  vec.reserve(choices.size());
+  for (const auto& choice : choices) vec.emplace_back(choice);
+  m_status = 0;
+  SetSourceEnumPropertyChoices(m_handle, property.m_handle, vec, &m_status);
+}
+
+inline VideoSink::VideoSink(const VideoSink& sink)
+    : m_handle(sink.m_handle == 0 ? 0 : CopySink(sink.m_handle, &m_status)) {}
+
+inline VideoSink::VideoSink(VideoSink&& other) noexcept : VideoSink() {
+  swap(*this, other);
+}
+
+inline VideoSink& VideoSink::operator=(VideoSink other) noexcept {
+  swap(*this, other);
+  return *this;
+}
+
+inline VideoSink::~VideoSink() {
+  m_status = 0;
+  if (m_handle != 0) ReleaseSink(m_handle, &m_status);
+}
+
+inline VideoSink::Kind VideoSink::GetKind() const {
+  m_status = 0;
+  return static_cast<VideoSink::Kind>(GetSinkKind(m_handle, &m_status));
+}
+
+inline std::string VideoSink::GetName() const {
+  m_status = 0;
+  return GetSinkName(m_handle, &m_status);
+}
+
+inline std::string VideoSink::GetDescription() const {
+  m_status = 0;
+  return GetSinkDescription(m_handle, &m_status);
+}
+
+inline VideoProperty VideoSink::GetProperty(const wpi::Twine& name) {
+  m_status = 0;
+  return VideoProperty{GetSinkProperty(m_handle, name, &m_status)};
+}
+
+inline void VideoSink::SetSource(VideoSource source) {
+  m_status = 0;
+  if (!source)
+    SetSinkSource(m_handle, 0, &m_status);
+  else
+    SetSinkSource(m_handle, source.m_handle, &m_status);
+}
+
+inline VideoSource VideoSink::GetSource() const {
+  m_status = 0;
+  auto handle = GetSinkSource(m_handle, &m_status);
+  return VideoSource{handle == 0 ? 0 : CopySource(handle, &m_status)};
+}
+
+inline VideoProperty VideoSink::GetSourceProperty(const wpi::Twine& name) {
+  m_status = 0;
+  return VideoProperty{GetSinkSourceProperty(m_handle, name, &m_status)};
+}
+
+inline bool VideoSink::SetConfigJson(wpi::StringRef config) {
+  m_status = 0;
+  return SetSinkConfigJson(m_handle, config, &m_status);
+}
+
+inline bool VideoSink::SetConfigJson(const wpi::json& config) {
+  m_status = 0;
+  return SetSinkConfigJson(m_handle, config, &m_status);
+}
+
+inline std::string VideoSink::GetConfigJson() const {
+  m_status = 0;
+  return GetSinkConfigJson(m_handle, &m_status);
+}
+
+inline MjpegServer::MjpegServer(const wpi::Twine& name,
+                                const wpi::Twine& listenAddress, int port) {
+  m_handle = CreateMjpegServer(name, listenAddress, port, &m_status);
+}
+
+inline std::string MjpegServer::GetListenAddress() const {
+  m_status = 0;
+  return cs::GetMjpegServerListenAddress(m_handle, &m_status);
+}
+
+inline int MjpegServer::GetPort() const {
+  m_status = 0;
+  return cs::GetMjpegServerPort(m_handle, &m_status);
+}
+
+inline void MjpegServer::SetResolution(int width, int height) {
+  m_status = 0;
+  SetProperty(GetSinkProperty(m_handle, "width", &m_status), width, &m_status);
+  SetProperty(GetSinkProperty(m_handle, "height", &m_status), height,
+              &m_status);
+}
+
+inline void MjpegServer::SetFPS(int fps) {
+  m_status = 0;
+  SetProperty(GetSinkProperty(m_handle, "fps", &m_status), fps, &m_status);
+}
+
+inline void MjpegServer::SetCompression(int quality) {
+  m_status = 0;
+  SetProperty(GetSinkProperty(m_handle, "compression", &m_status), quality,
+              &m_status);
+}
+
+inline void MjpegServer::SetDefaultCompression(int quality) {
+  m_status = 0;
+  SetProperty(GetSinkProperty(m_handle, "default_compression", &m_status),
+              quality, &m_status);
+}
+
+inline void ImageSink::SetDescription(const wpi::Twine& description) {
+  m_status = 0;
+  SetSinkDescription(m_handle, description, &m_status);
+}
+
+inline std::string ImageSink::GetError() const {
+  m_status = 0;
+  return GetSinkError(m_handle, &m_status);
+}
+
+inline void ImageSink::SetEnabled(bool enabled) {
+  m_status = 0;
+  SetSinkEnabled(m_handle, enabled, &m_status);
+}
+
+inline VideoSource VideoEvent::GetSource() const {
+  CS_Status status = 0;
+  return VideoSource{sourceHandle == 0 ? 0 : CopySource(sourceHandle, &status)};
+}
+
+inline VideoSink VideoEvent::GetSink() const {
+  CS_Status status = 0;
+  return VideoSink{sinkHandle == 0 ? 0 : CopySink(sinkHandle, &status)};
+}
+
+inline VideoProperty VideoEvent::GetProperty() const {
+  return VideoProperty{propertyHandle,
+                       static_cast<VideoProperty::Kind>(propertyKind)};
+}
+
+inline VideoListener::VideoListener(
+    std::function<void(const VideoEvent& event)> callback, int eventMask,
+    bool immediateNotify) {
+  CS_Status status = 0;
+  m_handle = AddListener(
+      [=](const RawEvent& event) {
+        callback(static_cast<const VideoEvent&>(event));
+      },
+      eventMask, immediateNotify, &status);
+}
+
+inline VideoListener::VideoListener(VideoListener&& other) noexcept
+    : VideoListener() {
+  swap(*this, other);
+}
+
+inline VideoListener& VideoListener::operator=(VideoListener&& other) noexcept {
+  swap(*this, other);
+  return *this;
+}
+
+inline VideoListener::~VideoListener() {
+  CS_Status status = 0;
+  if (m_handle != 0) RemoveListener(m_handle, &status);
+}
+
+}  // namespace cs
+
+#endif  /* CSCORE_OO_INL_ */
diff --git a/cscore/src/main/native/include/cscore_raw.h b/cscore/src/main/native/include/cscore_raw.h
new file mode 100644
index 0000000..902d90e
--- /dev/null
+++ b/cscore/src/main/native/include/cscore_raw.h
@@ -0,0 +1,234 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CSCORE_RAW_H_
+#define CSCORE_CSCORE_RAW_H_
+
+#include "cscore_c.h"
+
+#ifdef __cplusplus
+#include "cscore_oo.h"
+#endif
+
+/**
+ * Raw Frame
+ */
+typedef struct CS_RawFrame {
+  char* data;
+  int dataLength;
+  int pixelFormat;
+  int width;
+  int height;
+  int totalData;
+} CS_RawFrame;
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @defgroup cscore_raw_cfunc Raw Image Functions
+ * @{
+ */
+void CS_AllocateRawFrameData(CS_RawFrame* frame, int requestedSize);
+void CS_FreeRawFrameData(CS_RawFrame* frame);
+
+uint64_t CS_GrabRawSinkFrame(CS_Sink sink, struct CS_RawFrame* rawImage,
+                             CS_Status* status);
+uint64_t CS_GrabRawSinkFrameTimeout(CS_Sink sink, struct CS_RawFrame* rawImage,
+                                    double timeout, CS_Status* status);
+
+CS_Sink CS_CreateRawSink(const char* name, CS_Status* status);
+
+CS_Sink CS_CreateRawSinkCallback(const char* name, void* data,
+                                 void (*processFrame)(void* data,
+                                                      uint64_t time),
+                                 CS_Status* status);
+
+void CS_PutRawSourceFrame(CS_Source source, const struct CS_RawFrame* image,
+                          CS_Status* status);
+
+CS_Source CS_CreateRawSource(const char* name, const CS_VideoMode* mode,
+                             CS_Status* status);
+/** @} */
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#ifdef __cplusplus
+namespace cs {
+
+struct RawFrame : public CS_RawFrame {
+  RawFrame() {
+    data = nullptr;
+    dataLength = 0;
+    pixelFormat = CS_PIXFMT_UNKNOWN;
+    width = 0;
+    height = 0;
+    totalData = 0;
+  }
+
+  ~RawFrame() { CS_FreeRawFrameData(this); }
+};
+
+/**
+ * @defgroup cscore_raw_func Raw Image Functions
+ * @{
+ */
+
+CS_Source CreateRawSource(const wpi::Twine& name, const VideoMode& mode,
+                          CS_Status* status);
+
+CS_Sink CreateRawSink(const wpi::Twine& name, CS_Status* status);
+CS_Sink CreateRawSinkCallback(const wpi::Twine& name,
+                              std::function<void(uint64_t time)> processFrame,
+                              CS_Status* status);
+
+void PutSourceFrame(CS_Source source, const CS_RawFrame& image,
+                    CS_Status* status);
+uint64_t GrabSinkFrame(CS_Sink sink, CS_RawFrame& image, CS_Status* status);
+uint64_t GrabSinkFrameTimeout(CS_Sink sink, CS_RawFrame& image, double timeout,
+                              CS_Status* status);
+
+/**
+ * A source for user code to provide video frames as raw bytes.
+ *
+ * This is a complex API, most cases should use CvSource.
+ */
+class RawSource : public ImageSource {
+ public:
+  RawSource() = default;
+
+  /**
+   * Create a raw frame source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param mode Video mode being generated
+   */
+  RawSource(const wpi::Twine& name, const VideoMode& mode);
+
+  /**
+   * Create a raw frame source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param pixelFormat Pixel format
+   * @param width width
+   * @param height height
+   * @param fps fps
+   */
+  RawSource(const wpi::Twine& name, VideoMode::PixelFormat pixelFormat,
+            int width, int height, int fps);
+
+ protected:
+  /**
+   * Put a raw image and notify sinks.
+   *
+   * @param image raw frame image
+   */
+  void PutFrame(RawFrame& image);
+};
+
+/**
+ * A sink for user code to accept video frames as raw bytes.
+ *
+ * This is a complex API, most cases should use CvSource.
+ */
+class RawSink : public ImageSink {
+ public:
+  RawSink() = default;
+
+  /**
+   * Create a sink for accepting raw images.
+   *
+   * <p>GrabFrame() must be called on the created sink to get each new
+   * image.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   */
+  explicit RawSink(const wpi::Twine& name);
+
+  /**
+   * Create a sink for accepting raws images in a separate thread.
+   *
+   * <p>A thread will be created that calls WaitForFrame() and calls the
+   * processFrame() callback each time a new frame arrives.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param processFrame Frame processing function; will be called with a
+   *        time=0 if an error occurred.  processFrame should call GetImage()
+   *        or GetError() as needed, but should not call (except in very
+   *        unusual circumstances) WaitForImage().
+   */
+  RawSink(const wpi::Twine& name,
+          std::function<void(uint64_t time)> processFrame);
+
+ protected:
+  /**
+   * Wait for the next frame and get the image.
+   * Times out (returning 0) after timeout seconds.
+   * The provided image will have three 8-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in the same time base as wpi::Now(),
+   *         and is in 1 us increments.
+   */
+  uint64_t GrabFrame(RawFrame& image, double timeout = 0.225) const;
+
+  /**
+   * Wait for the next frame and get the image.  May block forever.
+   * The provided image will have three 8-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in the same time base as wpi::Now(),
+   *         and is in 1 us increments.
+   */
+  uint64_t GrabFrameNoTimeout(RawFrame& image) const;
+};
+
+inline RawSource::RawSource(const wpi::Twine& name, const VideoMode& mode) {
+  m_handle = CreateRawSource(name, mode, &m_status);
+}
+
+inline RawSource::RawSource(const wpi::Twine& name,
+                            VideoMode::PixelFormat format, int width,
+                            int height, int fps) {
+  m_handle =
+      CreateRawSource(name, VideoMode{format, width, height, fps}, &m_status);
+}
+
+inline void RawSource::PutFrame(RawFrame& image) {
+  m_status = 0;
+  PutSourceFrame(m_handle, image, &m_status);
+}
+
+inline RawSink::RawSink(const wpi::Twine& name) {
+  m_handle = CreateRawSink(name, &m_status);
+}
+
+inline RawSink::RawSink(const wpi::Twine& name,
+                        std::function<void(uint64_t time)> processFrame) {
+  m_handle = CreateRawSinkCallback(name, processFrame, &m_status);
+}
+
+inline uint64_t RawSink::GrabFrame(RawFrame& image, double timeout) const {
+  m_status = 0;
+  return GrabSinkFrameTimeout(m_handle, image, timeout, &m_status);
+}
+
+inline uint64_t RawSink::GrabFrameNoTimeout(RawFrame& image) const {
+  m_status = 0;
+  return GrabSinkFrame(m_handle, image, &m_status);
+}
+
+}  // namespace cs
+
+/** @} */
+
+#endif
+
+#endif  // CSCORE_CSCORE_RAW_H_
diff --git a/cscore/src/main/native/include/cscore_raw_cv.h b/cscore/src/main/native/include/cscore_raw_cv.h
new file mode 100644
index 0000000..ed40006
--- /dev/null
+++ b/cscore/src/main/native/include/cscore_raw_cv.h
@@ -0,0 +1,218 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CSCORE_RAW_CV_H_
+#define CSCORE_CSCORE_RAW_CV_H_
+
+#ifdef CSCORE_CSCORE_CV_H_
+#error "Cannot include both cscore_cv.h and cscore_raw_cv.h in the same file"
+#endif
+
+#include "cscore_raw.h"
+
+namespace cs {
+/**
+ * A source for using the raw frame API to provide opencv images.
+ *
+ * If you are using the WPILib OpenCV builds, do not use this, and
+ * instead include "cscore_cv.h" to get a more performant version.
+ *
+ * This is not dependent on any opencv binary ABI, and can be used
+ * with versions of OpenCV that are not 3. If using OpenCV 3, use
+ * CvSource.
+ */
+class RawCvSource : public RawSource {
+ public:
+  RawCvSource() = default;
+
+  /**
+   * Create a Raw OpenCV source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param mode Video mode being generated
+   */
+  RawCvSource(const wpi::Twine& name, const VideoMode& mode);
+
+  /**
+   * Create a Raw OpenCV source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param pixelFormat Pixel format
+   * @param width width
+   * @param height height
+   * @param fps fps
+   */
+  RawCvSource(const wpi::Twine& name, VideoMode::PixelFormat pixelFormat,
+              int width, int height, int fps);
+
+  /**
+   * Put an OpenCV image and notify sinks.
+   *
+   * <p>Only 8-bit single-channel or 3-channel (with BGR channel order) images
+   * are supported. If the format, depth or channel order is different, use
+   * cv::Mat::convertTo() and/or cv::cvtColor() to convert it first.
+   *
+   * @param image OpenCV image
+   */
+  void PutFrame(cv::Mat& image);
+
+ private:
+  RawFrame rawFrame;
+};
+
+/**
+ * A sink for user code to accept raw video frames as OpenCV images.
+ *
+ * If you are using the WPILib OpenCV builds, do not use this, and
+ * instead include "cscore_cv.h" to get a more performant version.
+ *
+ * This is not dependent on any opencv binary ABI, and can be used
+ * with versions of OpenCV that are not 3. If using OpenCV 3, use
+ * CvSink.
+ */
+class RawCvSink : public RawSink {
+ public:
+  RawCvSink() = default;
+
+  /**
+   * Create a sink for accepting OpenCV images.
+   *
+   * <p>WaitForFrame() must be called on the created sink to get each new
+   * image.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   */
+  explicit RawCvSink(const wpi::Twine& name);
+
+  /**
+   * Create a sink for accepting OpenCV images in a separate thread.
+   *
+   * <p>A thread will be created that calls WaitForFrame() and calls the
+   * processFrame() callback each time a new frame arrives.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param processFrame Frame processing function; will be called with a
+   *        time=0 if an error occurred.  processFrame should call GetImage()
+   *        or GetError() as needed, but should not call (except in very
+   *        unusual circumstances) WaitForImage().
+   */
+  RawCvSink(const wpi::Twine& name,
+            std::function<void(uint64_t time)> processFrame);
+
+  /**
+   * Wait for the next frame and get the image.
+   * Times out (returning 0) after timeout seconds.
+   * The provided image will have three 8-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in the same time base as wpi::Now(),
+   *         and is in 1 us increments.
+   */
+  uint64_t GrabFrame(cv::Mat& image, double timeout = 0.225);
+
+  /**
+   * Wait for the next frame and get the image.  May block forever.
+   * The provided image will have three 8-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in the same time base as wpi::Now(),
+   *         and is in 1 us increments.
+   */
+  uint64_t GrabFrameNoTimeout(cv::Mat& image);
+
+  /**
+   * Wait for the next frame and get the image.
+   * Times out (returning 0) after timeout seconds.
+   * The provided image will have three 8-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in the same time base as wpi::Now(),
+   *         and is in 1 us increments.
+   */
+  uint64_t GrabFrameDirect(cv::Mat& image, double timeout = 0.225);
+
+  /**
+   * Wait for the next frame and get the image.  May block forever.
+   * The provided image will have three 8-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in the same time base as wpi::Now(),
+   *         and is in 1 us increments.
+   */
+  uint64_t GrabFrameNoTimeoutDirect(cv::Mat& image);
+
+ private:
+  RawFrame rawFrame;
+};
+
+inline RawCvSource::RawCvSource(const wpi::Twine& name, const VideoMode& mode)
+    : RawSource{name, mode} {}
+
+inline RawCvSource::RawCvSource(const wpi::Twine& name,
+                                VideoMode::PixelFormat format, int width,
+                                int height, int fps)
+    : RawSource{name, format, width, height, fps} {}
+
+inline void RawCvSource::PutFrame(cv::Mat& image) {
+  m_status = 0;
+  rawFrame.data = reinterpret_cast<char*>(image.data);
+  rawFrame.width = image.cols;
+  rawFrame.height = image.rows;
+  rawFrame.totalData = image.total() * image.channels;
+  rawFrame.pixelFormat = image.channels == 3 ? CS_PIXFMT_BGR : CS_PIXFMT_GRAY;
+  PutSourceFrame(m_handle, rawFrame, &m_status);
+}
+
+inline RawCvSink::RawCvSink(const wpi::Twine& name) : RawSink{name} {}
+
+inline RawCvSink::RawCvSink(const wpi::Twine& name,
+                            std::function<void(uint64_t time)> processFrame)
+    : RawSink{name, processFrame} {}
+
+inline uint64_t RawCvSink::GrabFrame(cv::Mat& image, double timeout) {
+  cv::Mat tmpMat;
+  auto retVal = GrabFrameDirect(tmpMat);
+  if (retVal <= 0) {
+    return retVal;
+  }
+  tmpMat.copyTo(image);
+  return retVal;
+}
+
+inline uint64_t RawCvSink::GrabFrameNoTimeout(cv::Mat& image) {
+  cv::Mat tmpMat;
+  auto retVal = GrabFrameNoTimeoutDirect(tmpMat);
+  if (retVal <= 0) {
+    return retVal;
+  }
+  tmpMat.copyTo(image);
+  return retVal;
+}
+
+inline uint64_t RawCvSink::GrabFrameDirect(cv::Mat& image, double timeout) {
+  rawFrame.height = 0;
+  rawFrame.width = 0;
+  rawFrame.pixelFormat = CS_PixelFormat::CS_PIXFMT_BGR;
+  m_status = RawSink::GrabFrame(rawFrame, timeout);
+  if (m_status <= 0) return m_status;
+  image = cv::Mat{rawFrame.height, rawFrame.width, CV_8UC3, rawFrame.data};
+  return m_status;
+}
+
+inline uint64_t RawCvSink::GrabFrameNoTimeoutDirect(cv::Mat& image) {
+  rawFrame.height = 0;
+  rawFrame.width = 0;
+  rawFrame.pixelFormat = CS_PixelFormat::CS_PIXFMT_BGR;
+  m_status = RawSink::GrabFrameNoTimeout(rawFrame);
+  if (m_status <= 0) return m_status;
+  image = cv::Mat{rawFrame.height, rawFrame.width, CV_8UC3, rawFrame.data};
+  return m_status;
+}
+
+}  // namespace cs
+
+#endif  // CSCORE_CSCORE_RAW_CV_H_
diff --git a/cscore/src/main/native/linux/NetworkListener.cpp b/cscore/src/main/native/linux/NetworkListener.cpp
new file mode 100644
index 0000000..6915b30
--- /dev/null
+++ b/cscore/src/main/native/linux/NetworkListener.cpp
@@ -0,0 +1,148 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkListener.h"
+
+#include <linux/netlink.h>
+#include <linux/rtnetlink.h>
+#include <sys/eventfd.h>
+#include <sys/select.h>
+#include <sys/socket.h>
+#include <sys/time.h>
+#include <sys/types.h>
+#include <unistd.h>
+
+#include <cerrno>
+
+#include <wpi/SafeThread.h>
+
+#include "Log.h"
+#include "Notifier.h"
+
+using namespace cs;
+
+class NetworkListener::Impl {
+ public:
+  Impl(wpi::Logger& logger, Notifier& notifier)
+      : m_logger(logger), m_notifier(notifier) {}
+
+  wpi::Logger& m_logger;
+  Notifier& m_notifier;
+
+  class Thread : public wpi::SafeThread {
+   public:
+    Thread(wpi::Logger& logger, Notifier& notifier)
+        : m_logger(logger), m_notifier(notifier) {}
+    void Main();
+
+    wpi::Logger& m_logger;
+    Notifier& m_notifier;
+    int m_command_fd = -1;
+  };
+
+  wpi::SafeThreadOwner<Thread> m_owner;
+};
+
+NetworkListener::NetworkListener(wpi::Logger& logger, Notifier& notifier)
+    : m_impl(std::make_unique<Impl>(logger, notifier)) {}
+
+NetworkListener::~NetworkListener() { Stop(); }
+
+void NetworkListener::Start() {
+  m_impl->m_owner.Start(m_impl->m_logger, m_impl->m_notifier);
+}
+
+void NetworkListener::Stop() {
+  // Wake up thread
+  if (auto thr = m_impl->m_owner.GetThread()) {
+    thr->m_active = false;
+    if (thr->m_command_fd >= 0) eventfd_write(thr->m_command_fd, 1);
+  }
+  m_impl->m_owner.Stop();
+}
+
+void NetworkListener::Impl::Thread::Main() {
+  // Create event socket so we can be shut down
+  m_command_fd = ::eventfd(0, 0);
+  if (m_command_fd < 0) {
+    ERROR(
+        "NetworkListener: could not create eventfd: " << std::strerror(errno));
+    return;
+  }
+
+  // Create netlink socket
+  int sd = ::socket(AF_NETLINK, SOCK_RAW, NETLINK_ROUTE);
+  if (sd < 0) {
+    ERROR("NetworkListener: could not create socket: " << std::strerror(errno));
+    ::close(m_command_fd);
+    m_command_fd = -1;
+    return;
+  }
+
+  // Bind to netlink socket
+  struct sockaddr_nl addr;
+  std::memset(&addr, 0, sizeof(addr));
+  addr.nl_family = AF_NETLINK;
+  addr.nl_groups = RTMGRP_LINK | RTMGRP_IPV4_IFADDR;
+  if (bind(sd, reinterpret_cast<struct sockaddr*>(&addr), sizeof(addr)) < 0) {
+    ERROR("NetworkListener: could not create socket: " << std::strerror(errno));
+    ::close(sd);
+    ::close(m_command_fd);
+    m_command_fd = -1;
+    return;
+  }
+
+  char buf[4096];
+
+  while (m_active) {
+    // select timeout
+    struct timeval tv;
+    tv.tv_sec = 10;
+    tv.tv_usec = 0;
+
+    // select on applicable read descriptors
+    fd_set readfds;
+    FD_ZERO(&readfds);
+    FD_SET(m_command_fd, &readfds);
+    FD_SET(sd, &readfds);
+    int nfds = std::max(m_command_fd, sd) + 1;
+
+    if (::select(nfds, &readfds, nullptr, nullptr, &tv) < 0) {
+      ERROR("NetworkListener: select(): " << std::strerror(errno));
+      break;  // XXX: is this the right thing to do here?
+    }
+
+    // Double-check to see if we're shutting down
+    if (!m_active) break;
+
+    if (!FD_ISSET(sd, &readfds)) continue;
+
+    std::memset(&addr, 0, sizeof(addr));
+    struct iovec iov = {buf, sizeof(buf)};
+    struct msghdr msg = {&addr, sizeof(addr), &iov, 1, nullptr, 0, 0};
+    int len = ::recvmsg(sd, &msg, 0);
+    if (len < 0) {
+      if (errno == EWOULDBLOCK || errno == EAGAIN) continue;
+      ERROR(
+          "NetworkListener: could not read netlink: " << std::strerror(errno));
+      break;  // XXX: is this the right thing to do here?
+    }
+    if (len == 0) continue;  // EOF?
+    unsigned int ulen = static_cast<unsigned int>(len);
+    for (struct nlmsghdr* nh = reinterpret_cast<struct nlmsghdr*>(buf);
+         NLMSG_OK(nh, ulen); nh = NLMSG_NEXT(nh, ulen)) {
+      if (nh->nlmsg_type == NLMSG_DONE) break;
+      if (nh->nlmsg_type == RTM_NEWLINK || nh->nlmsg_type == RTM_DELLINK ||
+          nh->nlmsg_type == RTM_NEWADDR || nh->nlmsg_type == RTM_DELADDR) {
+        m_notifier.NotifyNetworkInterfacesChanged();
+      }
+    }
+  }
+  ::close(sd);
+  ::close(m_command_fd);
+  m_command_fd = -1;
+}
diff --git a/cscore/src/main/native/linux/NetworkUtil.cpp b/cscore/src/main/native/linux/NetworkUtil.cpp
new file mode 100644
index 0000000..2c1f3cd
--- /dev/null
+++ b/cscore/src/main/native/linux/NetworkUtil.cpp
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "cscore_cpp.h"  // NOLINT(build/include_order)
+
+#include <arpa/inet.h>
+#include <ifaddrs.h>
+#include <sys/types.h>
+#include <unistd.h>
+
+namespace cs {
+
+std::vector<std::string> GetNetworkInterfaces() {
+  struct ifaddrs* ifa;
+  if (::getifaddrs(&ifa) != 0) return std::vector<std::string>{};
+
+  std::vector<std::string> rv;
+  char buf[256];
+  for (struct ifaddrs* i = ifa; i; i = i->ifa_next) {
+    if (!i->ifa_addr) continue;                       // no address
+    if (i->ifa_addr->sa_family != AF_INET) continue;  // only return IPv4
+    struct sockaddr_in* addr_in = reinterpret_cast<sockaddr_in*>(i->ifa_addr);
+    const char* addr =
+        ::inet_ntop(addr_in->sin_family, &addr_in->sin_addr, buf, sizeof(buf));
+    if (!addr) continue;  // error converting address
+    rv.emplace_back(addr);
+  }
+
+  ::freeifaddrs(ifa);
+  return rv;
+}
+
+}  // namespace cs
diff --git a/cscore/src/main/native/linux/UsbCameraBuffer.h b/cscore/src/main/native/linux/UsbCameraBuffer.h
new file mode 100644
index 0000000..98ac149
--- /dev/null
+++ b/cscore/src/main/native/linux/UsbCameraBuffer.h
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_USBCAMERABUFFER_H_
+#define CSCORE_USBCAMERABUFFER_H_
+
+#include <sys/mman.h>
+
+#include <utility>
+
+namespace cs {
+
+class UsbCameraBuffer {
+ public:
+  UsbCameraBuffer() noexcept : m_data{nullptr}, m_length{0} {}
+  UsbCameraBuffer(UsbCameraBuffer&& other) noexcept : UsbCameraBuffer() {
+    swap(*this, other);
+  }
+  UsbCameraBuffer& operator=(UsbCameraBuffer&& other) noexcept {
+    swap(*this, other);
+    return *this;
+  }
+  UsbCameraBuffer(const UsbCameraBuffer&) = delete;
+  UsbCameraBuffer& operator=(const UsbCameraBuffer&) = delete;
+
+  UsbCameraBuffer(int fd, size_t length, off_t offset) noexcept
+      : m_length{length} {
+    m_data =
+        mmap(nullptr, length, PROT_READ | PROT_WRITE, MAP_SHARED, fd, offset);
+    if (m_data == MAP_FAILED) {
+      m_data = nullptr;
+      m_length = 0;
+    }
+  }
+
+  ~UsbCameraBuffer() {
+    if (m_data) munmap(m_data, m_length);
+  }
+
+  friend void swap(UsbCameraBuffer& first, UsbCameraBuffer& second) noexcept {
+    using std::swap;
+    swap(first.m_data, second.m_data);
+    swap(first.m_length, second.m_length);
+  }
+
+  void* m_data;
+  size_t m_length;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_USBCAMERABUFFER_H_
diff --git a/cscore/src/main/native/linux/UsbCameraImpl.cpp b/cscore/src/main/native/linux/UsbCameraImpl.cpp
new file mode 100644
index 0000000..a75d3cd
--- /dev/null
+++ b/cscore/src/main/native/linux/UsbCameraImpl.cpp
@@ -0,0 +1,1471 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "UsbCameraImpl.h"
+
+#include <dirent.h>
+#include <fcntl.h>
+#include <libgen.h>
+#include <linux/kernel.h>
+#include <linux/types.h>
+#include <linux/videodev2.h>
+#include <sys/eventfd.h>
+#include <sys/inotify.h>
+#include <sys/ioctl.h>
+#include <sys/select.h>
+#include <sys/stat.h>
+#include <sys/time.h>
+#include <sys/types.h>
+#include <unistd.h>
+
+#include <algorithm>
+
+#include <wpi/FileSystem.h>
+#include <wpi/MemAlloc.h>
+#include <wpi/Path.h>
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+#include <wpi/timestamp.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "JpegUtil.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "Telemetry.h"
+#include "UsbUtil.h"
+#include "cscore_cpp.h"
+
+using namespace cs;
+
+static constexpr char const* kPropWbAuto = "white_balance_temperature_auto";
+static constexpr char const* kPropWbValue = "white_balance_temperature";
+static constexpr char const* kPropExAuto = "exposure_auto";
+static constexpr char const* kPropExValue = "exposure_absolute";
+static constexpr char const* kPropBrValue = "brightness";
+static constexpr char const* kPropConnectVerbose = "connect_verbose";
+static constexpr unsigned kPropConnectVerboseId = 0;
+
+// Conversions v4l2_fract time per frame from/to frames per second (fps)
+static inline int FractToFPS(const struct v4l2_fract& timeperframe) {
+  return (1.0 * timeperframe.denominator) / timeperframe.numerator;
+}
+
+static inline struct v4l2_fract FPSToFract(int fps) {
+  struct v4l2_fract timeperframe;
+  timeperframe.numerator = 1;
+  timeperframe.denominator = fps;
+  return timeperframe;
+}
+
+// Conversion from v4l2_format pixelformat to VideoMode::PixelFormat
+static VideoMode::PixelFormat ToPixelFormat(__u32 pixelFormat) {
+  switch (pixelFormat) {
+    case V4L2_PIX_FMT_MJPEG:
+      return VideoMode::kMJPEG;
+    case V4L2_PIX_FMT_YUYV:
+      return VideoMode::kYUYV;
+    case V4L2_PIX_FMT_RGB565:
+      return VideoMode::kRGB565;
+    case V4L2_PIX_FMT_BGR24:
+      return VideoMode::kBGR;
+    case V4L2_PIX_FMT_GREY:
+      return VideoMode::kGray;
+    default:
+      return VideoMode::kUnknown;
+  }
+}
+
+// Conversion from VideoMode::PixelFormat to v4l2_format pixelformat
+static __u32 FromPixelFormat(VideoMode::PixelFormat pixelFormat) {
+  switch (pixelFormat) {
+    case VideoMode::kMJPEG:
+      return V4L2_PIX_FMT_MJPEG;
+    case VideoMode::kYUYV:
+      return V4L2_PIX_FMT_YUYV;
+    case VideoMode::kRGB565:
+      return V4L2_PIX_FMT_RGB565;
+    case VideoMode::kBGR:
+      return V4L2_PIX_FMT_BGR24;
+    case VideoMode::kGray:
+      return V4L2_PIX_FMT_GREY;
+    default:
+      return 0;
+  }
+}
+
+static bool IsPercentageProperty(wpi::StringRef name) {
+  if (name.startswith("raw_")) name = name.substr(4);
+  return name == "brightness" || name == "contrast" || name == "saturation" ||
+         name == "hue" || name == "sharpness" || name == "gain" ||
+         name == "exposure_absolute";
+}
+
+static constexpr const int quirkLifeCamHd3000[] = {
+    5, 10, 20, 39, 78, 156, 312, 625, 1250, 2500, 5000, 10000, 20000};
+
+static constexpr char const* quirkPS3EyePropExAuto = "auto_exposure";
+static constexpr char const* quirkPS3EyePropExValue = "exposure";
+static constexpr const int quirkPS3EyePropExAutoOn = 0;
+static constexpr const int quirkPS3EyePropExAutoOff = 1;
+
+int UsbCameraImpl::RawToPercentage(const UsbCameraProperty& rawProp,
+                                   int rawValue) {
+  // LifeCam exposure setting quirk
+  if (m_lifecam_exposure && rawProp.name == "raw_exposure_absolute" &&
+      rawProp.minimum == 5 && rawProp.maximum == 20000) {
+    int nelems = wpi::array_lengthof(quirkLifeCamHd3000);
+    for (int i = 0; i < nelems; ++i) {
+      if (rawValue < quirkLifeCamHd3000[i]) return 100.0 * i / nelems;
+    }
+    return 100;
+  }
+  return 100.0 * (rawValue - rawProp.minimum) /
+         (rawProp.maximum - rawProp.minimum);
+}
+
+int UsbCameraImpl::PercentageToRaw(const UsbCameraProperty& rawProp,
+                                   int percentValue) {
+  // LifeCam exposure setting quirk
+  if (m_lifecam_exposure && rawProp.name == "raw_exposure_absolute" &&
+      rawProp.minimum == 5 && rawProp.maximum == 20000) {
+    int nelems = wpi::array_lengthof(quirkLifeCamHd3000);
+    int ndx = nelems * percentValue / 100.0;
+    if (ndx < 0) ndx = 0;
+    if (ndx >= nelems) ndx = nelems - 1;
+    return quirkLifeCamHd3000[ndx];
+  }
+  return rawProp.minimum +
+         (rawProp.maximum - rawProp.minimum) * (percentValue / 100.0);
+}
+
+static bool GetVendorProduct(int dev, int* vendor, int* product) {
+  wpi::SmallString<64> ifpath;
+  {
+    wpi::raw_svector_ostream oss{ifpath};
+    oss << "/sys/class/video4linux/video" << dev << "/device/modalias";
+  }
+
+  int fd = open(ifpath.c_str(), O_RDONLY);
+  if (fd < 0) return false;
+
+  char readBuf[128];
+  ssize_t n = read(fd, readBuf, sizeof(readBuf));
+  close(fd);
+
+  if (n <= 0) return false;
+  wpi::StringRef readStr{readBuf};
+  if (readStr.substr(readStr.find('v')).substr(1, 4).getAsInteger(16, *vendor))
+    return false;
+  if (readStr.substr(readStr.find('p')).substr(1, 4).getAsInteger(16, *product))
+    return false;
+
+  return true;
+}
+
+static bool GetDescriptionSysV4L(int dev, std::string* desc) {
+  wpi::SmallString<64> ifpath;
+  {
+    wpi::raw_svector_ostream oss{ifpath};
+    oss << "/sys/class/video4linux/video" << dev << "/device/interface";
+  }
+
+  int fd = open(ifpath.c_str(), O_RDONLY);
+  if (fd < 0) return false;
+
+  char readBuf[128];
+  ssize_t n = read(fd, readBuf, sizeof(readBuf));
+  close(fd);
+
+  if (n <= 0) return false;
+
+  *desc = wpi::StringRef(readBuf, n).rtrim();
+  return true;
+}
+
+static bool GetDescriptionIoctl(const char* cpath, std::string* desc) {
+  int fd = open(cpath, O_RDWR);
+  if (fd < 0) return false;
+
+  struct v4l2_capability vcap;
+  std::memset(&vcap, 0, sizeof(vcap));
+  if (DoIoctl(fd, VIDIOC_QUERYCAP, &vcap) < 0) {
+    close(fd);
+    return false;
+  }
+  close(fd);
+
+  wpi::StringRef card{reinterpret_cast<const char*>(vcap.card)};
+  // try to convert "UVC Camera (0000:0000)" into a better name
+  int vendor = 0;
+  int product = 0;
+  if (card.startswith("UVC Camera (") &&
+      !card.substr(12, 4).getAsInteger(16, vendor) &&
+      !card.substr(17, 4).getAsInteger(16, product)) {
+    wpi::SmallString<64> card2Buf;
+    wpi::StringRef card2 = GetUsbNameFromId(vendor, product, card2Buf);
+    if (!card2.empty()) {
+      *desc = card2;
+      return true;
+    }
+  }
+
+  *desc = card;
+  return true;
+}
+
+static int GetDeviceNum(const char* cpath) {
+  wpi::StringRef path{cpath};
+  std::string pathBuf;
+
+  // it might be a symlink; if so, find the symlink target (e.g. /dev/videoN),
+  // add that to the list and make it the keypath
+  if (wpi::sys::fs::is_symlink_file(cpath)) {
+    char* target = ::realpath(cpath, nullptr);
+    if (target) {
+      pathBuf = target;
+      path = pathBuf;
+      std::free(target);
+    }
+  }
+
+  path = wpi::sys::path::filename(path);
+  if (!path.startswith("video")) return -1;
+  int dev = -1;
+  if (path.substr(5).getAsInteger(10, dev)) return -1;
+  return dev;
+}
+
+static std::string GetDescriptionImpl(const char* cpath) {
+  std::string rv;
+
+  int dev = GetDeviceNum(cpath);
+  if (dev >= 0) {
+    // Sometimes the /sys tree gives a better name.
+    if (GetDescriptionSysV4L(dev, &rv)) return rv;
+  }
+
+  // Otherwise use an ioctl to query the caps and get the card name
+  if (GetDescriptionIoctl(cpath, &rv)) return rv;
+
+  return std::string{};
+}
+
+UsbCameraImpl::UsbCameraImpl(const wpi::Twine& name, wpi::Logger& logger,
+                             Notifier& notifier, Telemetry& telemetry,
+                             const wpi::Twine& path)
+    : SourceImpl{name, logger, notifier, telemetry},
+      m_path{path.str()},
+      m_fd{-1},
+      m_command_fd{eventfd(0, 0)},
+      m_active{true} {
+  SetDescription(GetDescriptionImpl(m_path.c_str()));
+  SetQuirks();
+
+  CreateProperty(kPropConnectVerbose, [] {
+    return std::make_unique<UsbCameraProperty>(kPropConnectVerbose,
+                                               kPropConnectVerboseId,
+                                               CS_PROP_INTEGER, 0, 1, 1, 1, 1);
+  });
+}
+
+UsbCameraImpl::~UsbCameraImpl() {
+  m_active = false;
+
+  // Just in case anyone is waiting...
+  m_responseCv.notify_all();
+
+  // Send message to wake up thread; select timeout will wake us up anyway,
+  // but this speeds shutdown.
+  Send(Message{Message::kNone});
+
+  // join camera thread
+  if (m_cameraThread.joinable()) m_cameraThread.join();
+
+  // close command fd
+  int fd = m_command_fd.exchange(-1);
+  if (fd >= 0) close(fd);
+}
+
+static inline void DoFdSet(int fd, fd_set* set, int* nfds) {
+  if (fd >= 0) {
+    FD_SET(fd, set);
+    if ((fd + 1) > *nfds) *nfds = fd + 1;
+  }
+}
+
+void UsbCameraImpl::Start() {
+  // Kick off the camera thread
+  m_cameraThread = std::thread(&UsbCameraImpl::CameraThreadMain, this);
+}
+
+void UsbCameraImpl::CameraThreadMain() {
+  // We want to be notified on file creation and deletion events in the device
+  // path.  This is used to detect disconnects and reconnects.
+  std::unique_ptr<wpi::raw_fd_istream> notify_is;
+  int notify_fd = inotify_init();
+  if (notify_fd >= 0) {
+    // need to make a copy as dirname can modify it
+    wpi::SmallString<64> pathCopy{m_path};
+    pathCopy.push_back('\0');
+    if (inotify_add_watch(notify_fd, dirname(pathCopy.data()),
+                          IN_CREATE | IN_DELETE) < 0) {
+      close(notify_fd);
+      notify_fd = -1;
+    } else {
+      notify_is.reset(new wpi::raw_fd_istream{
+          notify_fd, true, sizeof(struct inotify_event) + NAME_MAX + 1});
+    }
+  }
+  bool notified = (notify_fd < 0);  // treat as always notified if cannot notify
+
+  // Get the basename for later notify use
+  wpi::SmallString<64> pathCopy{m_path};
+  pathCopy.push_back('\0');
+  wpi::SmallString<64> base{basename(pathCopy.data())};
+
+  // Used to restart streaming on reconnect
+  bool wasStreaming = false;
+
+  // Default to not streaming
+  m_streaming = false;
+
+  while (m_active) {
+    // If not connected, try to reconnect
+    if (m_fd < 0) DeviceConnect();
+
+    // Make copies of fd's in case they go away
+    int command_fd = m_command_fd.load();
+    int fd = m_fd.load();
+    if (!m_active) break;
+
+    // Reset notified flag and restart streaming if necessary
+    if (fd >= 0) {
+      notified = (notify_fd < 0);
+      if (wasStreaming && !m_streaming) {
+        DeviceStreamOn();
+        wasStreaming = false;
+      }
+    }
+
+    // Turn off streaming if not enabled, and turn it on if enabled
+    if (m_streaming && !IsEnabled()) {
+      DeviceStreamOff();
+    } else if (!m_streaming && IsEnabled()) {
+      DeviceStreamOn();
+    }
+
+    // The select timeout can be long unless we're trying to reconnect
+    struct timeval tv;
+    if (fd < 0 && notified) {
+      tv.tv_sec = 0;
+      tv.tv_usec = 300000;
+    } else {
+      tv.tv_sec = 2;
+      tv.tv_usec = 0;
+    }
+
+    // select on applicable read descriptors
+    int nfds = 0;
+    fd_set readfds;
+    FD_ZERO(&readfds);
+    DoFdSet(command_fd, &readfds, &nfds);
+    if (m_streaming) DoFdSet(fd, &readfds, &nfds);
+    DoFdSet(notify_fd, &readfds, &nfds);
+
+    if (select(nfds, &readfds, nullptr, nullptr, &tv) < 0) {
+      SERROR("select(): " << std::strerror(errno));
+      break;  // XXX: is this the right thing to do here?
+    }
+
+    // Double-check to see if we're shutting down
+    if (!m_active) break;
+
+    // Handle notify events
+    if (notify_fd >= 0 && FD_ISSET(notify_fd, &readfds)) {
+      SDEBUG4("notify event");
+      struct inotify_event event;
+      do {
+        // Read the event structure
+        notify_is->read(&event, sizeof(event));
+        // Read the event name
+        wpi::SmallString<64> raw_name;
+        raw_name.resize(event.len);
+        notify_is->read(raw_name.data(), event.len);
+        // If the name is what we expect...
+        wpi::StringRef name{raw_name.c_str()};
+        SDEBUG4("got event on '" << name << "' (" << name.size()
+                                 << ") compare to '" << base << "' ("
+                                 << base.size() << ") mask " << event.mask);
+        if (name == base) {
+          if ((event.mask & IN_DELETE) != 0) {
+            wasStreaming = m_streaming;
+            DeviceStreamOff();
+            DeviceDisconnect();
+          } else if ((event.mask & IN_CREATE) != 0) {
+            notified = true;
+          }
+        }
+      } while (!notify_is->has_error() &&
+               notify_is->in_avail() >= sizeof(event));
+      continue;
+    }
+
+    // Handle commands
+    if (command_fd >= 0 && FD_ISSET(command_fd, &readfds)) {
+      SDEBUG4("got command");
+      // Read it to clear
+      eventfd_t val;
+      eventfd_read(command_fd, &val);
+      DeviceProcessCommands();
+      continue;
+    }
+
+    // Handle frames
+    if (m_streaming && fd >= 0 && FD_ISSET(fd, &readfds)) {
+      SDEBUG4("grabbing image");
+
+      // Dequeue buffer
+      struct v4l2_buffer buf;
+      std::memset(&buf, 0, sizeof(buf));
+      buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+      buf.memory = V4L2_MEMORY_MMAP;
+      if (DoIoctl(fd, VIDIOC_DQBUF, &buf) != 0) {
+        SWARNING("could not dequeue buffer");
+        wasStreaming = m_streaming;
+        DeviceStreamOff();
+        DeviceDisconnect();
+        notified = true;  // device wasn't deleted, just error'ed
+        continue;         // will reconnect
+      }
+
+      if ((buf.flags & V4L2_BUF_FLAG_ERROR) == 0) {
+        SDEBUG4("got image size=" << buf.bytesused << " index=" << buf.index);
+
+        if (buf.index >= kNumBuffers || !m_buffers[buf.index].m_data) {
+          SWARNING("invalid buffer" << buf.index);
+          continue;
+        }
+
+        wpi::StringRef image{
+            static_cast<const char*>(m_buffers[buf.index].m_data),
+            static_cast<size_t>(buf.bytesused)};
+        int width = m_mode.width;
+        int height = m_mode.height;
+        bool good = true;
+        if (m_mode.pixelFormat == VideoMode::kMJPEG &&
+            !GetJpegSize(image, &width, &height)) {
+          SWARNING("invalid JPEG image received from camera");
+          good = false;
+        }
+        if (good) {
+          PutFrame(static_cast<VideoMode::PixelFormat>(m_mode.pixelFormat),
+                   width, height, image, wpi::Now());  // TODO: time
+        }
+      }
+
+      // Requeue buffer
+      if (DoIoctl(fd, VIDIOC_QBUF, &buf) != 0) {
+        SWARNING("could not requeue buffer");
+        wasStreaming = m_streaming;
+        DeviceStreamOff();
+        DeviceDisconnect();
+        notified = true;  // device wasn't deleted, just error'ed
+        continue;         // will reconnect
+      }
+    }
+  }
+
+  // close camera connection
+  DeviceStreamOff();
+  DeviceDisconnect();
+}
+
+void UsbCameraImpl::DeviceDisconnect() {
+  int fd = m_fd.exchange(-1);
+  if (fd < 0) return;  // already disconnected
+
+  // Unmap buffers
+  for (int i = 0; i < kNumBuffers; ++i) m_buffers[i] = UsbCameraBuffer{};
+
+  // Close device
+  close(fd);
+
+  // Notify
+  SetConnected(false);
+}
+
+void UsbCameraImpl::DeviceConnect() {
+  if (m_fd >= 0) return;
+
+  if (m_connectVerbose) SINFO("Connecting to USB camera on " << m_path);
+
+  // Try to open the device
+  SDEBUG3("opening device");
+  int fd = open(m_path.c_str(), O_RDWR);
+  if (fd < 0) return;
+  m_fd = fd;
+
+  // Get capabilities
+  SDEBUG3("getting capabilities");
+  struct v4l2_capability vcap;
+  std::memset(&vcap, 0, sizeof(vcap));
+  if (DoIoctl(fd, VIDIOC_QUERYCAP, &vcap) >= 0) {
+    m_capabilities = vcap.capabilities;
+    if (m_capabilities & V4L2_CAP_DEVICE_CAPS)
+      m_capabilities = vcap.device_caps;
+  }
+
+  // Get or restore video mode
+  if (!m_properties_cached) {
+    SDEBUG3("caching properties");
+    DeviceCacheProperties();
+    DeviceCacheVideoModes();
+    DeviceCacheMode();
+    m_properties_cached = true;
+  } else {
+    SDEBUG3("restoring video mode");
+    DeviceSetMode();
+    DeviceSetFPS();
+
+    // Restore settings
+    SDEBUG3("restoring settings");
+    std::unique_lock lock2(m_mutex);
+    for (size_t i = 0; i < m_propertyData.size(); ++i) {
+      const auto prop =
+          static_cast<const UsbCameraProperty*>(m_propertyData[i].get());
+      if (!prop || !prop->valueSet || !prop->device || prop->percentage)
+        continue;
+      if (!prop->DeviceSet(lock2, m_fd))
+        SWARNING("failed to set property " << prop->name);
+    }
+  }
+
+  // Request buffers
+  SDEBUG3("allocating buffers");
+  struct v4l2_requestbuffers rb;
+  std::memset(&rb, 0, sizeof(rb));
+  rb.count = kNumBuffers;
+  rb.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  rb.memory = V4L2_MEMORY_MMAP;
+  if (DoIoctl(fd, VIDIOC_REQBUFS, &rb) != 0) {
+    SWARNING("could not allocate buffers");
+    close(fd);
+    m_fd = -1;
+    return;
+  }
+
+  // Map buffers
+  SDEBUG3("mapping buffers");
+  for (int i = 0; i < kNumBuffers; ++i) {
+    struct v4l2_buffer buf;
+    std::memset(&buf, 0, sizeof(buf));
+    buf.index = i;
+    buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+    buf.memory = V4L2_MEMORY_MMAP;
+    if (DoIoctl(fd, VIDIOC_QUERYBUF, &buf) != 0) {
+      SWARNING("could not query buffer " << i);
+      close(fd);
+      m_fd = -1;
+      return;
+    }
+    SDEBUG4("buf " << i << " length=" << buf.length
+                   << " offset=" << buf.m.offset);
+
+    m_buffers[i] = UsbCameraBuffer(fd, buf.length, buf.m.offset);
+    if (!m_buffers[i].m_data) {
+      SWARNING("could not map buffer " << i);
+      // release other buffers
+      for (int j = 0; j < i; ++j) m_buffers[j] = UsbCameraBuffer{};
+      close(fd);
+      m_fd = -1;
+      return;
+    }
+
+    SDEBUG4("buf " << i << " address=" << m_buffers[i].m_data);
+  }
+
+  // Update description (as it may have changed)
+  SetDescription(GetDescriptionImpl(m_path.c_str()));
+
+  // Update quirks settings
+  SetQuirks();
+
+  // Notify
+  SetConnected(true);
+}
+
+bool UsbCameraImpl::DeviceStreamOn() {
+  if (m_streaming) return false;  // ignore if already enabled
+  int fd = m_fd.load();
+  if (fd < 0) return false;
+
+  // Queue buffers
+  SDEBUG3("queuing buffers");
+  for (int i = 0; i < kNumBuffers; ++i) {
+    struct v4l2_buffer buf;
+    std::memset(&buf, 0, sizeof(buf));
+    buf.index = i;
+    buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+    buf.memory = V4L2_MEMORY_MMAP;
+    if (DoIoctl(fd, VIDIOC_QBUF, &buf) != 0) {
+      SWARNING("could not queue buffer " << i);
+      return false;
+    }
+  }
+
+  // Turn stream on
+  int type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  if (TryIoctl(fd, VIDIOC_STREAMON, &type) < 0) {
+    if (errno == ENOSPC) {
+      // indicates too much USB bandwidth requested
+      SERROR(
+          "could not start streaming due to USB bandwidth limitations; try a "
+          "lower resolution or a different pixel format (VIDIOC_STREAMON: "
+          "No space left on device)");
+    } else {
+      // some other error
+      SERROR("ioctl VIDIOC_STREAMON failed: " << std::strerror(errno));
+    }
+    return false;
+  }
+  SDEBUG4("enabled streaming");
+  m_streaming = true;
+  return true;
+}
+
+bool UsbCameraImpl::DeviceStreamOff() {
+  if (!m_streaming) return false;  // ignore if already disabled
+  int fd = m_fd.load();
+  if (fd < 0) return false;
+  int type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  if (DoIoctl(fd, VIDIOC_STREAMOFF, &type) != 0) return false;
+  SDEBUG4("disabled streaming");
+  m_streaming = false;
+  return true;
+}
+
+CS_StatusValue UsbCameraImpl::DeviceCmdSetMode(
+    std::unique_lock<wpi::mutex>& lock, const Message& msg) {
+  VideoMode newMode;
+  if (msg.kind == Message::kCmdSetMode) {
+    newMode.pixelFormat = msg.data[0];
+    newMode.width = msg.data[1];
+    newMode.height = msg.data[2];
+    newMode.fps = msg.data[3];
+    m_modeSetPixelFormat = true;
+    m_modeSetResolution = true;
+    m_modeSetFPS = true;
+  } else if (msg.kind == Message::kCmdSetPixelFormat) {
+    newMode = m_mode;
+    newMode.pixelFormat = msg.data[0];
+    m_modeSetPixelFormat = true;
+  } else if (msg.kind == Message::kCmdSetResolution) {
+    newMode = m_mode;
+    newMode.width = msg.data[0];
+    newMode.height = msg.data[1];
+    m_modeSetResolution = true;
+  } else if (msg.kind == Message::kCmdSetFPS) {
+    newMode = m_mode;
+    newMode.fps = msg.data[0];
+    m_modeSetFPS = true;
+  }
+
+  // If the pixel format or resolution changed, we need to disconnect and
+  // reconnect
+  if (newMode.pixelFormat != m_mode.pixelFormat ||
+      newMode.width != m_mode.width || newMode.height != m_mode.height) {
+    m_mode = newMode;
+    lock.unlock();
+    bool wasStreaming = m_streaming;
+    if (wasStreaming) DeviceStreamOff();
+    if (m_fd >= 0) {
+      DeviceDisconnect();
+      DeviceConnect();
+    }
+    if (wasStreaming) DeviceStreamOn();
+    m_notifier.NotifySourceVideoMode(*this, newMode);
+    lock.lock();
+  } else if (newMode.fps != m_mode.fps) {
+    m_mode = newMode;
+    lock.unlock();
+    // Need to stop streaming to set FPS
+    bool wasStreaming = m_streaming;
+    if (wasStreaming) DeviceStreamOff();
+    DeviceSetFPS();
+    if (wasStreaming) DeviceStreamOn();
+    m_notifier.NotifySourceVideoMode(*this, newMode);
+    lock.lock();
+  }
+
+  return CS_OK;
+}
+
+CS_StatusValue UsbCameraImpl::DeviceCmdSetProperty(
+    std::unique_lock<wpi::mutex>& lock, const Message& msg) {
+  bool setString = (msg.kind == Message::kCmdSetPropertyStr);
+  int property = msg.data[0];
+  int value = msg.data[1];
+  wpi::StringRef valueStr = msg.dataStr;
+
+  // Look up
+  auto prop = static_cast<UsbCameraProperty*>(GetProperty(property));
+  if (!prop) return CS_INVALID_PROPERTY;
+
+  // If setting before we get, guess initial type based on set
+  if (prop->propKind == CS_PROP_NONE) {
+    if (setString)
+      prop->propKind = CS_PROP_STRING;
+    else
+      prop->propKind = CS_PROP_INTEGER;
+  }
+
+  // Check kind match
+  if ((setString && prop->propKind != CS_PROP_STRING) ||
+      (!setString && (prop->propKind &
+                      (CS_PROP_BOOLEAN | CS_PROP_INTEGER | CS_PROP_ENUM)) == 0))
+    return CS_WRONG_PROPERTY_TYPE;
+
+  // Handle percentage property
+  int percentageProperty = prop->propPair;
+  int percentageValue = value;
+  if (percentageProperty != 0) {
+    if (prop->percentage) {
+      std::swap(percentageProperty, property);
+      prop = static_cast<UsbCameraProperty*>(GetProperty(property));
+      value = PercentageToRaw(*prop, percentageValue);
+    } else {
+      percentageValue = RawToPercentage(*prop, value);
+    }
+  }
+
+  // Actually set the new value on the device (if possible)
+  if (!prop->device) {
+    if (prop->id == kPropConnectVerboseId) m_connectVerbose = value;
+  } else {
+    if (!prop->DeviceSet(lock, m_fd, value, valueStr))
+      return CS_PROPERTY_WRITE_FAILED;
+  }
+
+  // Cache the set values
+  UpdatePropertyValue(property, setString, value, valueStr);
+  if (percentageProperty != 0)
+    UpdatePropertyValue(percentageProperty, setString, percentageValue,
+                        valueStr);
+
+  return CS_OK;
+}
+
+CS_StatusValue UsbCameraImpl::DeviceProcessCommand(
+    std::unique_lock<wpi::mutex>& lock, const Message& msg) {
+  if (msg.kind == Message::kCmdSetMode ||
+      msg.kind == Message::kCmdSetPixelFormat ||
+      msg.kind == Message::kCmdSetResolution ||
+      msg.kind == Message::kCmdSetFPS) {
+    return DeviceCmdSetMode(lock, msg);
+  } else if (msg.kind == Message::kCmdSetProperty ||
+             msg.kind == Message::kCmdSetPropertyStr) {
+    return DeviceCmdSetProperty(lock, msg);
+  } else if (msg.kind == Message::kNumSinksChanged ||
+             msg.kind == Message::kNumSinksEnabledChanged) {
+    return CS_OK;
+  } else {
+    return CS_OK;
+  }
+}
+
+void UsbCameraImpl::DeviceProcessCommands() {
+  std::unique_lock lock(m_mutex);
+  if (m_commands.empty()) return;
+  while (!m_commands.empty()) {
+    auto msg = std::move(m_commands.back());
+    m_commands.pop_back();
+
+    CS_StatusValue status = DeviceProcessCommand(lock, msg);
+    if (msg.kind != Message::kNumSinksChanged &&
+        msg.kind != Message::kNumSinksEnabledChanged)
+      m_responses.emplace_back(msg.from, status);
+  }
+  lock.unlock();
+  m_responseCv.notify_all();
+}
+
+void UsbCameraImpl::DeviceSetMode() {
+  int fd = m_fd.load();
+  if (fd < 0) return;
+
+  struct v4l2_format vfmt;
+  std::memset(&vfmt, 0, sizeof(vfmt));
+#ifdef V4L2_CAP_EXT_PIX_FORMAT
+  vfmt.fmt.pix.priv = (m_capabilities & V4L2_CAP_EXT_PIX_FORMAT) != 0
+                          ? V4L2_PIX_FMT_PRIV_MAGIC
+                          : 0;
+#endif
+  vfmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  vfmt.fmt.pix.pixelformat =
+      FromPixelFormat(static_cast<VideoMode::PixelFormat>(m_mode.pixelFormat));
+  if (vfmt.fmt.pix.pixelformat == 0) {
+    SWARNING("could not set format " << m_mode.pixelFormat
+                                     << ", defaulting to MJPEG");
+    vfmt.fmt.pix.pixelformat = V4L2_PIX_FMT_MJPEG;
+  }
+  vfmt.fmt.pix.width = m_mode.width;
+  vfmt.fmt.pix.height = m_mode.height;
+  vfmt.fmt.pix.field = V4L2_FIELD_ANY;
+  if (DoIoctl(fd, VIDIOC_S_FMT, &vfmt) != 0) {
+    SWARNING("could not set format " << m_mode.pixelFormat << " res "
+                                     << m_mode.width << "x" << m_mode.height);
+  } else {
+    SINFO("set format " << m_mode.pixelFormat << " res " << m_mode.width << "x"
+                        << m_mode.height);
+  }
+}
+
+void UsbCameraImpl::DeviceSetFPS() {
+  int fd = m_fd.load();
+  if (fd < 0) return;
+
+  struct v4l2_streamparm parm;
+  std::memset(&parm, 0, sizeof(parm));
+  parm.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  if (DoIoctl(fd, VIDIOC_G_PARM, &parm) != 0) return;
+  if ((parm.parm.capture.capability & V4L2_CAP_TIMEPERFRAME) == 0) return;
+  std::memset(&parm, 0, sizeof(parm));
+  parm.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  parm.parm.capture.timeperframe = FPSToFract(m_mode.fps);
+  if (DoIoctl(fd, VIDIOC_S_PARM, &parm) != 0)
+    SWARNING("could not set FPS to " << m_mode.fps);
+  else
+    SINFO("set FPS to " << m_mode.fps);
+}
+
+void UsbCameraImpl::DeviceCacheMode() {
+  int fd = m_fd.load();
+  if (fd < 0) return;
+
+  // Get format
+  struct v4l2_format vfmt;
+  std::memset(&vfmt, 0, sizeof(vfmt));
+#ifdef V4L2_CAP_EXT_PIX_FORMAT
+  vfmt.fmt.pix.priv = (m_capabilities & V4L2_CAP_EXT_PIX_FORMAT) != 0
+                          ? V4L2_PIX_FMT_PRIV_MAGIC
+                          : 0;
+#endif
+  vfmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  if (DoIoctl(fd, VIDIOC_G_FMT, &vfmt) != 0) {
+    SERROR("could not read current video mode");
+    std::scoped_lock lock(m_mutex);
+    m_mode = VideoMode{VideoMode::kMJPEG, 320, 240, 30};
+    return;
+  }
+  VideoMode::PixelFormat pixelFormat = ToPixelFormat(vfmt.fmt.pix.pixelformat);
+  int width = vfmt.fmt.pix.width;
+  int height = vfmt.fmt.pix.height;
+
+  // Get FPS
+  int fps = 0;
+  struct v4l2_streamparm parm;
+  std::memset(&parm, 0, sizeof(parm));
+  parm.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  if (TryIoctl(fd, VIDIOC_G_PARM, &parm) == 0) {
+    if (parm.parm.capture.capability & V4L2_CAP_TIMEPERFRAME)
+      fps = FractToFPS(parm.parm.capture.timeperframe);
+  }
+
+  // Update format with user changes.
+  bool formatChanged = false;
+
+  if (m_modeSetPixelFormat) {
+    // User set pixel format
+    if (pixelFormat != m_mode.pixelFormat) {
+      formatChanged = true;
+      pixelFormat = static_cast<VideoMode::PixelFormat>(m_mode.pixelFormat);
+    }
+  } else {
+    // Default to MJPEG
+    if (pixelFormat != VideoMode::kMJPEG) {
+      formatChanged = true;
+      pixelFormat = VideoMode::kMJPEG;
+    }
+  }
+
+  if (m_modeSetResolution) {
+    // User set resolution
+    if (width != m_mode.width || height != m_mode.height) {
+      formatChanged = true;
+      width = m_mode.width;
+      height = m_mode.height;
+    }
+  } else {
+    // Default to lowest known resolution (based on number of total pixels)
+    int numPixels = width * height;
+    for (const auto& mode : m_videoModes) {
+      if (mode.pixelFormat != pixelFormat) continue;
+      int numPixelsHere = mode.width * mode.height;
+      if (numPixelsHere < numPixels) {
+        formatChanged = true;
+        numPixels = numPixelsHere;
+        width = mode.width;
+        height = mode.height;
+      }
+    }
+  }
+
+  // Update FPS with user changes
+  bool fpsChanged = false;
+  if (m_modeSetFPS && fps != m_mode.fps) {
+    fpsChanged = true;
+    fps = m_mode.fps;
+  }
+
+  // Save to global mode
+  {
+    std::scoped_lock lock(m_mutex);
+    m_mode.pixelFormat = pixelFormat;
+    m_mode.width = width;
+    m_mode.height = height;
+    m_mode.fps = fps;
+  }
+
+  if (formatChanged) DeviceSetMode();
+  if (fpsChanged) DeviceSetFPS();
+
+  m_notifier.NotifySourceVideoMode(*this, m_mode);
+}
+
+void UsbCameraImpl::DeviceCacheProperty(
+    std::unique_ptr<UsbCameraProperty> rawProp) {
+  // For percentage properties, we want to cache both the raw and the
+  // percentage versions.  This function is always called with prop being
+  // the raw property (as it's coming from the camera) so if required, we need
+  // to rename this one as well as create/cache the percentage version.
+  //
+  // This is complicated by the fact that either the percentage version or the
+  // the raw version may have been set previously.  If both were previously set,
+  // the raw version wins.
+  std::unique_ptr<UsbCameraProperty> perProp;
+  if (IsPercentageProperty(rawProp->name)) {
+    perProp =
+        std::make_unique<UsbCameraProperty>(rawProp->name, 0, *rawProp, 0, 0);
+    rawProp->name = "raw_" + perProp->name;
+  }
+
+  std::unique_lock lock(m_mutex);
+  int* rawIndex = &m_properties[rawProp->name];
+  bool newRaw = *rawIndex == 0;
+  UsbCameraProperty* oldRawProp =
+      newRaw ? nullptr
+             : static_cast<UsbCameraProperty*>(GetProperty(*rawIndex));
+
+  int* perIndex = perProp ? &m_properties[perProp->name] : nullptr;
+  bool newPer = !perIndex || *perIndex == 0;
+  UsbCameraProperty* oldPerProp =
+      newPer ? nullptr
+             : static_cast<UsbCameraProperty*>(GetProperty(*perIndex));
+
+  if (oldRawProp && oldRawProp->valueSet) {
+    // Merge existing raw setting and set percentage from it
+    rawProp->SetValue(oldRawProp->value);
+    rawProp->valueStr = std::move(oldRawProp->valueStr);
+
+    if (perProp) {
+      perProp->SetValue(RawToPercentage(*rawProp, rawProp->value));
+      perProp->valueStr = rawProp->valueStr;  // copy
+    }
+  } else if (oldPerProp && oldPerProp->valueSet) {
+    // Merge existing percentage setting and set raw from it
+    perProp->SetValue(oldPerProp->value);
+    perProp->valueStr = std::move(oldPerProp->valueStr);
+
+    rawProp->SetValue(PercentageToRaw(*rawProp, perProp->value));
+    rawProp->valueStr = perProp->valueStr;  // copy
+  } else {
+    // Read current raw value and set percentage from it
+    if (!rawProp->DeviceGet(lock, m_fd))
+      SWARNING("failed to get property " << rawProp->name);
+
+    if (perProp) {
+      perProp->SetValue(RawToPercentage(*rawProp, rawProp->value));
+      perProp->valueStr = rawProp->valueStr;  // copy
+    }
+  }
+
+  // Set value on device if user-configured
+  if (rawProp->valueSet) {
+    if (!rawProp->DeviceSet(lock, m_fd))
+      SWARNING("failed to set property " << rawProp->name);
+  }
+
+  // Update pointers since we released the lock
+  rawIndex = &m_properties[rawProp->name];
+  perIndex = perProp ? &m_properties[perProp->name] : nullptr;
+
+  // Get pointers before we move the std::unique_ptr values
+  auto rawPropPtr = rawProp.get();
+  auto perPropPtr = perProp.get();
+
+  if (newRaw) {
+    // create a new index
+    *rawIndex = m_propertyData.size() + 1;
+    m_propertyData.emplace_back(std::move(rawProp));
+  } else {
+    // update
+    m_propertyData[*rawIndex - 1] = std::move(rawProp);
+  }
+
+  // Finish setting up percentage property
+  if (perProp) {
+    perProp->propPair = *rawIndex;
+    perProp->defaultValue =
+        RawToPercentage(*rawPropPtr, rawPropPtr->defaultValue);
+
+    if (newPer) {
+      // create a new index
+      *perIndex = m_propertyData.size() + 1;
+      m_propertyData.emplace_back(std::move(perProp));
+    } else if (perIndex) {
+      // update
+      m_propertyData[*perIndex - 1] = std::move(perProp);
+    }
+
+    // Tell raw property where to find percentage property
+    rawPropPtr->propPair = *perIndex;
+  }
+
+  NotifyPropertyCreated(*rawIndex, *rawPropPtr);
+  if (perPropPtr) NotifyPropertyCreated(*perIndex, *perPropPtr);
+}
+
+void UsbCameraImpl::DeviceCacheProperties() {
+  int fd = m_fd.load();
+  if (fd < 0) return;
+
+#ifdef V4L2_CTRL_FLAG_NEXT_COMPOUND
+  constexpr __u32 nextFlags =
+      V4L2_CTRL_FLAG_NEXT_CTRL | V4L2_CTRL_FLAG_NEXT_COMPOUND;
+#else
+  constexpr __u32 nextFlags = V4L2_CTRL_FLAG_NEXT_CTRL;
+#endif
+  __u32 id = nextFlags;
+
+  while (auto prop = UsbCameraProperty::DeviceQuery(fd, &id)) {
+    DeviceCacheProperty(std::move(prop));
+    id |= nextFlags;
+  }
+
+  if (id == nextFlags) {
+    // try just enumerating standard...
+    for (id = V4L2_CID_BASE; id < V4L2_CID_LASTP1; ++id) {
+      if (auto prop = UsbCameraProperty::DeviceQuery(fd, &id))
+        DeviceCacheProperty(std::move(prop));
+    }
+    // ... and custom controls
+    std::unique_ptr<UsbCameraProperty> prop;
+    for (id = V4L2_CID_PRIVATE_BASE;
+         (prop = UsbCameraProperty::DeviceQuery(fd, &id)); ++id)
+      DeviceCacheProperty(std::move(prop));
+  }
+}
+
+void UsbCameraImpl::DeviceCacheVideoModes() {
+  int fd = m_fd.load();
+  if (fd < 0) return;
+
+  std::vector<VideoMode> modes;
+
+  // Pixel formats
+  struct v4l2_fmtdesc fmt;
+  std::memset(&fmt, 0, sizeof(fmt));
+  fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  for (fmt.index = 0; TryIoctl(fd, VIDIOC_ENUM_FMT, &fmt) >= 0; ++fmt.index) {
+    VideoMode::PixelFormat pixelFormat = ToPixelFormat(fmt.pixelformat);
+    if (pixelFormat == VideoMode::kUnknown) continue;
+
+    // Frame sizes
+    struct v4l2_frmsizeenum frmsize;
+    std::memset(&frmsize, 0, sizeof(frmsize));
+    frmsize.pixel_format = fmt.pixelformat;
+    for (frmsize.index = 0; TryIoctl(fd, VIDIOC_ENUM_FRAMESIZES, &frmsize) >= 0;
+         ++frmsize.index) {
+      if (frmsize.type != V4L2_FRMSIZE_TYPE_DISCRETE) continue;
+
+      // Frame intervals
+      struct v4l2_frmivalenum frmival;
+      std::memset(&frmival, 0, sizeof(frmival));
+      frmival.pixel_format = fmt.pixelformat;
+      frmival.width = frmsize.discrete.width;
+      frmival.height = frmsize.discrete.height;
+      for (frmival.index = 0;
+           TryIoctl(fd, VIDIOC_ENUM_FRAMEINTERVALS, &frmival) >= 0;
+           ++frmival.index) {
+        if (frmival.type != V4L2_FRMIVAL_TYPE_DISCRETE) continue;
+
+        modes.emplace_back(pixelFormat,
+                           static_cast<int>(frmsize.discrete.width),
+                           static_cast<int>(frmsize.discrete.height),
+                           FractToFPS(frmival.discrete));
+      }
+    }
+  }
+
+  {
+    std::scoped_lock lock(m_mutex);
+    m_videoModes.swap(modes);
+  }
+  m_notifier.NotifySource(*this, CS_SOURCE_VIDEOMODES_UPDATED);
+}
+
+CS_StatusValue UsbCameraImpl::SendAndWait(Message&& msg) const {
+  int fd = m_command_fd.load();
+  // exit early if not possible to signal
+  if (fd < 0) return CS_SOURCE_IS_DISCONNECTED;
+
+  auto from = msg.from;
+
+  // Add the message to the command queue
+  {
+    std::scoped_lock lock(m_mutex);
+    m_commands.emplace_back(std::move(msg));
+  }
+
+  // Signal the camera thread
+  if (eventfd_write(fd, 1) < 0) return CS_SOURCE_IS_DISCONNECTED;
+
+  std::unique_lock lock(m_mutex);
+  while (m_active) {
+    // Did we get a response to *our* request?
+    auto it =
+        std::find_if(m_responses.begin(), m_responses.end(),
+                     [=](const std::pair<std::thread::id, CS_StatusValue>& r) {
+                       return r.first == from;
+                     });
+    if (it != m_responses.end()) {
+      // Yes, remove it from the vector and we're done.
+      auto rv = it->second;
+      m_responses.erase(it);
+      return rv;
+    }
+    // No, keep waiting for a response
+    m_responseCv.wait(lock);
+  }
+
+  return CS_SOURCE_IS_DISCONNECTED;
+}
+
+void UsbCameraImpl::Send(Message&& msg) const {
+  int fd = m_command_fd.load();
+  // exit early if not possible to signal
+  if (fd < 0) return;
+
+  // Add the message to the command queue
+  {
+    std::scoped_lock lock(m_mutex);
+    m_commands.emplace_back(std::move(msg));
+  }
+
+  // Signal the camera thread
+  eventfd_write(fd, 1);
+}
+
+std::unique_ptr<PropertyImpl> UsbCameraImpl::CreateEmptyProperty(
+    const wpi::Twine& name) const {
+  return std::make_unique<UsbCameraProperty>(name);
+}
+
+bool UsbCameraImpl::CacheProperties(CS_Status* status) const {
+  // Wake up camera thread; this will try to reconnect
+  *status = SendAndWait(Message{Message::kNone});
+  if (*status != CS_OK) return false;
+  if (!m_properties_cached) {
+    *status = CS_SOURCE_IS_DISCONNECTED;
+    return false;
+  }
+  return true;
+}
+
+void UsbCameraImpl::SetQuirks() {
+  wpi::SmallString<128> descbuf;
+  wpi::StringRef desc = GetDescription(descbuf);
+  m_lifecam_exposure =
+      desc.endswith("LifeCam HD-3000") || desc.endswith("LifeCam Cinema (TM)");
+
+  int deviceNum = GetDeviceNum(m_path.c_str());
+  if (deviceNum >= 0) {
+    int vendorId, productId;
+    if (GetVendorProduct(deviceNum, &vendorId, &productId)) {
+      m_ps3eyecam_exposure = vendorId == 0x1415 && productId == 0x2000;
+    }
+  }
+}
+
+void UsbCameraImpl::SetProperty(int property, int value, CS_Status* status) {
+  Message msg{Message::kCmdSetProperty};
+  msg.data[0] = property;
+  msg.data[1] = value;
+  *status = SendAndWait(std::move(msg));
+}
+
+void UsbCameraImpl::SetStringProperty(int property, const wpi::Twine& value,
+                                      CS_Status* status) {
+  Message msg{Message::kCmdSetPropertyStr};
+  msg.data[0] = property;
+  msg.dataStr = value.str();
+  *status = SendAndWait(std::move(msg));
+}
+
+void UsbCameraImpl::SetBrightness(int brightness, CS_Status* status) {
+  if (brightness > 100) {
+    brightness = 100;
+  } else if (brightness < 0) {
+    brightness = 0;
+  }
+  SetProperty(GetPropertyIndex(kPropBrValue), brightness, status);
+}
+
+int UsbCameraImpl::GetBrightness(CS_Status* status) const {
+  return GetProperty(GetPropertyIndex(kPropBrValue), status);
+}
+
+void UsbCameraImpl::SetWhiteBalanceAuto(CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropWbAuto), 1, status);  // auto
+}
+
+void UsbCameraImpl::SetWhiteBalanceHoldCurrent(CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropWbAuto), 0, status);  // manual
+}
+
+void UsbCameraImpl::SetWhiteBalanceManual(int value, CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropWbAuto), 0, status);  // manual
+  SetProperty(GetPropertyIndex(kPropWbValue), value, status);
+}
+
+void UsbCameraImpl::SetExposureAuto(CS_Status* status) {
+  // auto; this is an enum value
+  if (m_ps3eyecam_exposure) {
+    SetProperty(GetPropertyIndex(quirkPS3EyePropExAuto),
+                quirkPS3EyePropExAutoOn, status);
+
+  } else {
+    SetProperty(GetPropertyIndex(kPropExAuto), 3, status);
+  }
+}
+
+void UsbCameraImpl::SetExposureHoldCurrent(CS_Status* status) {
+  if (m_ps3eyecam_exposure) {
+    SetProperty(GetPropertyIndex(quirkPS3EyePropExAuto),
+                quirkPS3EyePropExAutoOff, status);  // manual
+  } else {
+    SetProperty(GetPropertyIndex(kPropExAuto), 1, status);  // manual
+  }
+}
+
+void UsbCameraImpl::SetExposureManual(int value, CS_Status* status) {
+  if (m_ps3eyecam_exposure) {
+    SetProperty(GetPropertyIndex(quirkPS3EyePropExAuto),
+                quirkPS3EyePropExAutoOff, status);  // manual
+  } else {
+    SetProperty(GetPropertyIndex(kPropExAuto), 1, status);  // manual
+  }
+  if (value > 100) {
+    value = 100;
+  } else if (value < 0) {
+    value = 0;
+  }
+  if (m_ps3eyecam_exposure) {
+    SetProperty(GetPropertyIndex(quirkPS3EyePropExValue), value, status);
+  } else {
+    SetProperty(GetPropertyIndex(kPropExValue), value, status);
+  }
+}
+
+bool UsbCameraImpl::SetVideoMode(const VideoMode& mode, CS_Status* status) {
+  Message msg{Message::kCmdSetMode};
+  msg.data[0] = mode.pixelFormat;
+  msg.data[1] = mode.width;
+  msg.data[2] = mode.height;
+  msg.data[3] = mode.fps;
+  *status = SendAndWait(std::move(msg));
+  return *status == CS_OK;
+}
+
+bool UsbCameraImpl::SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                                   CS_Status* status) {
+  Message msg{Message::kCmdSetPixelFormat};
+  msg.data[0] = pixelFormat;
+  *status = SendAndWait(std::move(msg));
+  return *status == CS_OK;
+}
+
+bool UsbCameraImpl::SetResolution(int width, int height, CS_Status* status) {
+  Message msg{Message::kCmdSetResolution};
+  msg.data[0] = width;
+  msg.data[1] = height;
+  *status = SendAndWait(std::move(msg));
+  return *status == CS_OK;
+}
+
+bool UsbCameraImpl::SetFPS(int fps, CS_Status* status) {
+  Message msg{Message::kCmdSetFPS};
+  msg.data[0] = fps;
+  *status = SendAndWait(std::move(msg));
+  return *status == CS_OK;
+}
+
+void UsbCameraImpl::NumSinksChanged() {
+  Send(Message{Message::kNumSinksChanged});
+}
+
+void UsbCameraImpl::NumSinksEnabledChanged() {
+  Send(Message{Message::kNumSinksEnabledChanged});
+}
+
+namespace cs {
+
+CS_Source CreateUsbCameraDev(const wpi::Twine& name, int dev,
+                             CS_Status* status) {
+  wpi::SmallString<32> path;
+  wpi::raw_svector_ostream oss{path};
+  oss << "/dev/video" << dev;
+  return CreateUsbCameraPath(name, oss.str(), status);
+}
+
+CS_Source CreateUsbCameraPath(const wpi::Twine& name, const wpi::Twine& path,
+                              CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  return inst.CreateSource(CS_SOURCE_USB, std::make_shared<UsbCameraImpl>(
+                                              name, inst.logger, inst.notifier,
+                                              inst.telemetry, path));
+}
+
+std::string GetUsbCameraPath(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_USB) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return static_cast<UsbCameraImpl&>(*data->source).GetPath();
+}
+
+static const char* symlinkDirs[] = {"/dev/v4l/by-id", "/dev/v4l/by-path"};
+
+UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status) {
+  UsbCameraInfo info;
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_USB) {
+    *status = CS_INVALID_HANDLE;
+    return info;
+  }
+  std::string keypath = static_cast<UsbCameraImpl&>(*data->source).GetPath();
+  info.path = keypath;
+
+  // device number
+  info.dev = GetDeviceNum(keypath.c_str());
+
+  // description
+  info.name = GetDescriptionImpl(keypath.c_str());
+
+  // vendor/product id
+  GetVendorProduct(info.dev, &info.vendorId, &info.productId);
+
+  // look through /dev/v4l/by-id and /dev/v4l/by-path for symlinks to the
+  // keypath
+  wpi::SmallString<128> path;
+  for (auto symlinkDir : symlinkDirs) {
+    if (DIR* dp = ::opendir(symlinkDir)) {
+      while (struct dirent* ep = ::readdir(dp)) {
+        if (ep->d_type == DT_LNK) {
+          path = symlinkDir;
+          path += '/';
+          path += ep->d_name;
+          char* target = ::realpath(path.c_str(), nullptr);
+          if (target) {
+            if (keypath == target) info.otherPaths.emplace_back(path.str());
+            std::free(target);
+          }
+        }
+      }
+      ::closedir(dp);
+    }
+  }
+
+  // eliminate any duplicates
+  std::sort(info.otherPaths.begin(), info.otherPaths.end());
+  info.otherPaths.erase(
+      std::unique(info.otherPaths.begin(), info.otherPaths.end()),
+      info.otherPaths.end());
+  return info;
+}
+
+std::vector<UsbCameraInfo> EnumerateUsbCameras(CS_Status* status) {
+  std::vector<UsbCameraInfo> retval;
+
+  if (DIR* dp = ::opendir("/dev")) {
+    while (struct dirent* ep = ::readdir(dp)) {
+      wpi::StringRef fname{ep->d_name};
+      if (!fname.startswith("video")) continue;
+
+      unsigned int dev = 0;
+      if (fname.substr(5).getAsInteger(10, dev)) continue;
+
+      UsbCameraInfo info;
+      info.dev = dev;
+
+      wpi::SmallString<32> path{"/dev/"};
+      path += fname;
+      info.path = path.str();
+
+      info.name = GetDescriptionImpl(path.c_str());
+      if (info.name.empty()) continue;
+
+      GetVendorProduct(dev, &info.vendorId, &info.productId);
+
+      if (dev >= retval.size()) retval.resize(info.dev + 1);
+      retval[info.dev] = std::move(info);
+    }
+    ::closedir(dp);
+  } else {
+    // *status = ;
+    WPI_ERROR(Instance::GetInstance().logger, "Could not open /dev");
+    return retval;
+  }
+
+  // look through /dev/v4l/by-id and /dev/v4l/by-path for symlinks to
+  // /dev/videoN
+  wpi::SmallString<128> path;
+  for (auto symlinkDir : symlinkDirs) {
+    if (DIR* dp = ::opendir(symlinkDir)) {
+      while (struct dirent* ep = ::readdir(dp)) {
+        if (ep->d_type == DT_LNK) {
+          path = symlinkDir;
+          path += '/';
+          path += ep->d_name;
+          char* target = ::realpath(path.c_str(), nullptr);
+          if (target) {
+            wpi::StringRef fname = wpi::sys::path::filename(target);
+            unsigned int dev = 0;
+            if (fname.startswith("video") &&
+                !fname.substr(5).getAsInteger(10, dev) && dev < retval.size()) {
+              retval[dev].otherPaths.emplace_back(path.str());
+            }
+            std::free(target);
+          }
+        }
+      }
+      ::closedir(dp);
+    }
+  }
+
+  // remove devices with empty names
+  retval.erase(
+      std::remove_if(retval.begin(), retval.end(),
+                     [](const UsbCameraInfo& x) { return x.name.empty(); }),
+      retval.end());
+
+  return retval;
+}
+
+}  // namespace cs
diff --git a/cscore/src/main/native/linux/UsbCameraImpl.h b/cscore/src/main/native/linux/UsbCameraImpl.h
new file mode 100644
index 0000000..3627228
--- /dev/null
+++ b/cscore/src/main/native/linux/UsbCameraImpl.h
@@ -0,0 +1,182 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_USBCAMERAIMPL_H_
+#define CSCORE_USBCAMERAIMPL_H_
+
+#include <linux/videodev2.h>
+
+#include <atomic>
+#include <memory>
+#include <string>
+#include <thread>
+#include <utility>
+#include <vector>
+
+#include <wpi/STLExtras.h>
+#include <wpi/SmallVector.h>
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+#include <wpi/raw_istream.h>
+#include <wpi/raw_ostream.h>
+
+#include "SourceImpl.h"
+#include "UsbCameraBuffer.h"
+#include "UsbCameraProperty.h"
+
+namespace cs {
+
+class Notifier;
+class Telemetry;
+
+class UsbCameraImpl : public SourceImpl {
+ public:
+  UsbCameraImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+                Telemetry& telemetry, const wpi::Twine& path);
+  ~UsbCameraImpl() override;
+
+  void Start() override;
+
+  // Property functions
+  void SetProperty(int property, int value, CS_Status* status) override;
+  void SetStringProperty(int property, const wpi::Twine& value,
+                         CS_Status* status) override;
+
+  // Standard common camera properties
+  void SetBrightness(int brightness, CS_Status* status) override;
+  int GetBrightness(CS_Status* status) const override;
+  void SetWhiteBalanceAuto(CS_Status* status) override;
+  void SetWhiteBalanceHoldCurrent(CS_Status* status) override;
+  void SetWhiteBalanceManual(int value, CS_Status* status) override;
+  void SetExposureAuto(CS_Status* status) override;
+  void SetExposureHoldCurrent(CS_Status* status) override;
+  void SetExposureManual(int value, CS_Status* status) override;
+
+  bool SetVideoMode(const VideoMode& mode, CS_Status* status) override;
+  bool SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                      CS_Status* status) override;
+  bool SetResolution(int width, int height, CS_Status* status) override;
+  bool SetFPS(int fps, CS_Status* status) override;
+
+  void NumSinksChanged() override;
+  void NumSinksEnabledChanged() override;
+
+  std::string GetPath() { return m_path; }
+
+  // Messages passed to/from camera thread
+  struct Message {
+    enum Kind {
+      kNone = 0,
+      kCmdSetMode,
+      kCmdSetPixelFormat,
+      kCmdSetResolution,
+      kCmdSetFPS,
+      kCmdSetProperty,
+      kCmdSetPropertyStr,
+      kNumSinksChanged,         // no response
+      kNumSinksEnabledChanged,  // no response
+      // Responses
+      kOk,
+      kError
+    };
+
+    explicit Message(Kind kind_)
+        : kind(kind_), from(std::this_thread::get_id()) {}
+
+    Kind kind;
+    int data[4];
+    std::string dataStr;
+    std::thread::id from;
+  };
+
+ protected:
+  std::unique_ptr<PropertyImpl> CreateEmptyProperty(
+      const wpi::Twine& name) const override;
+
+  // Cache properties.  Immediately successful if properties are already cached.
+  // If they are not, tries to connect to the camera to do so; returns false and
+  // sets status to CS_SOURCE_IS_DISCONNECTED if that too fails.
+  bool CacheProperties(CS_Status* status) const override;
+
+ private:
+  // Send a message to the camera thread and wait for a response (generic)
+  CS_StatusValue SendAndWait(Message&& msg) const;
+  // Send a message to the camera thread with no response
+  void Send(Message&& msg) const;
+
+  // The camera processing thread
+  void CameraThreadMain();
+
+  // Functions used by CameraThreadMain()
+  void DeviceDisconnect();
+  void DeviceConnect();
+  bool DeviceStreamOn();
+  bool DeviceStreamOff();
+  void DeviceProcessCommands();
+  void DeviceSetMode();
+  void DeviceSetFPS();
+  void DeviceCacheMode();
+  void DeviceCacheProperty(std::unique_ptr<UsbCameraProperty> rawProp);
+  void DeviceCacheProperties();
+  void DeviceCacheVideoModes();
+
+  // Command helper functions
+  CS_StatusValue DeviceProcessCommand(std::unique_lock<wpi::mutex>& lock,
+                                      const Message& msg);
+  CS_StatusValue DeviceCmdSetMode(std::unique_lock<wpi::mutex>& lock,
+                                  const Message& msg);
+  CS_StatusValue DeviceCmdSetProperty(std::unique_lock<wpi::mutex>& lock,
+                                      const Message& msg);
+
+  // Property helper functions
+  int RawToPercentage(const UsbCameraProperty& rawProp, int rawValue);
+  int PercentageToRaw(const UsbCameraProperty& rawProp, int percentValue);
+
+  void SetQuirks();
+
+  //
+  // Variables only used within camera thread
+  //
+  bool m_streaming;
+  bool m_modeSetPixelFormat{false};
+  bool m_modeSetResolution{false};
+  bool m_modeSetFPS{false};
+  int m_connectVerbose{1};
+  unsigned m_capabilities = 0;
+  // Number of buffers to ask OS for
+  static constexpr int kNumBuffers = 4;
+  std::array<UsbCameraBuffer, kNumBuffers> m_buffers;
+
+  //
+  // Path never changes, so not protected by mutex.
+  //
+  std::string m_path;
+
+  std::atomic_int m_fd;
+  std::atomic_int m_command_fd;  // for command eventfd
+
+  std::atomic_bool m_active;  // set to false to terminate thread
+  std::thread m_cameraThread;
+
+  // Quirks
+  bool m_lifecam_exposure{false};    // Microsoft LifeCam exposure
+  bool m_ps3eyecam_exposure{false};  // PS3 Eyecam exposure
+
+  //
+  // Variables protected by m_mutex
+  //
+
+  // Message queues
+  mutable std::vector<Message> m_commands;
+  mutable std::vector<std::pair<std::thread::id, CS_StatusValue>> m_responses;
+  mutable wpi::condition_variable m_responseCv;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_USBCAMERAIMPL_H_
diff --git a/cscore/src/main/native/linux/UsbCameraProperty.cpp b/cscore/src/main/native/linux/UsbCameraProperty.cpp
new file mode 100644
index 0000000..4dfa39c
--- /dev/null
+++ b/cscore/src/main/native/linux/UsbCameraProperty.cpp
@@ -0,0 +1,330 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "UsbCameraProperty.h"
+
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "UsbUtil.h"
+
+using namespace cs;
+
+static int GetIntCtrlIoctl(int fd, unsigned id, int type, int64_t* value) {
+  unsigned ctrl_class = V4L2_CTRL_ID2CLASS(id);
+  if (type == V4L2_CTRL_TYPE_INTEGER64 || V4L2_CTRL_DRIVER_PRIV(id) ||
+      (ctrl_class != V4L2_CTRL_CLASS_USER &&
+       ctrl_class != V4L2_CID_PRIVATE_BASE)) {
+    // Use extended control
+    struct v4l2_ext_control ctrl;
+    struct v4l2_ext_controls ctrls;
+    std::memset(&ctrl, 0, sizeof(ctrl));
+    std::memset(&ctrls, 0, sizeof(ctrls));
+    ctrl.id = id;
+    ctrls.ctrl_class = ctrl_class;
+    ctrls.count = 1;
+    ctrls.controls = &ctrl;
+    int rc = DoIoctl(fd, VIDIOC_G_EXT_CTRLS, &ctrls);
+    if (rc < 0) return rc;
+    *value = ctrl.value;
+  } else {
+    // Use normal control
+    struct v4l2_control ctrl;
+    std::memset(&ctrl, 0, sizeof(ctrl));
+    ctrl.id = id;
+    int rc = DoIoctl(fd, VIDIOC_G_CTRL, &ctrl);
+    if (rc < 0) return rc;
+    *value = ctrl.value;
+  }
+  return 0;
+}
+
+static int SetIntCtrlIoctl(int fd, unsigned id, int type, int64_t value) {
+  unsigned ctrl_class = V4L2_CTRL_ID2CLASS(id);
+  if (type == V4L2_CTRL_TYPE_INTEGER64 || V4L2_CTRL_DRIVER_PRIV(id) ||
+      (ctrl_class != V4L2_CTRL_CLASS_USER &&
+       ctrl_class != V4L2_CID_PRIVATE_BASE)) {
+    // Use extended control
+    struct v4l2_ext_control ctrl;
+    struct v4l2_ext_controls ctrls;
+    std::memset(&ctrl, 0, sizeof(ctrl));
+    std::memset(&ctrls, 0, sizeof(ctrls));
+    ctrl.id = id;
+    if (type == V4L2_CTRL_TYPE_INTEGER64)
+      ctrl.value64 = value;
+    else
+      ctrl.value = static_cast<__s32>(value);
+    ctrls.ctrl_class = ctrl_class;
+    ctrls.count = 1;
+    ctrls.controls = &ctrl;
+    return DoIoctl(fd, VIDIOC_S_EXT_CTRLS, &ctrls);
+  } else {
+    // Use normal control
+    struct v4l2_control ctrl;
+    ctrl.id = id;
+    ctrl.value = static_cast<__s32>(value);
+    return DoIoctl(fd, VIDIOC_S_CTRL, &ctrl);
+  }
+}
+
+static int GetStringCtrlIoctl(int fd, int id, int maximum, std::string* value) {
+  struct v4l2_ext_control ctrl;
+  struct v4l2_ext_controls ctrls;
+  std::memset(&ctrl, 0, sizeof(ctrl));
+  std::memset(&ctrls, 0, sizeof(ctrls));
+  ctrl.id = id;
+  ctrls.ctrl_class = V4L2_CTRL_ID2CLASS(id);
+  ctrls.count = 1;
+  ctrls.controls = &ctrl;
+  int rc = DoIoctl(fd, VIDIOC_G_EXT_CTRLS, &ctrls);
+  if (rc < 0) {
+    value->clear();
+    return rc;
+  }
+  value->assign(ctrl.string, std::strlen(ctrl.string));
+  return 0;
+}
+
+static int SetStringCtrlIoctl(int fd, int id, int maximum,
+                              const wpi::Twine& value) {
+  wpi::SmallString<64> strBuf, strBuf2;
+  wpi::StringRef str = value.toNullTerminatedStringRef(strBuf);
+  if (str.size() > static_cast<size_t>(maximum)) {
+    // don't know if strBuf was used, just recopy
+    strBuf2 = str.take_front(maximum);
+    str = strBuf2;
+    strBuf2.push_back('\0');  // null terminate
+  }
+
+  struct v4l2_ext_control ctrl;
+  struct v4l2_ext_controls ctrls;
+  std::memset(&ctrl, 0, sizeof(ctrl));
+  std::memset(&ctrls, 0, sizeof(ctrls));
+  ctrl.id = id;
+  ctrl.size = str.size();
+  ctrl.string = const_cast<char*>(str.data());
+  ctrls.ctrl_class = V4L2_CTRL_ID2CLASS(id);
+  ctrls.count = 1;
+  ctrls.controls = &ctrl;
+  return DoIoctl(fd, VIDIOC_S_EXT_CTRLS, &ctrls);
+}
+
+// Removes non-alphanumeric characters and replaces spaces with underscores.
+// e.g. "Zoom, Absolute" -> "zoom_absolute", "Pan (Absolute)" -> "pan_absolute"
+static wpi::StringRef NormalizeName(wpi::StringRef name,
+                                    wpi::SmallVectorImpl<char>& buf) {
+  bool newWord = false;
+  for (auto ch : name) {
+    if (std::isalnum(ch)) {
+      if (newWord) buf.push_back('_');
+      newWord = false;
+      buf.push_back(std::tolower(ch));
+    } else if (!buf.empty()) {
+      newWord = true;
+    }
+  }
+  return wpi::StringRef(buf.data(), buf.size());
+}
+
+#ifdef VIDIOC_QUERY_EXT_CTRL
+UsbCameraProperty::UsbCameraProperty(const struct v4l2_query_ext_ctrl& ctrl)
+    : PropertyImpl(wpi::StringRef{}, CS_PROP_NONE, ctrl.step,
+                   ctrl.default_value, 0),
+      id(ctrl.id & V4L2_CTRL_ID_MASK),
+      type(ctrl.type) {
+  hasMinimum = true;
+  minimum = ctrl.minimum;
+  hasMaximum = true;
+  maximum = ctrl.maximum;
+
+  // propKind
+  switch (ctrl.type) {
+    case V4L2_CTRL_TYPE_INTEGER:
+    case V4L2_CTRL_TYPE_INTEGER64:
+      propKind = CS_PROP_INTEGER;
+      break;
+    case V4L2_CTRL_TYPE_BOOLEAN:
+      propKind = CS_PROP_BOOLEAN;
+      break;
+    case V4L2_CTRL_TYPE_INTEGER_MENU:
+      propKind = CS_PROP_ENUM;
+      intMenu = true;
+      break;
+    case V4L2_CTRL_TYPE_MENU:
+      propKind = CS_PROP_ENUM;
+      break;
+    case V4L2_CTRL_TYPE_STRING:
+      propKind = CS_PROP_STRING;
+      break;
+    default:
+      return;  // others unsupported
+  }
+
+  // name
+  size_t len = 0;
+  while (len < sizeof(ctrl.name) && ctrl.name[len] != '\0') ++len;
+  wpi::SmallString<64> name_buf;
+  name = NormalizeName(wpi::StringRef(ctrl.name, len), name_buf);
+}
+#endif
+
+UsbCameraProperty::UsbCameraProperty(const struct v4l2_queryctrl& ctrl)
+    : PropertyImpl(wpi::StringRef{}, CS_PROP_NONE, ctrl.step,
+                   ctrl.default_value, 0),
+      id(ctrl.id & V4L2_CTRL_ID_MASK),
+      type(ctrl.type) {
+  hasMinimum = true;
+  minimum = ctrl.minimum;
+  hasMaximum = true;
+  maximum = ctrl.maximum;
+
+  // propKind
+  switch (ctrl.type) {
+    case V4L2_CTRL_TYPE_INTEGER:
+    case V4L2_CTRL_TYPE_INTEGER64:
+      propKind = CS_PROP_INTEGER;
+      break;
+    case V4L2_CTRL_TYPE_BOOLEAN:
+      propKind = CS_PROP_BOOLEAN;
+      break;
+    case V4L2_CTRL_TYPE_INTEGER_MENU:
+    case V4L2_CTRL_TYPE_MENU:
+      propKind = CS_PROP_ENUM;
+      break;
+    case V4L2_CTRL_TYPE_STRING:
+      propKind = CS_PROP_STRING;
+      break;
+    default:
+      return;  // others unsupported
+  }
+
+  // name
+  size_t len = 0;
+  while (len < sizeof(ctrl.name) && ctrl.name[len] != '\0') ++len;
+  wpi::SmallString<64> name_buf;
+  name = NormalizeName(
+      wpi::StringRef(reinterpret_cast<const char*>(ctrl.name), len), name_buf);
+}
+
+std::unique_ptr<UsbCameraProperty> UsbCameraProperty::DeviceQuery(int fd,
+                                                                  __u32* id) {
+  int rc;
+  std::unique_ptr<UsbCameraProperty> prop;
+#ifdef VIDIOC_QUERY_EXT_CTRL
+  v4l2_query_ext_ctrl qc_ext;
+  std::memset(&qc_ext, 0, sizeof(qc_ext));
+  qc_ext.id = *id;
+  rc = TryIoctl(fd, VIDIOC_QUERY_EXT_CTRL, &qc_ext);
+  if (rc == 0) {
+    *id = qc_ext.id;  // copy back
+    // We don't support array types
+    if (qc_ext.elems > 1 || qc_ext.nr_of_dims > 0) return nullptr;
+    prop = std::make_unique<UsbCameraProperty>(qc_ext);
+  }
+#endif
+  if (!prop) {
+    // Fall back to normal QUERYCTRL
+    struct v4l2_queryctrl qc;
+    std::memset(&qc, 0, sizeof(qc));
+    qc.id = *id;
+    rc = TryIoctl(fd, VIDIOC_QUERYCTRL, &qc);
+    *id = qc.id;  // copy back
+    if (rc != 0) return nullptr;
+    prop = std::make_unique<UsbCameraProperty>(qc);
+  }
+
+  // Cache enum property choices
+  if (prop->propKind == CS_PROP_ENUM) {
+    prop->enumChoices.resize(prop->maximum + 1);
+    v4l2_querymenu qmenu;
+    std::memset(&qmenu, 0, sizeof(qmenu));
+    qmenu.id = *id;
+    for (int i = prop->minimum; i <= prop->maximum; ++i) {
+      qmenu.index = static_cast<__u32>(i);
+      if (TryIoctl(fd, VIDIOC_QUERYMENU, &qmenu) != 0) continue;
+      if (prop->intMenu) {
+        wpi::raw_string_ostream os(prop->enumChoices[i]);
+        os << qmenu.value;
+      } else {
+        prop->enumChoices[i] = reinterpret_cast<const char*>(qmenu.name);
+      }
+    }
+  }
+
+  return prop;
+}
+
+bool UsbCameraProperty::DeviceGet(std::unique_lock<wpi::mutex>& lock, int fd) {
+  if (fd < 0) return true;
+  unsigned idCopy = id;
+  int rv = 0;
+
+  switch (propKind) {
+    case CS_PROP_BOOLEAN:
+    case CS_PROP_INTEGER:
+    case CS_PROP_ENUM: {
+      int typeCopy = type;
+      int64_t newValue = 0;
+      lock.unlock();
+      rv = GetIntCtrlIoctl(fd, idCopy, typeCopy, &newValue);
+      lock.lock();
+      if (rv >= 0) value = newValue;
+      break;
+    }
+    case CS_PROP_STRING: {
+      int maximumCopy = maximum;
+      std::string newValueStr;
+      lock.unlock();
+      rv = GetStringCtrlIoctl(fd, idCopy, maximumCopy, &newValueStr);
+      lock.lock();
+      if (rv >= 0) valueStr = std::move(newValueStr);
+      break;
+    }
+    default:
+      break;
+  }
+
+  return rv >= 0;
+}
+
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                                  int fd) const {
+  // Make a copy of the string as we're about to release the lock
+  wpi::SmallString<128> valueStrCopy{valueStr};
+  return DeviceSet(lock, fd, value, valueStrCopy);
+}
+
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock, int fd,
+                                  int newValue,
+                                  const wpi::Twine& newValueStr) const {
+  if (!device || fd < 0) return true;
+  unsigned idCopy = id;
+  int rv = 0;
+
+  switch (propKind) {
+    case CS_PROP_BOOLEAN:
+    case CS_PROP_INTEGER:
+    case CS_PROP_ENUM: {
+      int typeCopy = type;
+      lock.unlock();
+      rv = SetIntCtrlIoctl(fd, idCopy, typeCopy, newValue);
+      lock.lock();
+      break;
+    }
+    case CS_PROP_STRING: {
+      int maximumCopy = maximum;
+      lock.unlock();
+      rv = SetStringCtrlIoctl(fd, idCopy, maximumCopy, newValueStr);
+      lock.lock();
+      break;
+    }
+    default:
+      break;
+  }
+
+  return rv >= 0;
+}
diff --git a/cscore/src/main/native/linux/UsbCameraProperty.h b/cscore/src/main/native/linux/UsbCameraProperty.h
new file mode 100644
index 0000000..32c5e19
--- /dev/null
+++ b/cscore/src/main/native/linux/UsbCameraProperty.h
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_USBCAMERAPROPERTY_H_
+#define CSCORE_USBCAMERAPROPERTY_H_
+
+#include <linux/videodev2.h>
+
+#include <memory>
+
+#include <wpi/mutex.h>
+
+#include "PropertyImpl.h"
+
+namespace cs {
+
+// Property data
+class UsbCameraProperty : public PropertyImpl {
+ public:
+  UsbCameraProperty() = default;
+  explicit UsbCameraProperty(const wpi::Twine& name_) : PropertyImpl{name_} {}
+
+  // Software property constructor
+  UsbCameraProperty(const wpi::Twine& name_, unsigned id_,
+                    CS_PropertyKind kind_, int minimum_, int maximum_,
+                    int step_, int defaultValue_, int value_)
+      : PropertyImpl(name_, kind_, minimum_, maximum_, step_, defaultValue_,
+                     value_),
+        device{false},
+        id{id_} {}
+
+  // Normalized property constructor
+  UsbCameraProperty(const wpi::Twine& name_, int rawIndex_,
+                    const UsbCameraProperty& rawProp, int defaultValue_,
+                    int value_)
+      : PropertyImpl(name_, rawProp.propKind, 1, defaultValue_, value_),
+        percentage{true},
+        propPair{rawIndex_},
+        id{rawProp.id},
+        type{rawProp.type} {
+    hasMinimum = true;
+    minimum = 0;
+    hasMaximum = true;
+    maximum = 100;
+  }
+
+#ifdef VIDIOC_QUERY_EXT_CTRL
+  explicit UsbCameraProperty(const struct v4l2_query_ext_ctrl& ctrl);
+#endif
+  explicit UsbCameraProperty(const struct v4l2_queryctrl& ctrl);
+
+  static std::unique_ptr<UsbCameraProperty> DeviceQuery(int fd, __u32* id);
+
+  bool DeviceGet(std::unique_lock<wpi::mutex>& lock, int fd);
+  bool DeviceSet(std::unique_lock<wpi::mutex>& lock, int fd) const;
+  bool DeviceSet(std::unique_lock<wpi::mutex>& lock, int fd, int newValue,
+                 const wpi::Twine& newValueStr) const;
+
+  // If this is a device (rather than software) property
+  bool device{true};
+
+  // If this is a percentage (rather than raw) property
+  bool percentage{false};
+
+  // If not 0, index of corresponding raw/percentage property
+  int propPair{0};
+
+  unsigned id{0};  // implementation-level id
+  int type{0};     // implementation type, not CS_PropertyKind!
+
+  // If the enum property is integer rather than string
+  bool intMenu{false};
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_USBCAMERAPROPERTY_H_
diff --git a/cscore/src/main/native/linux/UsbUtil.cpp b/cscore/src/main/native/linux/UsbUtil.cpp
new file mode 100644
index 0000000..ac48178
--- /dev/null
+++ b/cscore/src/main/native/linux/UsbUtil.cpp
@@ -0,0 +1,161 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "UsbUtil.h"
+
+#include <fcntl.h>
+#include <libgen.h>
+#include <sys/ioctl.h>
+
+#include <wpi/Format.h>
+#include <wpi/SmallString.h>
+#include <wpi/raw_istream.h>
+#include <wpi/raw_ostream.h>
+
+#include "Instance.h"
+#include "Log.h"
+
+namespace cs {
+
+static wpi::StringRef GetUsbNameFromFile(int vendor, int product,
+                                         wpi::SmallVectorImpl<char>& buf) {
+  int fd = open("/var/lib/usbutils/usb.ids", O_RDONLY);
+  if (fd < 0) return wpi::StringRef{};
+
+  wpi::raw_svector_ostream os{buf};
+  wpi::raw_fd_istream is{fd, true};
+
+  // build vendor and product 4-char hex strings
+  wpi::SmallString<16> vendorStr, productStr;
+  wpi::raw_svector_ostream vendorOs{vendorStr}, productOs{productStr};
+  vendorOs << wpi::format_hex_no_prefix(vendor, 4);
+  productOs << wpi::format_hex_no_prefix(product, 4);
+
+  // scan file
+  wpi::SmallString<128> lineBuf;
+  bool foundVendor = false;
+  for (;;) {
+    auto line = is.getline(lineBuf, 4096);
+    if (is.has_error()) break;
+
+    if (line.empty()) continue;
+
+    // look for vendor at start of line
+    if (line.startswith(vendorStr)) {
+      foundVendor = true;
+      os << line.substr(5).trim() << ' ';
+      continue;
+    }
+
+    if (foundVendor) {
+      // next vendor, but didn't match product?
+      if (line[0] != '\t') {
+        os << "Unknown";
+        return os.str();
+      }
+
+      // look for product
+      if (line.substr(1).startswith(productStr)) {
+        os << line.substr(6).trim();
+        return os.str();
+      }
+    }
+  }
+
+  return wpi::StringRef{};
+}
+
+wpi::StringRef GetUsbNameFromId(int vendor, int product,
+                                wpi::SmallVectorImpl<char>& buf) {
+  // try reading usb.ids
+  wpi::StringRef rv = GetUsbNameFromFile(vendor, product, buf);
+  if (!rv.empty()) return rv;
+
+  // Fall back to internal database
+  wpi::raw_svector_ostream os{buf};
+  switch (vendor) {
+    case 0x046d:
+      os << "Logitech, Inc. ";
+      switch (product) {
+        case 0x0802:
+          os << "Webcam C200";
+          break;
+        case 0x0804:
+          os << "Webcam C250";
+          break;
+        case 0x0805:
+          os << "Webcam C300";
+          break;
+        case 0x0807:
+          os << "Webcam B500";
+          break;
+        case 0x0808:
+          os << "Webcam C600";
+          break;
+        case 0x0809:
+          os << "Webcam Pro 9000";
+          break;
+        case 0x080a:
+          os << "Portable Webcam C905";
+          break;
+        case 0x080f:
+          os << "Webcam C120";
+          break;
+        case 0x0819:
+          os << "Webcam C210";
+          break;
+        case 0x081b:
+          os << "Webcam C310";
+          break;
+        case 0x081d:
+          os << "HD Webcam C510";
+          break;
+        case 0x0821:
+          os << "HD Webcam C910";
+          break;
+        case 0x0825:
+          os << "Webcam C270";
+          break;
+        case 0x0826:
+          os << "HD Webcam C525";
+          break;
+        case 0x0828:
+          os << "HD Webcam B990";
+          break;
+        case 0x082b:
+          os << "Webcam C170";
+          break;
+        case 0x082d:
+          os << "HD Pro Webcam C920";
+          break;
+        case 0x0836:
+          os << "B525 HD Webcam";
+          break;
+        case 0x0843:
+          os << "Webcam C930e";
+          break;
+      }
+      break;
+  }
+
+  return os.str();
+}
+
+int CheckedIoctl(int fd, unsigned long req, void* data,  // NOLINT(runtime/int)
+                 const char* name, const char* file, int line, bool quiet) {
+  int retval = ioctl(fd, req, data);
+  if (!quiet && retval < 0) {
+    wpi::SmallString<64> localfile{file};
+    localfile.push_back('\0');
+    WPI_ERROR(Instance::GetInstance().logger,
+              "ioctl " << name << " failed at " << basename(localfile.data())
+                       << ":" << line << ": " << std::strerror(errno));
+  }
+  return retval;
+}
+
+}  // namespace cs
diff --git a/cscore/src/main/native/linux/UsbUtil.h b/cscore/src/main/native/linux/UsbUtil.h
new file mode 100644
index 0000000..4f1d9d8
--- /dev/null
+++ b/cscore/src/main/native/linux/UsbUtil.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_USBUTIL_H_
+#define CSCORE_USBUTIL_H_
+
+#include <stdint.h>
+
+#include <wpi/SmallVector.h>
+#include <wpi/StringRef.h>
+
+namespace cs {
+
+wpi::StringRef GetUsbNameFromId(int vendor, int product,
+                                wpi::SmallVectorImpl<char>& buf);
+
+int CheckedIoctl(int fd, unsigned long req, void* data,  // NOLINT(runtime/int)
+                 const char* name, const char* file, int line, bool quiet);
+
+#define DoIoctl(fd, req, data) \
+  CheckedIoctl(fd, req, data, #req, __FILE__, __LINE__, false)
+#define TryIoctl(fd, req, data) \
+  CheckedIoctl(fd, req, data, #req, __FILE__, __LINE__, true)
+
+}  // namespace cs
+
+#endif  // CSCORE_USBUTIL_H_
diff --git a/cscore/src/main/native/objcpp/objcpptemp.mm b/cscore/src/main/native/objcpp/objcpptemp.mm
new file mode 100644
index 0000000..27aaaff
--- /dev/null
+++ b/cscore/src/main/native/objcpp/objcpptemp.mm
@@ -0,0 +1,12 @@
+#import <Foundation/Foundation.h>
+
+@interface XYZPerson : NSObject
+- (void)sayHello;
+@end
+
+
+@implementation XYZPerson
+- (void)sayHello {
+    NSLog(@"Hello, World!");
+}
+@end
diff --git a/cscore/src/main/native/osx/NetworkListener.cpp b/cscore/src/main/native/osx/NetworkListener.cpp
new file mode 100644
index 0000000..0716789
--- /dev/null
+++ b/cscore/src/main/native/osx/NetworkListener.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkListener.h"
+
+using namespace cs;
+
+class NetworkListener::Impl {};
+
+NetworkListener::NetworkListener(wpi::Logger& logger, Notifier& notifier) {}
+
+NetworkListener::~NetworkListener() {}
+
+void NetworkListener::Start() {}
+
+void NetworkListener::Stop() {}
diff --git a/cscore/src/main/native/osx/NetworkUtil.cpp b/cscore/src/main/native/osx/NetworkUtil.cpp
new file mode 100644
index 0000000..935c21f
--- /dev/null
+++ b/cscore/src/main/native/osx/NetworkUtil.cpp
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "cscore_cpp.h"
+
+namespace cs {
+
+std::vector<std::string> GetNetworkInterfaces() {
+  return std::vector<std::string>{};  // TODO
+}
+
+}  // namespace cs
diff --git a/cscore/src/main/native/osx/UsbCameraImpl.cpp b/cscore/src/main/native/osx/UsbCameraImpl.cpp
new file mode 100644
index 0000000..a10fae4
--- /dev/null
+++ b/cscore/src/main/native/osx/UsbCameraImpl.cpp
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "cscore_cpp.h"
+
+namespace cs {
+
+CS_Source CreateUsbCameraDev(const wpi::Twine& name, int dev,
+                             CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+  return 0;
+}
+
+CS_Source CreateUsbCameraPath(const wpi::Twine& name, const wpi::Twine& path,
+                              CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+  return 0;
+}
+
+std::string GetUsbCameraPath(CS_Source source, CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+  return std::string{};
+}
+
+UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+  return UsbCameraInfo{};
+}
+
+std::vector<UsbCameraInfo> EnumerateUsbCameras(CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+  return std::vector<UsbCameraInfo>{};
+}
+
+}  // namespace cs
diff --git a/cscore/src/main/native/windows/COMCreators.cpp b/cscore/src/main/native/windows/COMCreators.cpp
new file mode 100644
index 0000000..265f7d3
--- /dev/null
+++ b/cscore/src/main/native/windows/COMCreators.cpp
@@ -0,0 +1,158 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <mfapi.h>
+#include <mfidl.h>
+#include <shlwapi.h>
+#include <windowsx.h>
+
+#include <Windows.h>
+
+#include "UsbCameraImpl.h"
+
+// https://github.com/opencv/opencv/blob/master/modules/videoio/src/cap_msmf.cpp
+
+#include <mfidl.h>
+#include <mfapi.h>
+#include <Dbt.h>
+#include <ks.h>
+#include <ksmedia.h>
+#include <mfreadwrite.h>
+
+#include "COMCreators.h"
+#include "ComPtr.h"
+
+#pragma comment(lib, "Mfplat.lib")
+#pragma comment(lib, "Mf.lib")
+#pragma comment(lib, "mfuuid.lib")
+#pragma comment(lib, "Ole32.lib")
+#pragma comment(lib, "User32.lib")
+#pragma comment(lib, "Mfreadwrite.lib")
+#pragma comment(lib, "Shlwapi.lib")
+
+namespace cs {
+
+SourceReaderCB::SourceReaderCB(std::weak_ptr<cs::UsbCameraImpl> source,
+                               const cs::VideoMode& mode)
+    : m_nRefCount(1), m_source(source), m_mode{mode} {}
+
+// IUnknown methods
+STDMETHODIMP SourceReaderCB::QueryInterface(REFIID iid, void** ppv) {
+  static const QITAB qit[] = {
+      QITABENT(SourceReaderCB, IMFSourceReaderCallback),
+      {0},
+  };
+  return QISearch(this, qit, iid, ppv);
+}
+STDMETHODIMP_(ULONG) SourceReaderCB::AddRef() {
+  return InterlockedIncrement(&m_nRefCount);
+}
+STDMETHODIMP_(ULONG) SourceReaderCB::Release() {
+  ULONG uCount = InterlockedDecrement(&m_nRefCount);
+  if (uCount == 0) {
+    delete this;
+  }
+  return uCount;
+}
+
+STDMETHODIMP SourceReaderCB::OnEvent(DWORD, IMFMediaEvent*) { return S_OK; }
+
+STDMETHODIMP SourceReaderCB::OnFlush(DWORD) { return S_OK; }
+
+void SourceReaderCB::NotifyError(HRESULT hr) {
+  wprintf(L"Source Reader error: 0x%X\n", hr);
+}
+
+STDMETHODIMP SourceReaderCB::OnReadSample(HRESULT hrStatus, DWORD dwStreamIndex,
+                                          DWORD dwStreamFlags,
+                                          LONGLONG llTimestamp,
+                                          IMFSample* pSample  // Can be NULL
+) {
+  auto source = m_source.lock();
+  if (!source) return S_OK;
+  if (SUCCEEDED(hrStatus)) {
+    if (pSample) {
+      // Prcoess sample
+      source->ProcessFrame(pSample, m_mode);
+      // DO NOT release the frame
+    }
+  } else {
+    // Streaming error.
+    NotifyError(hrStatus);
+  }
+  // Trigger asking for a new frame.
+  // This is piped through the message pump for concurrency reasons
+  source->PostRequestNewFrame();
+  return S_OK;
+}
+
+// Create a Source Reader COM Smart Object
+ComPtr<SourceReaderCB> CreateSourceReaderCB(
+    std::weak_ptr<cs::UsbCameraImpl> source, const cs::VideoMode& mode) {
+  SourceReaderCB* ptr = new SourceReaderCB(source, mode);
+  ComPtr<SourceReaderCB> sourceReaderCB;
+  sourceReaderCB.Attach(ptr);
+  return sourceReaderCB;
+}
+
+ComPtr<IMFMediaSource> CreateVideoCaptureDevice(LPCWSTR pszSymbolicLink) {
+  ComPtr<IMFAttributes> pAttributes;
+  ComPtr<IMFMediaSource> pSource;
+
+  HRESULT hr = MFCreateAttributes(pAttributes.GetAddressOf(), 2);
+
+  // Set the device type to video.
+  if (SUCCEEDED(hr)) {
+    hr = pAttributes->SetGUID(MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE,
+                              MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE_VIDCAP_GUID);
+  }
+
+  // Set the symbolic link.
+  if (SUCCEEDED(hr)) {
+    hr = pAttributes->SetString(
+        MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE_VIDCAP_SYMBOLIC_LINK,
+        pszSymbolicLink);
+  }
+
+  if (SUCCEEDED(hr)) {
+    hr = MFCreateDeviceSource(pAttributes.Get(), pSource.GetAddressOf());
+  }
+
+  // No need to check last HR, as the source would be null anyway.
+  return pSource;
+}
+
+ComPtr<IMFSourceReader> CreateSourceReader(IMFMediaSource* mediaSource,
+                                           IMFSourceReaderCallback* callback) {
+  HRESULT hr = S_OK;
+  ComPtr<IMFAttributes> pAttributes;
+  ComPtr<IMFSourceReader> sourceReader;
+
+  hr = MFCreateAttributes(pAttributes.GetAddressOf(), 1);
+  if (FAILED(hr)) {
+    return nullptr;
+  }
+
+  hr = pAttributes->SetUnknown(MF_SOURCE_READER_ASYNC_CALLBACK, callback);
+  if (FAILED(hr)) {
+    return nullptr;
+  }
+
+  hr = pAttributes->SetUINT32(
+      MF_SOURCE_READER_DISCONNECT_MEDIASOURCE_ON_SHUTDOWN, TRUE);
+  if (FAILED(hr)) {
+    return nullptr;
+  }
+
+  MFCreateSourceReaderFromMediaSource(mediaSource, pAttributes.Get(),
+                                      sourceReader.GetAddressOf());
+
+  // No need to check last HR, as the sourceReader would be null anyway.
+  return sourceReader;
+}
+
+}  // namespace cs
diff --git a/cscore/src/main/native/windows/COMCreators.h b/cscore/src/main/native/windows/COMCreators.h
new file mode 100644
index 0000000..f89e6fd
--- /dev/null
+++ b/cscore/src/main/native/windows/COMCreators.h
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <mfidl.h>
+#include <mfreadwrite.h>
+
+#include <memory>
+
+#include "ComPtr.h"
+#include "cscore_cpp.h"
+
+namespace cs {
+
+class UsbCameraImpl;
+
+// Source callback used by the source reader.
+// COM object, so it needs a to ref count itself.
+class SourceReaderCB : public IMFSourceReaderCallback {
+ public:
+  explicit SourceReaderCB(std::weak_ptr<cs::UsbCameraImpl> source,
+                          const cs::VideoMode& mode);
+  void SetVideoMode(const VideoMode& mode) { m_mode = mode; }
+
+  STDMETHODIMP QueryInterface(REFIID iid, void** ppv);
+  STDMETHODIMP_(ULONG) AddRef();
+  STDMETHODIMP_(ULONG) Release();
+
+  STDMETHODIMP OnEvent(DWORD, IMFMediaEvent*);
+  STDMETHODIMP OnFlush(DWORD);
+  STDMETHODIMP OnReadSample(HRESULT hrStatus, DWORD dwStreamIndex,
+                            DWORD dwStreamFlags, LONGLONG llTimestamp,
+                            IMFSample* pSample  // Can be NULL
+  );
+
+  void InvalidateCapture() { m_source = std::weak_ptr<cs::UsbCameraImpl>(); }
+
+ private:
+  // Destructor is private. Caller should call Release.
+  virtual ~SourceReaderCB() {}
+  void NotifyError(HRESULT hr);
+
+  ULONG m_nRefCount;
+  std::weak_ptr<cs::UsbCameraImpl> m_source;
+  cs::VideoMode m_mode;
+};
+
+ComPtr<SourceReaderCB> CreateSourceReaderCB(
+    std::weak_ptr<cs::UsbCameraImpl> source, const cs::VideoMode& mode);
+ComPtr<IMFSourceReader> CreateSourceReader(IMFMediaSource* mediaSource,
+                                           IMFSourceReaderCallback* callback);
+ComPtr<IMFMediaSource> CreateVideoCaptureDevice(LPCWSTR pszSymbolicLink);
+}  // namespace cs
diff --git a/cscore/src/main/native/windows/ComPtr.h b/cscore/src/main/native/windows/ComPtr.h
new file mode 100644
index 0000000..22a330d
--- /dev/null
+++ b/cscore/src/main/native/windows/ComPtr.h
@@ -0,0 +1,152 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <comdef.h>
+#include <shlwapi.h>  // QISearch
+
+#include <cassert>
+
+namespace cs {
+
+template <typename Interface>
+class RemoveAddRefRelease : public Interface {
+  ULONG __stdcall AddRef();
+  ULONG __stdcall Release();
+  virtual ~RemoveAddRefRelease();
+};
+
+template <typename Interface>
+class ComPtr {
+ public:
+  template <typename T>
+  friend class ComPtr;
+
+  ComPtr(std::nullptr_t = nullptr) noexcept {}  // NOLINT(runtime/explicit)
+  ComPtr(const ComPtr& other) noexcept : m_ptr(other.m_ptr) {
+    InternalAddRef();
+  }
+
+  template <typename T>
+  ComPtr(const ComPtr<T>& other) noexcept : m_ptr(other.m_ptr) {
+    InternalAddRef();
+  }
+
+  template <typename T>
+  ComPtr(ComPtr<T>&& other) noexcept : m_ptr(other.m_ptr) {
+    other.m_ptr = nullptr;
+  }
+
+  ~ComPtr() noexcept { InternalRelease(); }
+
+  ComPtr& operator=(const ComPtr& other) noexcept {
+    InternalCopy(other.m_ptr);
+    return *this;
+  }
+
+  template <typename T>
+  ComPtr& operator=(const ComPtr<T>& other) noexcept {
+    InternalCopy(other.m_ptr);
+    return *this;
+  }
+
+  template <typename T>
+  ComPtr& operator=(ComPtr<T>&& other) noexcept {
+    InternalMove(other);
+    return *this;
+  }
+
+  void Swap(ComPtr& other) noexcept {
+    Interface* temp = m_ptr;
+    m_ptr = other.m_ptr;
+    other.m_ptr = temp;
+  }
+
+  explicit operator bool() const noexcept { return nullptr != m_ptr; }
+
+  void Reset() noexcept { InternalRelease(); }
+
+  Interface* Get() const noexcept { return m_ptr; }
+
+  Interface* Detach() noexcept {
+    Interface* temp = m_ptr;
+    m_ptr = nullptr;
+    return temp;
+  }
+
+  void Copy(Interface* other) noexcept { InternalCopy(other); }
+
+  void Attach(Interface* other) noexcept {
+    InternalRelease();
+    m_ptr = other;
+  }
+
+  Interface** GetAddressOf() noexcept {
+    assert(m_ptr == nullptr);
+    return &m_ptr;
+  }
+
+  void CopyTo(Interface** other) const noexcept {
+    InternalAddRef();
+    *other = m_ptr;
+  }
+
+  template <typename T>
+  ComPtr<T> As() const noexcept {
+    ComPtr<T> temp;
+    m_ptr->QueryInterface(temp.GetAddressOf());
+    return temp;
+  }
+
+  RemoveAddRefRelease<Interface>* operator->() const noexcept {
+    return static_cast<RemoveAddRefRelease<Interface>*>(m_ptr);
+  }
+
+ private:
+  Interface* m_ptr = nullptr;
+
+  void InternalAddRef() const noexcept {
+    if (m_ptr) {
+      m_ptr->AddRef();
+    }
+  }
+
+  void InternalRelease() noexcept {
+    Interface* temp = m_ptr;
+    if (temp) {
+      m_ptr = nullptr;
+      temp->Release();
+    }
+  }
+
+  void InternalCopy(Interface* other) noexcept {
+    if (m_ptr != other) {
+      InternalRelease();
+      m_ptr = other;
+      InternalAddRef();
+    }
+  }
+
+  template <typename T>
+  void InternalMove(ComPtr<T>& other) noexcept {
+    if (m_ptr != other.m_ptr) {
+      InternalRelease();
+      m_ptr = other.m_ptr;
+      other.m_ptr = nullptr;
+    }
+  }
+};
+
+template <typename Interface>
+void swap(
+    ComPtr<Interface>& left,
+    ComPtr<Interface>& right) noexcept {  // NOLINT(build/include_what_you_use)
+  left.Swap(right);
+}
+
+}  // namespace cs
diff --git a/cscore/src/main/native/windows/NetworkListener.cpp b/cscore/src/main/native/windows/NetworkListener.cpp
new file mode 100644
index 0000000..cd29e44
--- /dev/null
+++ b/cscore/src/main/native/windows/NetworkListener.cpp
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkListener.h"
+
+#include <winsock2.h>  // NOLINT(build/include_order)
+
+#include <windows.h>  // NOLINT(build/include_order)
+
+#include <ws2def.h>  // NOLINT(build/include_order)
+
+#include <ws2ipdef.h>  // NOLINT(build/include_order)
+
+#include <iphlpapi.h>  // NOLINT(build/include_order)
+
+#include <netioapi.h>  // NOLINT(build/include_order)
+
+#include "Instance.h"
+#include "Log.h"
+#include "Notifier.h"
+
+#pragma comment(lib, "Iphlpapi.lib")
+
+using namespace cs;
+
+class NetworkListener::Impl {
+ public:
+  Impl(wpi::Logger& logger, Notifier& notifier)
+      : m_logger(logger), m_notifier(notifier) {}
+  wpi::Logger& m_logger;
+  Notifier& m_notifier;
+  HANDLE eventHandle = 0;
+};
+
+// Static Callback function for NotifyIpInterfaceChange API.
+static void WINAPI OnInterfaceChange(PVOID callerContext,
+                                     PMIB_IPINTERFACE_ROW row,
+                                     MIB_NOTIFICATION_TYPE notificationType) {
+  Notifier* notifier = reinterpret_cast<Notifier*>(callerContext);
+  notifier->NotifyNetworkInterfacesChanged();
+}
+
+NetworkListener::NetworkListener(wpi::Logger& logger, Notifier& notifier)
+    : m_impl(std::make_unique<Impl>(logger, notifier)) {}
+
+NetworkListener::~NetworkListener() { Stop(); }
+
+void NetworkListener::Start() {
+  NotifyIpInterfaceChange(AF_INET, OnInterfaceChange, &m_impl->m_notifier, true,
+                          &m_impl->eventHandle);
+}
+
+void NetworkListener::Stop() {
+  if (m_impl->eventHandle) {
+    CancelMibChangeNotify2(m_impl->eventHandle);
+  }
+}
diff --git a/cscore/src/main/native/windows/NetworkUtil.cpp b/cscore/src/main/native/windows/NetworkUtil.cpp
new file mode 100644
index 0000000..151ba79
--- /dev/null
+++ b/cscore/src/main/native/windows/NetworkUtil.cpp
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <uv.h>
+
+#include "cscore_cpp.h"
+
+#pragma comment(lib, "Ws2_32.lib")
+
+namespace cs {
+
+std::vector<std::string> GetNetworkInterfaces() {
+  uv_interface_address_t* adrs;
+  int counts = 0;
+
+  std::vector<std::string> addresses{};
+
+  uv_interface_addresses(&adrs, &counts);
+
+  char ip[50];
+
+  for (int i = 0; i < counts; i++) {
+    if (adrs[i].is_internal) continue;
+    InetNtop(PF_INET, &(adrs[i].netmask.netmask4.sin_addr.s_addr), ip,
+             sizeof(ip) - 1);
+    ip[49] = '\0';
+    InetNtop(PF_INET, &(adrs[i].address.address4.sin_addr.s_addr), ip,
+             sizeof(ip) - 1);
+    ip[49] = '\0';
+    addresses.emplace_back(std::string{ip});
+  }
+
+  uv_free_interface_addresses(adrs, counts);
+
+  return addresses;
+}
+
+}  // namespace cs
diff --git a/cscore/src/main/native/windows/UsbCameraImpl.cpp b/cscore/src/main/native/windows/UsbCameraImpl.cpp
new file mode 100644
index 0000000..69c1fcb
--- /dev/null
+++ b/cscore/src/main/native/windows/UsbCameraImpl.cpp
@@ -0,0 +1,1077 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#define _WINSOCKAPI_
+#include "UsbCameraImpl.h"
+
+#include <ks.h>
+#include <ksmedia.h>
+#include <mfapi.h>
+#include <mferror.h>
+#include <mfidl.h>
+#include <shlwapi.h>
+#include <windowsx.h>
+
+#include <cmath>
+#include <codecvt>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <Dbt.h>
+#include <Dshow.h>
+#include <Windows.h>
+#include <opencv2/core/core.hpp>
+#include <opencv2/highgui/highgui.hpp>
+#include <opencv2/imgproc/imgproc.hpp>
+#include <wpi/MemAlloc.h>
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+#include <wpi/timestamp.h>
+
+#include "COMCreators.h"
+#include "ComPtr.h"
+#include "Handle.h"
+#include "Instance.h"
+#include "JpegUtil.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "PropertyImpl.h"
+#include "Telemetry.h"
+#include "WindowsMessagePump.h"
+#include "c_util.h"
+#include "cscore_cpp.h"
+
+#pragma comment(lib, "Mfplat.lib")
+#pragma comment(lib, "Mf.lib")
+#pragma comment(lib, "mfuuid.lib")
+#pragma comment(lib, "Ole32.lib")
+#pragma comment(lib, "User32.lib")
+#pragma comment(lib, "Mfreadwrite.lib")
+#pragma comment(lib, "Shlwapi.lib")
+
+#pragma warning(disable : 4996 4018 26451)
+
+static constexpr int NewImageMessage = 0x0400 + 4488;
+static constexpr int SetCameraMessage = 0x0400 + 254;
+static constexpr int WaitForStartupMessage = 0x0400 + 294;
+static constexpr int PumpReadyMessage = 0x0400 + 330;
+
+static constexpr char const* kPropWbValue = "WhiteBalance";
+static constexpr char const* kPropExValue = "Exposure";
+static constexpr char const* kPropBrValue = "Brightness";
+static constexpr char const* kPropConnectVerbose = "connect_verbose";
+
+static constexpr unsigned kPropConnectVerboseId = 0;
+
+using namespace cs;
+
+namespace cs {
+
+UsbCameraImpl::UsbCameraImpl(const wpi::Twine& name, wpi::Logger& logger,
+                             Notifier& notifier, Telemetry& telemetry,
+                             const wpi::Twine& path)
+    : SourceImpl{name, logger, notifier, telemetry}, m_path{path.str()} {
+  std::wstring_convert<std::codecvt_utf8<wchar_t>> utf8_conv;
+  m_widePath = utf8_conv.from_bytes(m_path.c_str());
+  m_deviceId = -1;
+  StartMessagePump();
+}
+
+UsbCameraImpl::UsbCameraImpl(const wpi::Twine& name, wpi::Logger& logger,
+                             Notifier& notifier, Telemetry& telemetry,
+                             int deviceId)
+    : SourceImpl{name, logger, notifier, telemetry}, m_deviceId(deviceId) {
+  StartMessagePump();
+}
+
+UsbCameraImpl::~UsbCameraImpl() { m_messagePump = nullptr; }
+
+void UsbCameraImpl::SetProperty(int property, int value, CS_Status* status) {
+  Message msg{Message::kCmdSetProperty};
+  msg.data[0] = property;
+  msg.data[1] = value;
+  auto result =
+      m_messagePump->SendWindowMessage<CS_Status, Message::Kind, Message*>(
+          SetCameraMessage, msg.kind, &msg);
+  *status = result;
+}
+void UsbCameraImpl::SetStringProperty(int property, const wpi::Twine& value,
+                                      CS_Status* status) {
+  Message msg{Message::kCmdSetPropertyStr};
+  msg.data[0] = property;
+  msg.dataStr = value.str();
+  auto result =
+      m_messagePump->SendWindowMessage<CS_Status, Message::Kind, Message*>(
+          SetCameraMessage, msg.kind, &msg);
+  *status = result;
+}
+
+// Standard common camera properties
+void UsbCameraImpl::SetBrightness(int brightness, CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropBrValue), brightness, status);
+}
+int UsbCameraImpl::GetBrightness(CS_Status* status) const {
+  return GetProperty(GetPropertyIndex(kPropBrValue), status);
+}
+void UsbCameraImpl::SetWhiteBalanceAuto(CS_Status* status) {
+  // TODO
+}
+void UsbCameraImpl::SetWhiteBalanceHoldCurrent(CS_Status* status) {
+  // TODO
+}
+void UsbCameraImpl::SetWhiteBalanceManual(int value, CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropWbValue), value, status);
+}
+void UsbCameraImpl::SetExposureAuto(CS_Status* status) {
+  // TODO
+}
+void UsbCameraImpl::SetExposureHoldCurrent(CS_Status* status) {
+  // TODO
+}
+void UsbCameraImpl::SetExposureManual(int value, CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropExValue), value, status);
+}
+
+bool UsbCameraImpl::SetVideoMode(const VideoMode& mode, CS_Status* status) {
+  if (mode.pixelFormat == VideoMode::kUnknown) {
+    *status = CS_UNSUPPORTED_MODE;
+    return false;
+  }
+
+  Message msg{Message::kCmdSetMode};
+  msg.data[0] = mode.pixelFormat;
+  msg.data[1] = mode.width;
+  msg.data[2] = mode.height;
+  msg.data[3] = mode.fps;
+  auto result =
+      m_messagePump->SendWindowMessage<CS_Status, Message::Kind, Message*>(
+          SetCameraMessage, msg.kind, &msg);
+  *status = result;
+  return result == 0;
+}
+
+bool UsbCameraImpl::SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                                   CS_Status* status) {
+  if (pixelFormat == VideoMode::kUnknown) {
+    *status = CS_UNSUPPORTED_MODE;
+    return false;
+  }
+  Message msg{Message::kCmdSetPixelFormat};
+  msg.data[0] = pixelFormat;
+  auto result =
+      m_messagePump->SendWindowMessage<CS_Status, Message::Kind, Message*>(
+          SetCameraMessage, msg.kind, &msg);
+  *status = result;
+  return result == 0;
+}
+bool UsbCameraImpl::SetResolution(int width, int height, CS_Status* status) {
+  Message msg{Message::kCmdSetResolution};
+  msg.data[0] = width;
+  msg.data[1] = height;
+  auto result =
+      m_messagePump->SendWindowMessage<CS_Status, Message::Kind, Message*>(
+          SetCameraMessage, msg.kind, &msg);
+  *status = result;
+  return result == 0;
+}
+bool UsbCameraImpl::SetFPS(int fps, CS_Status* status) {
+  Message msg{Message::kCmdSetFPS};
+  msg.data[0] = fps;
+  auto result =
+      m_messagePump->SendWindowMessage<CS_Status, Message::Kind, Message*>(
+          SetCameraMessage, msg.kind, &msg);
+  *status = result;
+  return result == 0;
+}
+
+void UsbCameraImpl::NumSinksChanged() {
+  m_messagePump->PostWindowMessage<Message::Kind, Message*>(
+      SetCameraMessage, Message::kNumSinksChanged, nullptr);
+}
+void UsbCameraImpl::NumSinksEnabledChanged() {
+  m_messagePump->PostWindowMessage<Message::Kind, Message*>(
+      SetCameraMessage, Message::kNumSinksEnabledChanged, nullptr);
+}
+
+void UsbCameraImpl::StartMessagePump() {
+  m_messagePump = std::make_unique<WindowsMessagePump>(
+      [this](HWND hwnd, UINT uiMsg, WPARAM wParam, LPARAM lParam) {
+        return this->PumpMain(hwnd, uiMsg, wParam, lParam);
+      });
+}
+
+void UsbCameraImpl::Start() {
+  m_messagePump->PostWindowMessage(PumpReadyMessage, nullptr, nullptr);
+}
+
+void UsbCameraImpl::PostRequestNewFrame() {
+  m_messagePump->PostWindowMessage(NewImageMessage, nullptr, nullptr);
+}
+
+bool UsbCameraImpl::CheckDeviceChange(WPARAM wParam, DEV_BROADCAST_HDR* pHdr,
+                                      bool* connected) {
+  DEV_BROADCAST_DEVICEINTERFACE* pDi = NULL;
+
+  *connected = false;
+
+  if (pHdr == NULL) {
+    return false;
+  }
+  if (pHdr->dbch_devicetype != DBT_DEVTYP_DEVICEINTERFACE) {
+    return false;
+  }
+
+  // Compare the device name with the symbolic link.
+
+  pDi = reinterpret_cast<DEV_BROADCAST_DEVICEINTERFACE*>(pHdr);
+
+  if (_stricmp(m_path.c_str(), pDi->dbcc_name) == 0) {
+    if (wParam == DBT_DEVICEARRIVAL) {
+      *connected = true;
+      return true;
+    } else if (wParam == DBT_DEVICEREMOVECOMPLETE) {
+      *connected = false;
+      return true;
+    }
+  }
+  return false;
+}
+
+void UsbCameraImpl::DeviceDisconnect() {
+  if (m_connectVerbose) SINFO("Disconnected from " << m_path);
+  m_sourceReader.Reset();
+  m_mediaSource.Reset();
+  if (m_imageCallback) {
+    m_imageCallback->InvalidateCapture();
+  }
+  m_imageCallback.Reset();
+  m_streaming = false;
+  SetConnected(false);
+}
+
+static bool IsPercentageProperty(wpi::StringRef name) {
+  if (name.startswith("raw_")) name = name.substr(4);
+  return name == "Brightness" || name == "Contrast" || name == "Saturation" ||
+         name == "Hue" || name == "Sharpness" || name == "Gain" ||
+         name == "Exposure";
+}
+
+void UsbCameraImpl::ProcessFrame(IMFSample* videoSample,
+                                 const VideoMode& mode) {
+  if (!videoSample) return;
+
+  ComPtr<IMFMediaBuffer> buf;
+
+  if (!SUCCEEDED(videoSample->ConvertToContiguousBuffer(buf.GetAddressOf()))) {
+    DWORD bcnt = 0;
+    if (!SUCCEEDED(videoSample->GetBufferCount(&bcnt))) return;
+    if (bcnt == 0) return;
+    if (!SUCCEEDED(videoSample->GetBufferByIndex(0, buf.GetAddressOf())))
+      return;
+  }
+
+  bool lock2d = false;
+  BYTE* ptr = NULL;
+  LONG pitch = 0;
+  DWORD maxsize = 0, cursize = 0;
+
+  // "For 2-D buffers, the Lock2D method is more efficient than the Lock
+  // method" see IMFMediaBuffer::Lock method documentation:
+  // https://msdn.microsoft.com/en-us/library/windows/desktop/bb970366(v=vs.85).aspx
+  ComPtr<IMF2DBuffer> buffer2d;
+  DWORD memLength2d = 0;
+  if (true) {
+    buffer2d = buf.As<IMF2DBuffer>();
+    if (buffer2d) {
+      buffer2d->GetContiguousLength(&memLength2d);
+      if (SUCCEEDED(buffer2d->Lock2D(&ptr, &pitch))) {
+        lock2d = true;
+      }
+    }
+  }
+  if (ptr == NULL) {
+    if (!SUCCEEDED(buf->Lock(&ptr, &maxsize, &cursize))) {
+      return;
+    }
+  }
+  if (!ptr) return;
+
+  cv::Mat tmpMat;
+  std::unique_ptr<Image> dest;
+  bool doFinalSet = true;
+
+  switch (mode.pixelFormat) {
+    case cs::VideoMode::PixelFormat::kMJPEG: {
+      // Special case
+      PutFrame(VideoMode::kMJPEG, mode.width, mode.height,
+               wpi::StringRef(reinterpret_cast<char*>(ptr), cursize),
+               wpi::Now());
+      doFinalSet = false;
+      break;
+    }
+    case cs::VideoMode::PixelFormat::kGray:
+      tmpMat = cv::Mat(mode.height, mode.width, CV_8UC1, ptr, pitch);
+      dest = AllocImage(VideoMode::kGray, tmpMat.cols, tmpMat.rows,
+                        tmpMat.total());
+      tmpMat.copyTo(dest->AsMat());
+      break;
+    case cs::VideoMode::PixelFormat::kBGR:
+      tmpMat = cv::Mat(mode.height, mode.width, CV_8UC3, ptr, pitch);
+      dest = AllocImage(VideoMode::kBGR, tmpMat.cols, tmpMat.rows,
+                        tmpMat.total() * 3);
+      tmpMat.copyTo(dest->AsMat());
+      break;
+    case cs::VideoMode::PixelFormat::kYUYV:
+      tmpMat = cv::Mat(mode.height, mode.width, CV_8UC2, ptr, pitch);
+      dest = AllocImage(VideoMode::kYUYV, tmpMat.cols, tmpMat.rows,
+                        tmpMat.total() * 2);
+      tmpMat.copyTo(dest->AsMat());
+      break;
+    default:
+      doFinalSet = false;
+      break;
+  }
+
+  if (doFinalSet) {
+    PutFrame(std::move(dest), wpi::Now());
+  }
+
+  if (lock2d)
+    buffer2d->Unlock2D();
+  else
+    buf->Unlock();
+}
+
+LRESULT UsbCameraImpl::PumpMain(HWND hwnd, UINT uiMsg, WPARAM wParam,
+                                LPARAM lParam) {
+  switch (uiMsg) {
+    case WM_CLOSE:
+      m_sourceReader.Reset();
+      m_mediaSource.Reset();
+      if (m_imageCallback) {
+        m_imageCallback->InvalidateCapture();
+      }
+      m_imageCallback.Reset();
+      break;
+    case PumpReadyMessage:
+      // Pump Created and ready to go
+      DeviceConnect();
+      break;
+    case WaitForStartupMessage:
+      DeviceConnect();
+      return CS_OK;
+    case WM_DEVICECHANGE: {
+      // Device potentially changed
+      PDEV_BROADCAST_HDR parameter =
+          reinterpret_cast<PDEV_BROADCAST_HDR>(lParam);
+      // Check if we're waiting on a device path, and this is a connection
+      if (m_path.empty() && wParam == DBT_DEVICEARRIVAL &&
+          parameter->dbch_devicetype == DBT_DEVTYP_DEVICEINTERFACE) {
+        // If path is empty, we attempted to connect with a device ID. Enumerate
+        // and check
+        CS_Status status = 0;
+        auto devices = cs::EnumerateUsbCameras(&status);
+        if (devices.size() > m_deviceId) {
+          // If has device ID, use the device ID from the event
+          // because of windows bug
+          auto&& device = devices[m_deviceId];
+          DEV_BROADCAST_DEVICEINTERFACE* pDi =
+              reinterpret_cast<DEV_BROADCAST_DEVICEINTERFACE*>(parameter);
+          m_path = pDi->dbcc_name;
+          std::wstring_convert<std::codecvt_utf8<wchar_t>> utf8_conv;
+          m_widePath = utf8_conv.from_bytes(m_path.c_str());
+        } else {
+          // This device not found
+          break;
+        }
+      }
+      bool connected = false;
+      if (CheckDeviceChange(wParam, parameter, &connected)) {
+        if (connected) {
+          DeviceConnect();
+        } else {
+          // Disconnected
+          DeviceDisconnect();
+        }
+      }
+    } break;
+    case NewImageMessage: {  // New image
+      if (m_streaming && m_sourceReader) {
+        m_sourceReader->ReadSample(MF_SOURCE_READER_FIRST_VIDEO_STREAM, 0, NULL,
+                                   NULL, NULL, NULL);
+      }
+      break;
+    }
+    case SetCameraMessage: {
+      {
+        Message* msg = reinterpret_cast<Message*>(lParam);
+        Message::Kind msgKind = static_cast<Message::Kind>(wParam);
+        std::unique_lock lock(m_mutex);
+        auto retVal = DeviceProcessCommand(lock, msgKind, msg);
+        return retVal;
+      }
+      break;
+    }
+  }
+  return 0l;
+}
+
+static cs::VideoMode::PixelFormat GetFromGUID(const GUID& guid) {
+  // Compare GUID to one of the supported ones
+  if (IsEqualGUID(guid, MFVideoFormat_NV12)) {
+    // GrayScale
+    return cs::VideoMode::PixelFormat::kGray;
+  } else if (IsEqualGUID(guid, MFVideoFormat_YUY2)) {
+    return cs::VideoMode::PixelFormat::kYUYV;
+  } else if (IsEqualGUID(guid, MFVideoFormat_RGB24)) {
+    return cs::VideoMode::PixelFormat::kBGR;
+  } else if (IsEqualGUID(guid, MFVideoFormat_MJPG)) {
+    return cs::VideoMode::PixelFormat::kMJPEG;
+  } else if (IsEqualGUID(guid, MFVideoFormat_RGB565)) {
+    return cs::VideoMode::PixelFormat::kRGB565;
+  } else {
+    return cs::VideoMode::PixelFormat::kUnknown;
+  }
+}
+
+bool UsbCameraImpl::DeviceConnect() {
+  if (m_mediaSource && m_sourceReader) return true;
+
+  if (m_connectVerbose) SINFO("Connecting to USB camera on " << m_path);
+
+  SDEBUG3("opening device");
+
+  const wchar_t* path = m_widePath.c_str();
+  m_mediaSource = CreateVideoCaptureDevice(path);
+
+  if (!m_mediaSource) return false;
+  m_imageCallback = CreateSourceReaderCB(shared_from_this(), m_mode);
+
+  m_sourceReader =
+      CreateSourceReader(m_mediaSource.Get(), m_imageCallback.Get());
+
+  if (!m_sourceReader) {
+    m_mediaSource.Reset();
+    return false;
+  }
+
+  CS_Status st = 0;
+  auto devices = EnumerateUsbCameras(&st);
+
+  for (auto&& device : devices) {
+    if (device.path == m_path) {
+      SetDescription(device.name);
+    }
+  }
+
+  if (!m_properties_cached) {
+    SDEBUG3("caching properties");
+    DeviceCacheProperties();
+    DeviceCacheVideoModes();
+    DeviceCacheMode();
+    m_properties_cached = true;
+  } else {
+    SDEBUG3("restoring video mode");
+    DeviceSetMode();
+  }
+
+  SetConnected(true);
+
+  // Turn off streaming if not enabled, and turn it on if enabled
+  if (IsEnabled()) {
+    DeviceStreamOn();
+  }
+  return true;
+}
+
+std::unique_ptr<PropertyImpl> UsbCameraImpl::CreateEmptyProperty(
+    const wpi::Twine& name) const {
+  return nullptr;
+}
+
+bool UsbCameraImpl::CacheProperties(CS_Status* status) const {
+  // Wait for Camera Thread to be started
+  auto result = m_messagePump->SendWindowMessage<CS_Status>(
+      WaitForStartupMessage, nullptr, nullptr);
+  *status = result;
+  if (*status != CS_OK) return false;
+  if (!m_properties_cached) {
+    *status = CS_SOURCE_IS_DISCONNECTED;
+    return false;
+  }
+  return true;
+}
+
+template <typename TagProperty, typename IAM>
+void UsbCameraImpl::DeviceAddProperty(const wpi::Twine& name_, TagProperty tag,
+                                      IAM* pProcAmp) {
+  // First see if properties exist
+  bool isValid = false;
+  auto property = std::make_unique<UsbCameraProperty>(name_, tag, false,
+                                                      pProcAmp, &isValid);
+  if (isValid) {
+    DeviceCacheProperty(std::move(property), m_sourceReader.Get());
+  }
+}
+
+template void UsbCameraImpl::DeviceAddProperty(const wpi::Twine& name_,
+                                               tagVideoProcAmpProperty tag,
+                                               IAMVideoProcAmp* pProcAmp);
+
+template void UsbCameraImpl::DeviceAddProperty(const wpi::Twine& name_,
+                                               tagCameraControlProperty tag,
+                                               IAMCameraControl* pProcAmp);
+
+#define CREATEPROPERTY(val) \
+  DeviceAddProperty(#val, VideoProcAmp_##val, pProcAmp);
+
+#define CREATECONTROLPROPERTY(val) \
+  DeviceAddProperty(#val, CameraControl_##val, pCamControl);
+
+void UsbCameraImpl::DeviceCacheProperties() {
+  if (!m_sourceReader) return;
+
+  IAMVideoProcAmp* pProcAmp = NULL;
+
+  if (SUCCEEDED(m_sourceReader->GetServiceForStream(
+          (DWORD)MF_SOURCE_READER_MEDIASOURCE, GUID_NULL,
+          IID_PPV_ARGS(&pProcAmp)))) {
+    CREATEPROPERTY(Brightness)
+    CREATEPROPERTY(Contrast)
+    CREATEPROPERTY(Hue)
+    CREATEPROPERTY(Saturation)
+    CREATEPROPERTY(Sharpness)
+    CREATEPROPERTY(Gamma)
+    CREATEPROPERTY(ColorEnable)
+    CREATEPROPERTY(WhiteBalance)
+    CREATEPROPERTY(BacklightCompensation)
+    CREATEPROPERTY(Gain)
+    pProcAmp->Release();
+  }
+
+  IAMCameraControl* pCamControl = NULL;
+
+  if (SUCCEEDED(m_sourceReader->GetServiceForStream(
+          (DWORD)MF_SOURCE_READER_MEDIASOURCE, GUID_NULL,
+          IID_PPV_ARGS(&pCamControl)))) {
+    CREATECONTROLPROPERTY(Pan)
+    CREATECONTROLPROPERTY(Tilt)
+    CREATECONTROLPROPERTY(Roll)
+    CREATECONTROLPROPERTY(Zoom)
+    CREATECONTROLPROPERTY(Exposure)
+    CREATECONTROLPROPERTY(Iris)
+    CREATECONTROLPROPERTY(Focus)
+    pCamControl->Release();
+  }
+}
+
+int UsbCameraImpl::RawToPercentage(const UsbCameraProperty& rawProp,
+                                   int rawValue) {
+  return 100.0 * (rawValue - rawProp.minimum) /
+         (rawProp.maximum - rawProp.minimum);
+}
+
+int UsbCameraImpl::PercentageToRaw(const UsbCameraProperty& rawProp,
+                                   int percentValue) {
+  return rawProp.minimum +
+         (rawProp.maximum - rawProp.minimum) * (percentValue / 100.0);
+}
+
+void UsbCameraImpl::DeviceCacheProperty(
+    std::unique_ptr<UsbCameraProperty> rawProp, IMFSourceReader* pProcAmp) {
+  // For percentage properties, we want to cache both the raw and the
+  // percentage versions.  This function is always called with prop being
+  // the raw property (as it's coming from the camera) so if required, we need
+  // to rename this one as well as create/cache the percentage version.
+  //
+  // This is complicated by the fact that either the percentage version or the
+  // the raw version may have been set previously.  If both were previously set,
+  // the raw version wins.
+  std::unique_ptr<UsbCameraProperty> perProp;
+  if (IsPercentageProperty(rawProp->name)) {
+    perProp =
+        std::make_unique<UsbCameraProperty>(rawProp->name, 0, *rawProp, 0, 0);
+    rawProp->name = "raw_" + perProp->name;
+  }
+
+  std::unique_lock lock(m_mutex);
+  int* rawIndex = &m_properties[rawProp->name];
+  bool newRaw = *rawIndex == 0;
+  UsbCameraProperty* oldRawProp =
+      newRaw ? nullptr
+             : static_cast<UsbCameraProperty*>(GetProperty(*rawIndex));
+
+  int* perIndex = perProp ? &m_properties[perProp->name] : nullptr;
+  bool newPer = !perIndex || *perIndex == 0;
+  UsbCameraProperty* oldPerProp =
+      newPer ? nullptr
+             : static_cast<UsbCameraProperty*>(GetProperty(*perIndex));
+
+  if (oldRawProp && oldRawProp->valueSet) {
+    // Merge existing raw setting and set percentage from it
+    rawProp->SetValue(oldRawProp->value);
+    rawProp->valueStr = std::move(oldRawProp->valueStr);
+
+    if (perProp) {
+      perProp->SetValue(RawToPercentage(*rawProp, rawProp->value));
+      perProp->valueStr = rawProp->valueStr;  // copy
+    }
+  } else if (oldPerProp && oldPerProp->valueSet) {
+    // Merge existing percentage setting and set raw from it
+    perProp->SetValue(oldPerProp->value);
+    perProp->valueStr = std::move(oldPerProp->valueStr);
+
+    rawProp->SetValue(PercentageToRaw(*rawProp, perProp->value));
+    rawProp->valueStr = perProp->valueStr;  // copy
+  } else {
+    // Read current raw value and set percentage from it
+    if (!rawProp->DeviceGet(lock, pProcAmp))
+      SWARNING("failed to get property " << rawProp->name);
+
+    if (perProp) {
+      perProp->SetValue(RawToPercentage(*rawProp, rawProp->value));
+      perProp->valueStr = rawProp->valueStr;  // copy
+    }
+  }
+
+  // Set value on device if user-configured
+  if (rawProp->valueSet) {
+    if (!rawProp->DeviceSet(lock, pProcAmp))
+      SWARNING("failed to set property " << rawProp->name);
+  }
+
+  // Update pointers since we released the lock
+  rawIndex = &m_properties[rawProp->name];
+  perIndex = perProp ? &m_properties[perProp->name] : nullptr;
+
+  // Get pointers before we move the std::unique_ptr values
+  auto rawPropPtr = rawProp.get();
+  auto perPropPtr = perProp.get();
+
+  if (newRaw) {
+    // create a new index
+    *rawIndex = m_propertyData.size() + 1;
+    m_propertyData.emplace_back(std::move(rawProp));
+  } else {
+    // update
+    m_propertyData[*rawIndex - 1] = std::move(rawProp);
+  }
+
+  // Finish setting up percentage property
+  if (perProp) {
+    perProp->propPair = *rawIndex;
+    perProp->defaultValue =
+        RawToPercentage(*rawPropPtr, rawPropPtr->defaultValue);
+
+    if (newPer) {
+      // create a new index
+      *perIndex = m_propertyData.size() + 1;
+      m_propertyData.emplace_back(std::move(perProp));
+    } else if (perIndex) {
+      // update
+      m_propertyData[*perIndex - 1] = std::move(perProp);
+    }
+
+    // Tell raw property where to find percentage property
+    rawPropPtr->propPair = *perIndex;
+  }
+
+  NotifyPropertyCreated(*rawIndex, *rawPropPtr);
+  if (perPropPtr && perIndex) NotifyPropertyCreated(*perIndex, *perPropPtr);
+}
+
+CS_StatusValue UsbCameraImpl::DeviceProcessCommand(
+    std::unique_lock<wpi::mutex>& lock, Message::Kind msgKind,
+    const Message* msg) {
+  if (msgKind == Message::kCmdSetMode ||
+      msgKind == Message::kCmdSetPixelFormat ||
+      msgKind == Message::kCmdSetResolution || msgKind == Message::kCmdSetFPS) {
+    return DeviceCmdSetMode(lock, *msg);
+  } else if (msgKind == Message::kCmdSetProperty ||
+             msgKind == Message::kCmdSetPropertyStr) {
+    return DeviceCmdSetProperty(lock, *msg);
+    return CS_OK;
+  } else if (msgKind == Message::kNumSinksChanged ||
+             msgKind == Message::kNumSinksEnabledChanged) {
+    // Turn On Streams
+    if (!IsEnabled()) {
+      DeviceStreamOff();
+    } else if (!m_streaming && IsEnabled()) {
+      DeviceStreamOn();
+    }
+    return CS_OK;
+  } else {
+    return CS_OK;
+  }
+}
+
+CS_StatusValue UsbCameraImpl::DeviceCmdSetProperty(
+    std::unique_lock<wpi::mutex>& lock, const Message& msg) {
+  bool setString = (msg.kind == Message::kCmdSetPropertyStr);
+  int property = msg.data[0];
+  int value = msg.data[1];
+  wpi::StringRef valueStr = msg.dataStr;
+
+  // Look up
+  auto prop = static_cast<UsbCameraProperty*>(GetProperty(property));
+  if (!prop) return CS_INVALID_PROPERTY;
+
+  // If setting before we get, guess initial type based on set
+  if (prop->propKind == CS_PROP_NONE) {
+    if (setString)
+      prop->propKind = CS_PROP_STRING;
+    else
+      prop->propKind = CS_PROP_INTEGER;
+  }
+
+  // Check kind match
+  if ((setString && prop->propKind != CS_PROP_STRING) ||
+      (!setString && (prop->propKind &
+                      (CS_PROP_BOOLEAN | CS_PROP_INTEGER | CS_PROP_ENUM)) == 0))
+    return CS_WRONG_PROPERTY_TYPE;
+
+  // Handle percentage property
+  int percentageProperty = prop->propPair;
+  int percentageValue = value;
+  if (percentageProperty != 0) {
+    if (prop->percentage) {
+      std::swap(percentageProperty, property);
+      prop = static_cast<UsbCameraProperty*>(GetProperty(property));
+      value = PercentageToRaw(*prop, percentageValue);
+    } else {
+      percentageValue = RawToPercentage(*prop, value);
+    }
+  }
+
+  // Actually set the new value on the device (if possible)
+  if (!prop->device) {
+    if (prop->id == kPropConnectVerboseId) m_connectVerbose = value;
+  } else {
+    if (!prop->DeviceSet(lock, m_sourceReader.Get())) {
+      return CS_PROPERTY_WRITE_FAILED;
+    }
+  }
+
+  // Cache the set values
+  UpdatePropertyValue(property, setString, value, valueStr);
+  if (percentageProperty != 0)
+    UpdatePropertyValue(percentageProperty, setString, percentageValue,
+                        valueStr);
+
+  return CS_OK;
+}
+
+ComPtr<IMFMediaType> UsbCameraImpl::DeviceCheckModeValid(
+    const VideoMode& toCheck) {
+  // Find the matching mode
+  auto match =
+      std::find_if(m_windowsVideoModes.begin(), m_windowsVideoModes.end(),
+                   [&](std::pair<VideoMode, ComPtr<IMFMediaType>>& input) {
+                     return input.first == toCheck;
+                   });
+
+  if (match == m_windowsVideoModes.end()) {
+    return nullptr;
+  }
+  return match->second;
+}
+
+CS_StatusValue UsbCameraImpl::DeviceCmdSetMode(
+    std::unique_lock<wpi::mutex>& lock, const Message& msg) {
+  VideoMode newMode;
+  if (msg.kind == Message::kCmdSetMode) {
+    newMode.pixelFormat = msg.data[0];
+    newMode.width = msg.data[1];
+    newMode.height = msg.data[2];
+    newMode.fps = msg.data[3];
+  } else if (msg.kind == Message::kCmdSetPixelFormat) {
+    newMode = m_mode;
+    newMode.pixelFormat = msg.data[0];
+  } else if (msg.kind == Message::kCmdSetResolution) {
+    newMode = m_mode;
+    newMode.width = msg.data[0];
+    newMode.height = msg.data[1];
+  } else if (msg.kind == Message::kCmdSetFPS) {
+    newMode = m_mode;
+    newMode.fps = msg.data[0];
+  }
+
+  // Check if the device is not connected, if not just apply and leave
+  if (!m_properties_cached) {
+    m_mode = newMode;
+    return CS_OK;
+  }
+
+  // If the pixel format or resolution changed, we need to disconnect and
+  // reconnect
+  if (newMode != m_mode) {
+    // First check if the new mode is valid
+    auto newModeType = DeviceCheckModeValid(newMode);
+    if (!newModeType) {
+      return CS_UNSUPPORTED_MODE;
+    }
+
+    m_currentMode = std::move(newModeType);
+    m_mode = newMode;
+#pragma warning(push)
+#pragma warning(disable : 26110)
+    lock.unlock();
+#pragma warning(pop)
+    if (m_sourceReader) {
+      DeviceDisconnect();
+      DeviceConnect();
+    }
+    m_notifier.NotifySourceVideoMode(*this, newMode);
+    lock.lock();
+  }
+
+  return CS_OK;
+}
+
+bool UsbCameraImpl::DeviceStreamOn() {
+  if (m_streaming) return false;
+  if (!m_deviceValid) return false;
+  m_streaming = true;
+  m_sourceReader->ReadSample(MF_SOURCE_READER_FIRST_VIDEO_STREAM, 0, NULL, NULL,
+                             NULL, NULL);
+  return true;
+}
+
+bool UsbCameraImpl::DeviceStreamOff() {
+  m_streaming = false;
+  return true;
+}
+
+void UsbCameraImpl::DeviceCacheMode() {
+  if (!m_sourceReader) return;
+
+  if (m_windowsVideoModes.size() == 0) return;
+
+  if (!m_currentMode) {
+    // First, see if our set mode is valid
+    m_currentMode = DeviceCheckModeValid(m_mode);
+    if (!m_currentMode) {
+      if (FAILED(m_sourceReader->GetCurrentMediaType(
+              MF_SOURCE_READER_FIRST_VIDEO_STREAM,
+              m_currentMode.GetAddressOf()))) {
+        return;
+      }
+      // Find cached version
+      DWORD compare = MF_MEDIATYPE_EQUAL_MAJOR_TYPES |
+                      MF_MEDIATYPE_EQUAL_FORMAT_TYPES |
+                      MF_MEDIATYPE_EQUAL_FORMAT_DATA;
+      auto result = std::find_if(
+          m_windowsVideoModes.begin(), m_windowsVideoModes.end(),
+          [this, &compare](std::pair<VideoMode, ComPtr<IMFMediaType>>& input) {
+            return input.second->IsEqual(m_currentMode.Get(), &compare) == S_OK;
+          });
+
+      if (result == m_windowsVideoModes.end()) {
+        // Default mode is not supported. Grab first supported image
+        auto&& firstSupported = m_windowsVideoModes[0];
+        m_currentMode = firstSupported.second;
+        std::scoped_lock lock(m_mutex);
+        m_mode = firstSupported.first;
+      } else {
+        std::scoped_lock lock(m_mutex);
+        m_mode = result->first;
+      }
+    }
+  }
+
+  DeviceSetMode();
+
+  m_notifier.NotifySourceVideoMode(*this, m_mode);
+}
+
+CS_StatusValue UsbCameraImpl::DeviceSetMode() {
+  HRESULT setResult = m_sourceReader->SetCurrentMediaType(
+      MF_SOURCE_READER_FIRST_VIDEO_STREAM, NULL, m_currentMode.Get());
+
+  m_deviceValid = SUCCEEDED(setResult);
+
+  m_imageCallback->SetVideoMode(m_mode);
+
+  switch (setResult) {
+    case S_OK:
+      return CS_OK;
+      break;
+    case MF_E_INVALIDMEDIATYPE:
+      break;
+    case MF_E_INVALIDREQUEST:
+      break;
+    case MF_E_INVALIDSTREAMNUMBER:
+      break;
+    case MF_E_TOPO_CODEC_NOT_FOUND:
+      break;
+  }
+
+  return CS_UNSUPPORTED_MODE;
+}
+
+void UsbCameraImpl::DeviceCacheVideoModes() {
+  if (!m_sourceReader) return;
+
+  std::vector<VideoMode> modes;
+  m_windowsVideoModes.clear();
+
+  bool set = false;
+
+  ComPtr<IMFMediaType> nativeType;
+  int count = 0;
+  while (true) {
+    nativeType.Reset();
+    auto hr = m_sourceReader->GetNativeMediaType(
+        MF_SOURCE_READER_FIRST_VIDEO_STREAM, count, nativeType.GetAddressOf());
+    if (FAILED(hr)) {
+      break;
+    }
+    GUID guid = {0};
+    nativeType->GetGUID(MF_MT_SUBTYPE, &guid);
+
+    auto format = GetFromGUID(guid);
+    if (format == VideoMode::kUnknown) {
+      count++;
+      // Don't put in unknowns
+      continue;
+    }
+    UINT32 width, height;
+    ::MFGetAttributeSize(nativeType.Get(), MF_MT_FRAME_SIZE, &width, &height);
+
+    UINT32 num, dom;
+    ::MFGetAttributeRatio(nativeType.Get(), MF_MT_FRAME_RATE, &num, &dom);
+
+    int fps = 30;
+
+    if (dom != 0) {
+      fps = std::ceil(num / static_cast<double>(dom));
+    }
+
+    VideoMode newMode = {format, static_cast<int>(width),
+                         static_cast<int>(height), fps};
+
+    modes.emplace_back(newMode);
+    m_windowsVideoModes.emplace_back(newMode, nativeType);
+    count++;
+  }
+  {
+    std::scoped_lock lock(m_mutex);
+    m_videoModes.swap(modes);
+  }
+  m_notifier.NotifySource(*this, CS_SOURCE_VIDEOMODES_UPDATED);
+}
+
+std::vector<UsbCameraInfo> EnumerateUsbCameras(CS_Status* status) {
+  std::vector<UsbCameraInfo> retval;
+
+  // Ensure we are initialized by grabbing the message pump
+  // GetMessagePump();
+
+  std::wstring_convert<std::codecvt_utf8<wchar_t>> utf8_conv;
+  ComPtr<IMFAttributes> pAttributes;
+  IMFActivate** ppDevices = nullptr;
+  UINT32 count = 0;
+
+  // Create an attribute store to specify the enumeration parameters.
+  HRESULT hr = MFCreateAttributes(pAttributes.GetAddressOf(), 1);
+  if (FAILED(hr)) {
+    goto done;
+  }
+
+  // Source type: video capture devices
+  hr = pAttributes->SetGUID(MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE,
+                            MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE_VIDCAP_GUID);
+  if (FAILED(hr)) {
+    goto done;
+  }
+
+  // Enumerate devices.
+  hr = MFEnumDeviceSources(pAttributes.Get(), &ppDevices, &count);
+  if (FAILED(hr)) {
+    goto done;
+  }
+
+  if (count == 0) {
+    hr = E_FAIL;
+    goto done;
+  }
+
+  for (UINT32 i = 0; i < count; i++) {
+    UsbCameraInfo info;
+    info.dev = i;
+    WCHAR buf[512];
+    ppDevices[i]->GetString(MF_DEVSOURCE_ATTRIBUTE_FRIENDLY_NAME, buf,
+                            sizeof(buf) / sizeof(WCHAR), NULL);
+    info.name = utf8_conv.to_bytes(buf);
+    ppDevices[i]->GetString(
+        MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE_VIDCAP_SYMBOLIC_LINK, buf,
+        sizeof(buf) / sizeof(WCHAR), NULL);
+    info.path = utf8_conv.to_bytes(buf);
+    retval.emplace_back(std::move(info));
+  }
+
+done:
+  pAttributes.Reset();
+
+  if (ppDevices) {
+    for (DWORD i = 0; i < count; i++) {
+      if (ppDevices[i]) {
+        ppDevices[i]->Release();
+        ppDevices[i] = nullptr;
+      }
+    }
+  }
+
+  CoTaskMemFree(ppDevices);
+  return retval;
+}
+
+CS_Source CreateUsbCameraDev(const wpi::Twine& name, int dev,
+                             CS_Status* status) {
+  // First check if device exists
+  auto devices = cs::EnumerateUsbCameras(status);
+  if (devices.size() > dev) {
+    return CreateUsbCameraPath(name, devices[dev].path, status);
+  }
+  auto& inst = Instance::GetInstance();
+  auto source = std::make_shared<UsbCameraImpl>(
+      name, inst.logger, inst.notifier, inst.telemetry, dev);
+  return inst.CreateSource(CS_SOURCE_USB, source);
+}
+
+CS_Source CreateUsbCameraPath(const wpi::Twine& name, const wpi::Twine& path,
+                              CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  auto source = std::make_shared<UsbCameraImpl>(
+      name, inst.logger, inst.notifier, inst.telemetry, path);
+  return inst.CreateSource(CS_SOURCE_USB, source);
+}
+
+std::string GetUsbCameraPath(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_USB) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return static_cast<UsbCameraImpl&>(*data->source).GetPath();
+}
+
+UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status) {
+  UsbCameraInfo info;
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_USB) {
+    *status = CS_INVALID_HANDLE;
+    return info;
+  }
+
+  info.path = static_cast<UsbCameraImpl&>(*data->source).GetPath();
+  // TODO: dev and name
+  return info;
+}
+
+}  // namespace cs
diff --git a/cscore/src/main/native/windows/UsbCameraImpl.h b/cscore/src/main/native/windows/UsbCameraImpl.h
new file mode 100644
index 0000000..11e07aa
--- /dev/null
+++ b/cscore/src/main/native/windows/UsbCameraImpl.h
@@ -0,0 +1,187 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_USBCAMERAIMPL_H_
+#define CSCORE_USBCAMERAIMPL_H_
+
+#include <mfapi.h>
+#include <mfidl.h>
+#include <mfreadwrite.h>
+
+#include <ks.h>  // NOLINT(build/include_order)
+
+#include <ksmedia.h>  // NOLINT(build/include_order)
+
+#include <atomic>
+#include <memory>
+#include <string>
+#include <thread>
+#include <utility>
+#include <vector>
+
+#include <Dbt.h>
+#include <wpi/STLExtras.h>
+#include <wpi/SmallVector.h>
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+#include <wpi/raw_istream.h>
+#include <wpi/raw_ostream.h>
+
+#include "ComCreators.h"
+#include "ComPtr.h"
+#include "SourceImpl.h"
+#include "UsbCameraProperty.h"
+#include "WindowsMessagePump.h"
+
+namespace cs {
+
+class UsbCameraImpl : public SourceImpl,
+                      public std::enable_shared_from_this<UsbCameraImpl> {
+ public:
+  UsbCameraImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+                Telemetry& telemetry, const wpi::Twine& path);
+  UsbCameraImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+                Telemetry& telemetry, int deviceId);
+  ~UsbCameraImpl() override;
+
+  void Start();
+
+  // Property functions
+  void SetProperty(int property, int value, CS_Status* status) override;
+  void SetStringProperty(int property, const wpi::Twine& value,
+                         CS_Status* status) override;
+
+  // Standard common camera properties
+  void SetBrightness(int brightness, CS_Status* status) override;
+  int GetBrightness(CS_Status* status) const override;
+  void SetWhiteBalanceAuto(CS_Status* status) override;
+  void SetWhiteBalanceHoldCurrent(CS_Status* status) override;
+  void SetWhiteBalanceManual(int value, CS_Status* status) override;
+  void SetExposureAuto(CS_Status* status) override;
+  void SetExposureHoldCurrent(CS_Status* status) override;
+  void SetExposureManual(int value, CS_Status* status) override;
+
+  bool SetVideoMode(const VideoMode& mode, CS_Status* status) override;
+  bool SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                      CS_Status* status) override;
+  bool SetResolution(int width, int height, CS_Status* status) override;
+  bool SetFPS(int fps, CS_Status* status) override;
+
+  void NumSinksChanged() override;
+  void NumSinksEnabledChanged() override;
+
+  void ProcessFrame(IMFSample* sample, const VideoMode& mode);
+  void PostRequestNewFrame();
+
+  std::string GetPath() { return m_path; }
+
+  // Messages passed to/from camera thread
+  struct Message {
+    enum Kind {
+      kNone = 0,
+      kCmdSetMode,
+      kCmdSetPixelFormat,
+      kCmdSetResolution,
+      kCmdSetFPS,
+      kCmdSetProperty,
+      kCmdSetPropertyStr,
+      kNumSinksChanged,         // no response
+      kNumSinksEnabledChanged,  // no response
+      // Responses
+      kOk,
+      kError
+    };
+
+    explicit Message(Kind kind_)
+        : kind(kind_), data{0}, from(std::this_thread::get_id()) {}
+
+    Kind kind;
+    int data[4];
+    std::string dataStr;
+    std::thread::id from;
+  };
+
+ protected:
+  std::unique_ptr<PropertyImpl> CreateEmptyProperty(
+      const wpi::Twine& name) const override;
+
+  // Cache properties.  Immediately successful if properties are already cached.
+  // If they are not, tries to connect to the camera to do so; returns false and
+  // sets status to CS_SOURCE_IS_DISCONNECTED if that too fails.
+  bool CacheProperties(CS_Status* status) const override;
+
+ private:
+  // The camera processing thread
+  void CameraThreadMain();
+
+  LRESULT PumpMain(HWND hwnd, UINT uiMsg, WPARAM wParam, LPARAM lParam);
+
+  bool CheckDeviceChange(WPARAM wParam, DEV_BROADCAST_HDR* pHdr,
+                         bool* connected);
+
+  // Functions used by CameraThreadMain()
+  void DeviceDisconnect();
+  bool DeviceConnect();
+  bool DeviceStreamOn();
+  bool DeviceStreamOff();
+  CS_StatusValue DeviceSetMode();
+  void DeviceCacheMode();
+  void DeviceCacheProperty(std::unique_ptr<UsbCameraProperty> rawProp,
+                           IMFSourceReader* sourceReader);
+  void DeviceCacheProperties();
+  void DeviceCacheVideoModes();
+  template <typename TagProperty, typename IAM>
+  void DeviceAddProperty(const wpi::Twine& name_, TagProperty tag,
+                         IAM* pProcAmp);
+
+  ComPtr<IMFMediaType> DeviceCheckModeValid(const VideoMode& toCheck);
+
+  // Command helper functions
+  CS_StatusValue DeviceProcessCommand(std::unique_lock<wpi::mutex>& lock,
+                                      Message::Kind msgKind,
+                                      const Message* msg);
+  CS_StatusValue DeviceCmdSetMode(std::unique_lock<wpi::mutex>& lock,
+                                  const Message& msg);
+  CS_StatusValue DeviceCmdSetProperty(std::unique_lock<wpi::mutex>& lock,
+                                      const Message& msg);
+
+  // Property helper functions
+  int RawToPercentage(const UsbCameraProperty& rawProp, int rawValue);
+  int PercentageToRaw(const UsbCameraProperty& rawProp, int percentValue);
+
+  void StartMessagePump();
+
+  //
+  // Variables only used within camera thread
+  //
+  bool m_streaming{false};
+  bool m_wasStreaming{false};
+  bool m_modeSet{false};
+  int m_connectVerbose{1};
+  bool m_deviceValid{false};
+
+  ComPtr<IMFMediaSource> m_mediaSource;
+  ComPtr<IMFSourceReader> m_sourceReader;
+  ComPtr<SourceReaderCB> m_imageCallback;
+  std::unique_ptr<cs::WindowsMessagePump> m_messagePump;
+  ComPtr<IMFMediaType> m_currentMode;
+
+  //
+  // Path never changes, so not protected by mutex.
+  //
+  std::string m_path;
+
+  std::wstring m_widePath;
+  int m_deviceId;
+
+  std::vector<std::pair<VideoMode, ComPtr<IMFMediaType>>> m_windowsVideoModes;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_USBCAMERAIMPL_H_
diff --git a/cscore/src/main/native/windows/UsbCameraProperty.cpp b/cscore/src/main/native/windows/UsbCameraProperty.cpp
new file mode 100644
index 0000000..ae22436
--- /dev/null
+++ b/cscore/src/main/native/windows/UsbCameraProperty.cpp
@@ -0,0 +1,189 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "UsbCameraProperty.h"
+
+#include "ComPtr.h"
+
+using namespace cs;
+
+UsbCameraProperty::UsbCameraProperty(const wpi::Twine& name_,
+                                     tagVideoProcAmpProperty tag, bool autoProp,
+                                     IAMVideoProcAmp* pProcAmp, bool* isValid)
+    : PropertyImpl{autoProp ? name_ + "_auto" : name_} {
+  this->tagVideoProc = tag;
+  this->isControlProperty = false;
+  this->isAutoProp = autoProp;
+  long paramVal, paramFlag;  // NOLINT(runtime/int)
+  HRESULT hr;
+  long minVal, maxVal, stepVal;  // NOLINT(runtime/int)
+  hr = pProcAmp->GetRange(tag, &minVal, &maxVal, &stepVal, &paramVal,
+                          &paramFlag);  // Unable to get the property, trying to
+                                        // return default value
+  if (SUCCEEDED(hr)) {
+    minimum = minVal;
+    maximum = maxVal;
+    hasMaximum = true;
+    hasMinimum = true;
+    defaultValue = paramVal;
+    step = stepVal;
+    value = paramVal;
+    propKind = CS_PropertyKind::CS_PROP_INTEGER;
+    *isValid = true;
+  } else {
+    *isValid = false;
+  }
+}
+
+bool UsbCameraProperty::DeviceGet(std::unique_lock<wpi::mutex>& lock,
+                                  IAMVideoProcAmp* pProcAmp) {
+  if (!pProcAmp) return true;
+
+  lock.unlock();
+  long newValue = 0, paramFlag = 0;  // NOLINT(runtime/int)
+  if (SUCCEEDED(pProcAmp->Get(tagVideoProc, &newValue, &paramFlag))) {
+    lock.lock();
+    value = newValue;
+    return true;
+  }
+
+  return false;
+}
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                                  IAMVideoProcAmp* pProcAmp) const {
+  return DeviceSet(lock, pProcAmp, value);
+}
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                                  IAMVideoProcAmp* pProcAmp,
+                                  int newValue) const {
+  if (!pProcAmp) return true;
+
+  lock.unlock();
+  if (SUCCEEDED(
+          pProcAmp->Set(tagVideoProc, newValue, VideoProcAmp_Flags_Manual))) {
+    lock.lock();
+    return true;
+  }
+
+  return false;
+}
+
+UsbCameraProperty::UsbCameraProperty(const wpi::Twine& name_,
+                                     tagCameraControlProperty tag,
+                                     bool autoProp, IAMCameraControl* pProcAmp,
+                                     bool* isValid)
+    : PropertyImpl{autoProp ? name_ + "_auto" : name_} {
+  this->tagCameraControl = tag;
+  this->isControlProperty = true;
+  this->isAutoProp = autoProp;
+  long paramVal, paramFlag;  // NOLINT(runtime/int)
+  HRESULT hr;
+  long minVal, maxVal, stepVal;  // NOLINT(runtime/int)
+  hr = pProcAmp->GetRange(tag, &minVal, &maxVal, &stepVal, &paramVal,
+                          &paramFlag);  // Unable to get the property, trying to
+                                        // return default value
+  if (SUCCEEDED(hr)) {
+    minimum = minVal;
+    maximum = maxVal;
+    hasMaximum = true;
+    hasMinimum = true;
+    defaultValue = paramVal;
+    step = stepVal;
+    value = paramVal;
+    propKind = CS_PropertyKind::CS_PROP_INTEGER;
+    *isValid = true;
+  } else {
+    *isValid = false;
+  }
+}
+
+bool UsbCameraProperty::DeviceGet(std::unique_lock<wpi::mutex>& lock,
+                                  IAMCameraControl* pProcAmp) {
+  if (!pProcAmp) return true;
+
+  lock.unlock();
+  long newValue = 0, paramFlag = 0;  // NOLINT(runtime/int)
+  if (SUCCEEDED(pProcAmp->Get(tagCameraControl, &newValue, &paramFlag))) {
+    lock.lock();
+    value = newValue;
+    return true;
+  }
+
+  return false;
+}
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                                  IAMCameraControl* pProcAmp) const {
+  return DeviceSet(lock, pProcAmp, value);
+}
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                                  IAMCameraControl* pProcAmp,
+                                  int newValue) const {
+  if (!pProcAmp) return true;
+
+  lock.unlock();
+  if (SUCCEEDED(pProcAmp->Set(tagCameraControl, newValue,
+                              CameraControl_Flags_Manual))) {
+    lock.lock();
+    return true;
+  }
+
+  return false;
+}
+
+bool UsbCameraProperty::DeviceGet(std::unique_lock<wpi::mutex>& lock,
+                                  IMFSourceReader* sourceReader) {
+  if (!sourceReader) return true;
+
+  if (isControlProperty) {
+    ComPtr<IAMCameraControl> pProcAmp;
+    if (SUCCEEDED(sourceReader->GetServiceForStream(
+            (DWORD)MF_SOURCE_READER_MEDIASOURCE, GUID_NULL,
+            IID_PPV_ARGS(pProcAmp.GetAddressOf())))) {
+      return DeviceGet(lock, pProcAmp.Get());
+    } else {
+      return false;
+    }
+  } else {
+    ComPtr<IAMVideoProcAmp> pProcAmp;
+    if (SUCCEEDED(sourceReader->GetServiceForStream(
+            (DWORD)MF_SOURCE_READER_MEDIASOURCE, GUID_NULL,
+            IID_PPV_ARGS(pProcAmp.GetAddressOf())))) {
+      return DeviceGet(lock, pProcAmp.Get());
+    } else {
+      return false;
+    }
+  }
+}
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                                  IMFSourceReader* sourceReader) const {
+  return DeviceSet(lock, sourceReader, value);
+}
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                                  IMFSourceReader* sourceReader,
+                                  int newValue) const {
+  if (!sourceReader) return true;
+
+  if (isControlProperty) {
+    ComPtr<IAMCameraControl> pProcAmp;
+    if (SUCCEEDED(sourceReader->GetServiceForStream(
+            (DWORD)MF_SOURCE_READER_MEDIASOURCE, GUID_NULL,
+            IID_PPV_ARGS(pProcAmp.GetAddressOf())))) {
+      return DeviceSet(lock, pProcAmp.Get(), newValue);
+    } else {
+      return false;
+    }
+  } else {
+    ComPtr<IAMVideoProcAmp> pProcAmp;
+    if (SUCCEEDED(sourceReader->GetServiceForStream(
+            (DWORD)MF_SOURCE_READER_MEDIASOURCE, GUID_NULL,
+            IID_PPV_ARGS(pProcAmp.GetAddressOf())))) {
+      return DeviceSet(lock, pProcAmp.Get(), newValue);
+    } else {
+      return false;
+    }
+  }
+}
diff --git a/cscore/src/main/native/windows/UsbCameraProperty.h b/cscore/src/main/native/windows/UsbCameraProperty.h
new file mode 100644
index 0000000..11888e9
--- /dev/null
+++ b/cscore/src/main/native/windows/UsbCameraProperty.h
@@ -0,0 +1,99 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <mfapi.h>
+#include <mfidl.h>
+#include <mfreadwrite.h>
+
+#include <memory>
+
+#include <Dshow.h>
+#include <wpi/mutex.h>
+
+#include "PropertyImpl.h"
+
+namespace cs {
+
+// Property data
+class UsbCameraProperty : public PropertyImpl {
+ public:
+  UsbCameraProperty() = default;
+  explicit UsbCameraProperty(const wpi::Twine& name_) : PropertyImpl{name_} {}
+
+  // Software property constructor
+  UsbCameraProperty(const wpi::Twine& name_, unsigned id_,
+                    CS_PropertyKind kind_, int minimum_, int maximum_,
+                    int step_, int defaultValue_, int value_)
+      : PropertyImpl(name_, kind_, minimum_, maximum_, step_, defaultValue_,
+                     value_),
+        device{false},
+        id{id_} {}
+
+  // Normalized property constructor
+  UsbCameraProperty(const wpi::Twine& name_, int rawIndex_,
+                    const UsbCameraProperty& rawProp, int defaultValue_,
+                    int value_)
+      : PropertyImpl(name_, rawProp.propKind, 1, defaultValue_, value_),
+        percentage{true},
+        propPair{rawIndex_},
+        id{rawProp.id},
+        type{rawProp.type} {
+    hasMinimum = true;
+    minimum = 0;
+    hasMaximum = true;
+    maximum = 100;
+  }
+
+  UsbCameraProperty(const wpi::Twine& name_, tagVideoProcAmpProperty tag,
+                    bool autoProp, IAMVideoProcAmp* pProcAmp, bool* isValid);
+
+  UsbCameraProperty(const wpi::Twine& name_, tagCameraControlProperty tag,
+                    bool autoProp, IAMCameraControl* pProcAmp, bool* isValid);
+
+  bool DeviceGet(std::unique_lock<wpi::mutex>& lock,
+                 IMFSourceReader* sourceReader);
+  bool DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                 IMFSourceReader* sourceReader) const;
+  bool DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                 IMFSourceReader* sourceReader, int newValue) const;
+
+  // If this is a device (rather than software) property
+  bool device{true};
+  bool isAutoProp{true};
+
+  bool isControlProperty{false};
+  tagVideoProcAmpProperty tagVideoProc{
+      tagVideoProcAmpProperty::VideoProcAmp_Brightness};
+  tagCameraControlProperty tagCameraControl{
+      tagCameraControlProperty::CameraControl_Pan};
+
+  // If this is a percentage (rather than raw) property
+  bool percentage{false};
+
+  // If not 0, index of corresponding raw/percentage property
+  int propPair{0};
+
+  unsigned id{0};  // implementation-level id
+  int type{0};     // implementation type, not CS_PropertyKind!
+
+ private:
+  bool DeviceGet(std::unique_lock<wpi::mutex>& lock,
+                 IAMCameraControl* pProcAmp);
+  bool DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                 IAMCameraControl* pProcAmp) const;
+  bool DeviceSet(std::unique_lock<wpi::mutex>& lock, IAMCameraControl* pProcAmp,
+                 int newValue) const;
+
+  bool DeviceGet(std::unique_lock<wpi::mutex>& lock, IAMVideoProcAmp* pProcAmp);
+  bool DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                 IAMVideoProcAmp* pProcAmp) const;
+  bool DeviceSet(std::unique_lock<wpi::mutex>& lock, IAMVideoProcAmp* pProcAmp,
+                 int newValue) const;
+};
+}  // namespace cs
diff --git a/cscore/src/main/native/windows/WindowsMessagePump.cpp b/cscore/src/main/native/windows/WindowsMessagePump.cpp
new file mode 100644
index 0000000..0206bd0
--- /dev/null
+++ b/cscore/src/main/native/windows/WindowsMessagePump.cpp
@@ -0,0 +1,152 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "WindowsMessagePump.h"
+
+#include <ks.h>
+#include <ksmedia.h>
+#include <mfapi.h>
+#include <mfidl.h>
+#include <windows.h>
+#include <windowsx.h>
+
+#include <memory>
+
+#include <Dbt.h>
+
+#pragma comment(lib, "Mfplat.lib")
+#pragma comment(lib, "Mf.lib")
+#pragma comment(lib, "mfuuid.lib")
+#pragma comment(lib, "Ole32.lib")
+#pragma comment(lib, "User32.lib")
+
+namespace cs {
+
+static LRESULT CALLBACK pWndProc(HWND hwnd, UINT uiMsg, WPARAM wParam,
+                                 LPARAM lParam) {
+  WindowsMessagePump* pumpContainer;
+  // Our "this" parameter is passed only during WM_CREATE
+  // If it is create, store in our user parameter
+  // Otherwise grab from our user parameter
+  if (uiMsg == WM_CREATE) {
+    CREATESTRUCT* pCreate = reinterpret_cast<CREATESTRUCT*>(lParam);
+    pumpContainer =
+        reinterpret_cast<WindowsMessagePump*>(pCreate->lpCreateParams);
+    SetWindowLongPtr(hwnd, GWLP_USERDATA, (LONG_PTR)pumpContainer);
+    SetWindowPos(hwnd, HWND_MESSAGE, 0, 0, 0, 0,
+                 SWP_NOMOVE | SWP_NOSIZE | SWP_NOZORDER | SWP_FRAMECHANGED);
+  } else {
+    pumpContainer = reinterpret_cast<WindowsMessagePump*>(
+        GetWindowLongPtr(hwnd, GWLP_USERDATA));
+  }
+
+  // Run the callback
+  bool hasCalledBack = false;
+  LRESULT result;
+
+  if (pumpContainer) {
+    hasCalledBack = true;
+    result = pumpContainer->m_callback(hwnd, uiMsg, wParam, lParam);
+  }
+
+  // Handle a close message
+  if (uiMsg == WM_CLOSE) {
+    return HANDLE_WM_CLOSE(hwnd, 0, 0, [](HWND) { PostQuitMessage(0); });
+  }
+
+  // Return message, otherwise return the base handler
+  if (hasCalledBack) {
+    return result;
+  }
+  return DefWindowProc(hwnd, uiMsg, wParam, lParam);
+}
+
+namespace {
+struct ClassHolder {
+  HINSTANCE current_instance;
+  WNDCLASSEX wx;
+  const char* class_name = "DUMMY_CLASS";
+  ClassHolder() {
+    current_instance = (HINSTANCE)GetModuleHandle(NULL);
+    wx = {};
+    wx.cbSize = sizeof(WNDCLASSEX);
+    wx.lpfnWndProc = pWndProc;  // function which will handle messages
+    wx.hInstance = current_instance;
+    wx.lpszClassName = class_name;
+    RegisterClassEx(&wx);
+  }
+  ~ClassHolder() { UnregisterClass(class_name, current_instance); }
+};
+}  // namespace
+
+static std::shared_ptr<ClassHolder> GetClassHolder() {
+  static std::shared_ptr<ClassHolder> clsHolder =
+      std::make_shared<ClassHolder>();
+  return clsHolder;
+}
+
+WindowsMessagePump::WindowsMessagePump(
+    std::function<LRESULT(HWND, UINT, WPARAM, LPARAM)> callback) {
+  m_callback = callback;
+  auto handle = CreateEvent(NULL, true, false, NULL);
+  m_mainThread = std::thread([=]() { ThreadMain(handle); });
+  auto waitResult = WaitForSingleObject(handle, 1000);
+  if (waitResult == WAIT_OBJECT_0) {
+    CloseHandle(handle);
+  }
+}
+
+WindowsMessagePump::~WindowsMessagePump() {
+  auto res = SendMessage(hwnd, WM_CLOSE, NULL, NULL);
+  if (m_mainThread.joinable()) m_mainThread.join();
+}
+
+void WindowsMessagePump::ThreadMain(HANDLE eventHandle) {
+  // Initialize COM
+  CoInitializeEx(0, COINIT_MULTITHREADED);
+  // Initialize MF
+  MFStartup(MF_VERSION);
+
+  auto classHolder = GetClassHolder();
+  hwnd = CreateWindowEx(0, classHolder->class_name, "dummy_name", 0, 0, 0, 0, 0,
+                        HWND_MESSAGE, NULL, NULL, this);
+
+  // Register for device notifications
+  HDEVNOTIFY g_hdevnotify = NULL;
+  HDEVNOTIFY g_hdevnotify2 = NULL;
+
+  DEV_BROADCAST_DEVICEINTERFACE di = {0};
+  di.dbcc_size = sizeof(di);
+  di.dbcc_devicetype = DBT_DEVTYP_DEVICEINTERFACE;
+  di.dbcc_classguid = KSCATEGORY_CAPTURE;
+
+  g_hdevnotify =
+      RegisterDeviceNotification(hwnd, &di, DEVICE_NOTIFY_WINDOW_HANDLE);
+
+  DEV_BROADCAST_DEVICEINTERFACE di2 = {0};
+  di2.dbcc_size = sizeof(di2);
+  di2.dbcc_devicetype = DBT_DEVTYP_DEVICEINTERFACE;
+  di2.dbcc_classguid = KSCATEGORY_VIDEO_CAMERA;
+
+  g_hdevnotify2 =
+      RegisterDeviceNotification(hwnd, &di2, DEVICE_NOTIFY_WINDOW_HANDLE);
+
+  SetEvent(eventHandle);
+
+  MSG Msg;
+  while (GetMessage(&Msg, NULL, 0, 0) > 0) {
+    TranslateMessage(&Msg);
+    DispatchMessage(&Msg);
+  }
+  UnregisterDeviceNotification(g_hdevnotify);
+  UnregisterDeviceNotification(g_hdevnotify2);
+
+  MFShutdown();
+  CoUninitialize();
+}
+
+}  // namespace cs
diff --git a/cscore/src/main/native/windows/WindowsMessagePump.h b/cscore/src/main/native/windows/WindowsMessagePump.h
new file mode 100644
index 0000000..4638e4e
--- /dev/null
+++ b/cscore/src/main/native/windows/WindowsMessagePump.h
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <windows.h>
+
+#include <functional>
+#include <thread>
+
+namespace cs {
+class WindowsMessagePump {
+ public:
+  WindowsMessagePump(
+      std::function<LRESULT(HWND, UINT, WPARAM, LPARAM)> callback);
+  ~WindowsMessagePump();
+
+  friend LRESULT CALLBACK pWndProc(HWND hwnd, UINT uiMsg, WPARAM wParam,
+                                   LPARAM lParam);
+
+  template <typename RetVal = LRESULT, typename FirstParam = WPARAM,
+            typename SecondParam = LPARAM>
+  RetVal SendWindowMessage(UINT msg, FirstParam wParam, SecondParam lParam) {
+    static_assert(sizeof(FirstParam) <= sizeof(WPARAM),
+                  "First Parameter Does Not Fit");
+    static_assert(sizeof(SecondParam) <= sizeof(LPARAM),
+                  "Second Parameter Does Not Fit");
+    static_assert(sizeof(RetVal) <= sizeof(LRESULT),
+                  "Return Value Does Not Fit");
+    WPARAM firstToSend = 0;
+    LPARAM secondToSend = 0;
+    std::memcpy(&firstToSend, &wParam, sizeof(FirstParam));
+    std::memcpy(&secondToSend, &lParam, sizeof(SecondParam));
+    LRESULT result = SendMessage(hwnd, msg, firstToSend, secondToSend);
+    RetVal toReturn;
+    std::memset(&toReturn, 0, sizeof(RetVal));
+    std::memcpy(&toReturn, &result, sizeof(RetVal));
+    return toReturn;
+  }
+
+  template <typename FirstParam = WPARAM, typename SecondParam = LPARAM>
+  BOOL PostWindowMessage(UINT msg, FirstParam wParam, SecondParam lParam) {
+    static_assert(sizeof(FirstParam) <= sizeof(WPARAM),
+                  "First Parameter Does Not Fit");
+    static_assert(sizeof(SecondParam) <= sizeof(LPARAM),
+                  "Second Parameter Does Not Fit");
+    WPARAM firstToSend = 0;
+    LPARAM secondToSend = 0;
+    std::memcpy(&firstToSend, &wParam, sizeof(FirstParam));
+    std::memcpy(&secondToSend, &lParam, sizeof(SecondParam));
+    return PostMessage(hwnd, msg, firstToSend, secondToSend);
+  }
+
+ private:
+  void ThreadMain(HANDLE eventHandle);
+
+  HWND hwnd;
+  std::function<LRESULT(HWND, UINT, WPARAM, LPARAM)> m_callback;
+
+  std::thread m_mainThread;
+};
+}  // namespace cs
diff --git a/cscore/src/test/java/edu/wpi/cscore/JNITest.java b/cscore/src/test/java/edu/wpi/cscore/JNITest.java
new file mode 100644
index 0000000..b3c1062
--- /dev/null
+++ b/cscore/src/test/java/edu/wpi/cscore/JNITest.java
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import org.junit.jupiter.api.Test;
+
+class JNITest {
+  @Test
+  void jniLinkTest() {
+    // Test to verify that the JNI test link works correctly.
+    CameraServerJNI.getHostname();
+  }
+}
diff --git a/cscore/src/test/java/edu/wpi/cscore/UsbCameraTest.java b/cscore/src/test/java/edu/wpi/cscore/UsbCameraTest.java
new file mode 100644
index 0000000..9df3645
--- /dev/null
+++ b/cscore/src/test/java/edu/wpi/cscore/UsbCameraTest.java
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import java.time.Duration;
+import java.util.Arrays;
+import java.util.concurrent.CompletableFuture;
+import java.util.concurrent.TimeUnit;
+import java.util.concurrent.TimeoutException;
+
+import org.junit.jupiter.api.Nested;
+import org.junit.jupiter.api.Test;
+import org.junit.jupiter.api.condition.EnabledOnOs;
+import org.junit.jupiter.api.condition.OS;
+
+import static org.junit.jupiter.api.Assertions.assertThrows;
+import static org.junit.jupiter.api.Assertions.assertTimeoutPreemptively;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+class UsbCameraTest {
+  @Nested
+  @EnabledOnOs(OS.LINUX)
+  class ConnectVerbose {
+    @Test
+    void setConnectVerboseEnabledTest() {
+      try (UsbCamera camera = new UsbCamera("Nonexistant Camera", getNonexistentCameraDev())) {
+        camera.setConnectVerbose(1);
+
+        CompletableFuture<String> result = new CompletableFuture<>();
+        CameraServerJNI.setLogger((level, file, line, message) -> result.complete(message), 20);
+
+        assertTimeoutPreemptively(Duration.ofSeconds(5),
+            () -> assertTrue(result.get().contains("Connecting to USB camera on ")));
+      }
+    }
+
+    @Test
+    void setConnectVerboseDisabledTest() {
+      try (UsbCamera camera = new UsbCamera("Nonexistant Camera", getNonexistentCameraDev())) {
+        camera.setConnectVerbose(0);
+
+        CompletableFuture<String> result = new CompletableFuture<>();
+        CameraServerJNI.setLogger((level, file, line, message) -> result.complete(message), 20);
+
+        assertThrows(TimeoutException.class,
+            () -> result.get(3, TimeUnit.SECONDS));
+      }
+    }
+  }
+
+  private static int getNonexistentCameraDev() {
+    return Arrays.stream(CameraServerJNI.enumerateUsbCameras())
+        .mapToInt(info -> info.dev)
+        .max().orElse(-1) + 1;
+  }
+}
diff --git a/cscore/src/test/native/cpp/CameraSourceTest.cpp b/cscore/src/test/native/cpp/CameraSourceTest.cpp
new file mode 100644
index 0000000..e09f5e6
--- /dev/null
+++ b/cscore/src/test/native/cpp/CameraSourceTest.cpp
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "cscore.h"
+#include "gtest/gtest.h"
+
+namespace cs {
+
+class CameraSourceTest : public ::testing::Test {
+ protected:
+  CameraSourceTest() {}
+};
+
+TEST_F(CameraSourceTest, HTTPCamera) {
+  auto source = HttpCamera("axis", "http://localhost:8000");
+}
+
+}  // namespace cs
diff --git a/cscore/src/test/native/cpp/main.cpp b/cscore/src/test/native/cpp/main.cpp
new file mode 100644
index 0000000..1e5ecf0
--- /dev/null
+++ b/cscore/src/test/native/cpp/main.cpp
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "gtest/gtest.h"
+
+int main(int argc, char** argv) {
+  ::testing::InitGoogleTest(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}