Put in new allwiplib-2018 and packaged the large files

added new allwpilib

added ntcore

Added new wpiutil

Change-Id: I5bbb966a69ac2fbdce056e4c092a13f246dbaa6a
diff --git a/third_party/allwpilib_2018/wpilibcExamples/.clang-format b/third_party/allwpilib_2018/wpilibcExamples/.clang-format
new file mode 100644
index 0000000..504fb82
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/.clang-format
@@ -0,0 +1,76 @@
+---
+Language: Cpp
+AccessModifierOffset: -8
+AlignAfterOpenBracket: DontAlign
+AlignConsecutiveAssignments: false
+AlignConsecutiveDeclarations: false
+AlignEscapedNewlinesLeft: true
+AlignOperands: true
+AlignTrailingComments: true
+AllowAllParametersOfDeclarationOnNextLine: true
+AllowShortBlocksOnASingleLine: false
+AllowShortCaseLabelsOnASingleLine: false
+AllowShortFunctionsOnASingleLine: Inline
+AllowShortIfStatementsOnASingleLine: true
+AllowShortLoopsOnASingleLine: true
+AlwaysBreakAfterDefinitionReturnType: None
+AlwaysBreakAfterReturnType: None
+AlwaysBreakBeforeMultilineStrings: false
+AlwaysBreakTemplateDeclarations: false
+BinPackArguments: true
+BinPackParameters: true
+BraceWrapping: {AfterClass: false, AfterControlStatement: false, AfterEnum: false,
+  AfterFunction: true, AfterNamespace: false, AfterObjCDeclaration: false, AfterStruct: false,
+  AfterUnion: false, BeforeCatch: false, BeforeElse: false, IndentBraces: false}
+BreakBeforeBinaryOperators: NonAssignment
+BreakBeforeBraces: Attach
+BreakBeforeTernaryOperators: false
+BreakConstructorInitializersBeforeComma: true
+ColumnLimit: 80
+CommentPragmas: '^ IWYU pragma:'
+ConstructorInitializerAllOnOneLineOrOnePerLine: false
+ConstructorInitializerIndentWidth: 4
+ContinuationIndentWidth: 16
+Cpp11BracedListStyle: true
+DerivePointerAlignment: false
+DisableFormat: false
+ExperimentalAutoDetectBinPacking: true
+ForEachMacros: [foreach, Q_FOREACH, BOOST_FOREACH]
+IncludeCategories:
+  - {Priority: 2, Regex: ^"(llvm|llvm-c|clang|clang-c)/}
+  - {Priority: 3, Regex: ^(<|"(gtest|isl|json)/)}
+  - {Priority: 1, Regex: .*}
+IndentCaseLabels: true
+IndentWidth: 8
+IndentWrappedFunctionNames: true
+KeepEmptyLinesAtTheStartOfBlocks: false
+MacroBlockBegin: ''
+MacroBlockEnd: ''
+MaxEmptyLinesToKeep: 1
+NamespaceIndentation: Inner
+ObjCBlockIndentWidth: 0
+ObjCSpaceAfterProperty: true
+ObjCSpaceBeforeProtocolList: true
+PenaltyBreakBeforeFirstCallParameter: 19
+PenaltyBreakComment: 345
+PenaltyBreakFirstLessLess: 150
+PenaltyBreakString: 618
+PenaltyExcessCharacter: 977572
+PenaltyReturnTypeOnItsOwnLine: 41
+PointerAlignment: Left
+ReflowComments: true
+SortIncludes: true
+SpaceAfterCStyleCast: false
+SpaceBeforeAssignmentOperators: true
+SpaceBeforeParens: ControlStatements
+SpaceInEmptyParentheses: false
+SpacesBeforeTrailingComments: 2
+SpacesInAngles: false
+SpacesInCStyleCastParentheses: true
+SpacesInContainerLiterals: true
+SpacesInParentheses: false
+SpacesInSquareBrackets: false
+Standard: Cpp03
+TabWidth: 8
+UseTab: Always
+...
diff --git a/third_party/allwpilib_2018/wpilibcExamples/.styleguide b/third_party/allwpilib_2018/wpilibcExamples/.styleguide
new file mode 100644
index 0000000..1925143
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/.styleguide
@@ -0,0 +1,45 @@
+cppHeaderFileInclude {
+  \.h$
+  \.hpp$
+  \.inc$
+}
+
+cppSrcFileInclude {
+  \.cpp$
+}
+
+generatedFileExclude {
+  gmock/
+  ni-libraries/include/
+  ni-libraries/lib/
+  hal/src/main/native/athena/ctre/
+  hal/src/main/native/athena/frccansae/
+  hal/src/main/native/athena/visa/
+  hal/src/main/native/include/ctre/
+  UsageReporting\.h$
+}
+
+modifiableFileExclude {
+  wpilibj/src/arm-linux-jni/
+  wpilibj/src/main/native/cpp/
+  \.patch$
+  \.png$
+  \.py$
+  \.so$
+}
+
+includeGuardRoots {
+  wpilibcExamples/src/main/cpp/examples/
+  wpilibcExamples/src/main/cpp/templates/
+}
+
+includeOtherLibs {
+  ^HAL/
+  ^llvm/
+  ^opencv2/
+  ^support/
+}
+
+includeProject {
+  ^ctre/
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/build.gradle b/third_party/allwpilib_2018/wpilibcExamples/build.gradle
new file mode 100644
index 0000000..d0b6649
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/build.gradle
@@ -0,0 +1,114 @@
+import org.gradle.language.base.internal.ProjectLayout
+
+if (!project.hasProperty('skipAthena')) {
+    apply plugin: 'cpp'
+    apply plugin: 'visual-studio'
+    apply plugin: 'edu.wpi.first.NativeUtils'
+
+    apply from: '../config.gradle'
+
+    ext.examplesMap = [:]
+    ext.templatesMap = [:]
+
+    File examplesTree = file("$projectDir/src/main/cpp/examples")
+    examplesTree.list(new FilenameFilter() {
+      @Override
+      public boolean accept(File current, String name) {
+        return new File(current, name).isDirectory();
+      }
+    }).each {
+        examplesMap.put(it, [])
+    }
+    File templatesTree = file("$projectDir/src/main/cpp/templates")
+    templatesTree.list(new FilenameFilter() {
+      @Override
+      public boolean accept(File current, String name) {
+        return new File(current, name).isDirectory();
+      }
+    }).each {
+        templatesMap.put(it, [])
+    }
+
+    model {
+        dependencyConfigs {
+            wpiutil(DependencyConfig) {
+                groupId = 'edu.wpi.first.wpiutil'
+                artifactId = 'wpiutil-cpp'
+                headerClassifier = 'headers'
+                ext = 'zip'
+                version = '3.+'
+                sharedConfigs = examplesMap + templatesMap
+            }
+            ntcore(DependencyConfig) {
+                groupId = 'edu.wpi.first.ntcore'
+                artifactId = 'ntcore-cpp'
+                headerClassifier = 'headers'
+                ext = 'zip'
+                version = '4.+'
+                sharedConfigs = examplesMap + templatesMap
+            }
+            opencv(DependencyConfig) {
+                groupId = 'org.opencv'
+                artifactId = 'opencv-cpp'
+                headerClassifier = 'headers'
+                ext = 'zip'
+                version = '3.2.0'
+                sharedConfigs = examplesMap + templatesMap
+            }
+            cscore(DependencyConfig) {
+                groupId = 'edu.wpi.first.cscore'
+                artifactId = 'cscore-cpp'
+                headerClassifier = 'headers'
+                ext = 'zip'
+                version = '1.+'
+                sharedConfigs = examplesMap + templatesMap
+            }
+        }
+
+        components {
+            examplesMap.each { key, value->
+                "${key}"(NativeExecutableSpec) {
+                    binaries.all { binary->
+                        if (binary.targetPlatform.architecture.name == 'athena') {
+                            project(':ni-libraries').addNiLibrariesToLinker(binary)
+                            project(':hal').addHalToLinker(binary)
+                            project(':wpilibc').addWpilibCToLinker(binary)
+                        } else {
+                            binary.buildable = false
+                        }
+                    }
+                    sources {
+                        cpp {
+                            source {
+                                srcDirs 'src/main/cpp/examples/' + "${key}"
+                                include '**/*.cpp'
+                            }
+                        }
+                    }
+                }
+            }
+            templatesMap.each { key, value->
+                "${key}"(NativeExecutableSpec) {
+                    binaries.all { binary->
+                        if (binary.targetPlatform.architecture.name == 'athena') {
+                            project(':ni-libraries').addNiLibrariesToLinker(binary)
+                            project(':hal').addHalToLinker(binary)
+                            project(':wpilibc').addWpilibCToLinker(binary)
+                        } else {
+                            binary.buildable = false
+                        }
+                    }
+                    sources {
+                        cpp {
+                            source {
+                                srcDirs 'src/main/cpp/templates/' + "${key}"
+                                include '**/*.cpp'
+                            }
+                        }
+                    }
+                }
+            }
+        }
+    }
+    apply from: 'publish.gradle'
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/examples.xml b/third_party/allwpilib_2018/wpilibcExamples/examples.xml
new file mode 100644
index 0000000..5450e84
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/examples.xml
@@ -0,0 +1,482 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<examples>
+    <!-- TODO add back in when there are enough samples to justify tags
+    <tagDescription>
+      <name>Simple Robot</name>
+      <description>Examples for simple robot programs.</description>
+    </tagDescription>
+    <tagDescription>
+      <name>Network Tables</name>
+      <description>Examples of how to use Network Tables to accomplish a
+      variety of tasks such as sending and receiving values to both
+      dashboards and co-processors.</description>
+    </tagDescription>
+    <tagDescription>
+      <name>Simulation</name>
+      <description>Examples that can be run in simulation.</description>
+    </tagDescription>-->
+    <tagDescription>
+        <name>Getting Started with C++</name>
+        <description>Examples for getting started with FRC C++</description>
+    </tagDescription>
+    <tagDescription>
+        <name>CommandBased Robot</name>
+        <description>Examples for CommandBased robot programs.</description>
+    </tagDescription>
+    <tagDescription>
+        <name>Actuators</name>
+        <description>Example programs that demonstrate the use of various actuators</description>
+    </tagDescription>
+    <tagDescription>
+        <name>Analog</name>
+        <description>Examples programs that show different uses of analog inputs,
+            outputs and various analog sensors</description>
+    </tagDescription>
+    <tagDescription>
+        <name>CAN</name>
+        <description>Example programs that demonstrate the use of the CAN components in the control
+            system</description>
+    </tagDescription>
+    <tagDescription>
+        <name>Complete List</name>
+        <description>Complete list of all sample programs across all categories</description>
+    </tagDescription>
+    <tagDescription>
+        <name>Digital</name>
+        <description>Example programs that demonstrate the sensors that use the digital I/O ports</description>
+    </tagDescription>
+    <tagDescription>
+        <name>I2C</name>
+        <description>Example programs that demonstrate the use of I2C and various sensors that use
+            it</description>
+    </tagDescription>
+    <tagDescription>
+        <name>Joystick</name>
+        <description>Example programs that demonstate different uses of joysticks for robot
+            driving</description>
+    </tagDescription>
+    <tagDescription>
+        <name>Pneumatics</name>
+        <description>Example programs that demonstrate the use of the compressor and solenoids</description>
+    </tagDescription>
+    <tagDescription>
+        <name>Robot and Motor</name>
+        <description>Example programs that demonstrate driving a robot and motors including safety,
+            servos, etc.</description>
+    </tagDescription>
+    <tagDescription>
+        <name>SPI</name>
+        <description>Example programs that demonstrate the use of the SPI bus and sensors that
+            connect to it</description>
+    </tagDescription>
+    <tagDescription>
+        <name>Safety</name>
+        <description>Example programs that demonstate the motor safety classes and how to use them
+            with your programs</description>
+    </tagDescription>
+    <tagDescription>
+        <name>Sensors</name>
+        <description>Example programs that demonstrate the use of the various commonly used sensors
+            on FRC robots</description>
+    </tagDescription>
+    <tagDescription>
+        <name>Vision</name>
+        <description>Example programs that demonstrate the use of a camera for image acquisition and
+            processing</description>
+    </tagDescription>
+    <example>
+        <name>Motor Controller</name>
+        <description>Demonstrate controlling a single motor with a Joystick.</description>
+        <tags>
+            <tag>Robot and Motor</tag>
+            <tag>Actuators</tag>
+            <tag>Joystick</tag>
+            <tag>Complete List</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/MotorControl/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>Motor Control With Encoder</name>
+        <description>Demonstrate controlling a single motor with a Joystick and displaying the net
+            movement of the motor using an encoder.</description>
+        <tags>
+            <tag>Robot and Motor</tag>
+            <tag>Digital</tag>
+            <tag>Sensors</tag>
+            <tag>Actuators</tag>
+            <tag>Joystick</tag>
+            <tag>Complete List</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/MotorControl/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>Relay</name>
+        <description>Demonstrate controlling a Relay from Joystick buttons.</description>
+        <tags>
+            <tag>Actuators</tag>
+            <tag>Joystick</tag>
+            <tag>Complete List</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/Relay/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>PDP CAN Monitoring</name>
+        <description>Demonstrate using CAN to monitor the voltage, current, and temperature in the
+            Power Distribution Panel.</description>
+        <tags>
+            <tag>Complete List</tag>
+            <tag>CAN</tag>
+            <tag>Sensors</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/CANPDP/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>Solenoids</name>
+        <description>Demonstrate controlling a single and double solenoid from Joystick buttons.</description>
+        <tags>
+            <tag>Actuators</tag>
+            <tag>Joystick</tag>
+            <tag>Pneumatics</tag>
+            <tag>Complete List</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/Solenoid/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>Encoder</name>
+        <description>Demonstrate displaying the value of a quadrature encoder on the
+            SmartDashboard.</description>
+        <tags>
+            <tag>Complete List</tag>
+            <tag>Digital</tag>
+            <tag>Sensors</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/Encoder/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>Arcade Drive</name>
+        <description>An example program which demonstrates the use of Arcade Drive with the DifferentialDrive class</description>
+        <tags>
+            <tag>Getting Started with C++</tag>
+            <tag>Robot and Motor</tag>
+            <tag>Joystick</tag>
+            <tag>Complete List</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/ArcadeDrive/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>Mecanum Drive</name>
+        <description>An example program which demonstrates the use of Mecanum Drive with the MecanumDrive class</description>
+        <tags>
+            <tag>Getting Started with C++</tag>
+            <tag>Robot and Motor</tag>
+            <tag>Joystick</tag>
+            <tag>Complete List</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/MecanumDrive/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>Ultrasonic</name>
+        <description>Demonstrate maintaining a set distance using an ultrasonic sensor.</description>
+        <tags>
+            <tag>Robot and Motor</tag>
+            <tag>Complete List</tag>
+            <tag>Sensors</tag>
+            <tag>Analog</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/Ultrasonic/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>UltrasonicPID</name>
+        <description>Demonstrate maintaining a set distance using an ultrasonic sensor and PID
+            control.</description>
+        <tags>
+            <tag>Robot and Motor</tag>
+            <tag>Complete List</tag>
+            <tag>Sensors</tag>
+            <tag>Analog</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/UltrasonicPID/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>Gyro</name>
+        <description>An example program showing how to drive straight with using a gyro sensor.</description>
+        <tags>
+            <tag>Robot and Motor</tag>
+            <tag>Complete List</tag>
+            <tag>Sensors</tag>
+            <tag>Analog</tag>
+            <tag>Joystick</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/Gyro/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>Gyro Mecanum</name>
+        <description>An example program showing how to perform mecanum drive with field oriented
+            controls.</description>
+        <tags>
+            <tag>Robot and Motor</tag>
+            <tag>Complete List</tag>
+            <tag>Sensors</tag>
+            <tag>Analog</tag>
+            <tag>Joysitck</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/GyroMecanum/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>PotentiometerPID</name>
+        <description>An example to demonstrate the use of a potentiometer and PID control to reach
+            elevator position setpoints.</description>
+        <tags>
+            <tag>Joystick</tag>
+            <tag>Actuators</tag>
+            <tag>Complete List</tag>
+            <tag>Sensors</tag>
+            <tag>Analog</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/PotentiometerPID/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>Getting Started</name>
+        <description>An example program which demonstrates the simplest autonomous and
+            teleoperated routines.</description>
+        <tags>
+            <tag>Getting Started with C++</tag>
+            <tag>Complete List</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/GettingStarted/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>Simple Vision</name>
+        <description>The minimal program to acquire images from an attached USB camera on the robot
+            and send them to the dashboard.</description>
+        <tags>
+            <tag>Vision</tag>
+            <tag>Complete List</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/QuickVision/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>Intermediate Vision</name>
+        <description>An example program that acquires images from an attached USB camera and adds
+            some
+            annotation to the image as you might do for showing operators the result of some image
+            recognition, and sends it to the dashboard for display.</description>
+        <tags>
+            <tag>Vision</tag>
+            <tag>Complete List</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/IntermediateVision/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>Axis Camera Sample</name>
+        <description>An example program that acquires images from an Axis network camera and adds
+            some
+            annotation to the image as you might do for showing operators the result of some image
+            recognition, and sends it to the dashboard for display. This demonstrates the use of the
+            AxisCamera class.</description>
+        <tags>
+            <tag>Vision</tag>
+            <tag>Complete List</tag>
+        </tags>
+        <packages>
+            <package>src</package>
+        </packages>
+        <files>
+            <file source="examples/AxisCameraSample/src/Robot.cpp" destination="src/Robot.cpp" />
+        </files>
+    </example>
+    <example>
+        <name>GearsBot</name>
+        <description>A fully functional example CommandBased program for
+            WPIs GearsBot robot. This code can run on your computer if it
+            supports simulation.</description>
+        <tags>
+            <tag>CommandBased Robot</tag>
+            <tag>Complete List</tag>
+        </tags>
+        <world>/usr/share/frcsim/worlds/GearsBotDemo.world</world>
+        <packages>
+            <package>src</package>
+            <package>src/Commands</package>
+            <package>src/Subsystems</package>
+        </packages>
+        <files>
+            <file source="examples/GearsBot/src/Commands/Autonomous.cpp" destination="src/Commands/Autonomous.cpp" />
+            <file source="examples/GearsBot/src/Commands/Autonomous.h" destination="src/Commands/Autonomous.h" />
+            <file source="examples/GearsBot/src/Commands/CloseClaw.cpp" destination="src/Commands/CloseClaw.cpp" />
+            <file source="examples/GearsBot/src/Commands/CloseClaw.h" destination="src/Commands/CloseClaw.h" />
+            <file source="examples/GearsBot/src/Commands/DriveStraight.cpp" destination="src/Commands/DriveStraight.cpp" />
+            <file source="examples/GearsBot/src/Commands/DriveStraight.h" destination="src/Commands/DriveStraight.h" />
+            <file source="examples/GearsBot/src/Commands/OpenClaw.cpp" destination="src/Commands/OpenClaw.cpp" />
+            <file source="examples/GearsBot/src/Commands/OpenClaw.h" destination="src/Commands/OpenClaw.h" />
+            <file source="examples/GearsBot/src/Commands/Pickup.cpp" destination="src/Commands/Pickup.cpp" />
+            <file source="examples/GearsBot/src/Commands/Pickup.h" destination="src/Commands/Pickup.h" />
+            <file source="examples/GearsBot/src/Commands/Place.cpp" destination="src/Commands/Place.cpp" />
+            <file source="examples/GearsBot/src/Commands/Place.h" destination="src/Commands/Place.h" />
+            <file source="examples/GearsBot/src/Commands/PrepareToPickup.cpp" destination="src/Commands/PrepareToPickup.cpp" />
+            <file source="examples/GearsBot/src/Commands/PrepareToPickup.h" destination="src/Commands/PrepareToPickup.h" />
+            <file source="examples/GearsBot/src/Commands/SetDistanceToBox.cpp" destination="src/Commands/SetDistanceToBox.cpp" />
+            <file source="examples/GearsBot/src/Commands/SetDistanceToBox.h" destination="src/Commands/SetDistanceToBox.h" />
+            <file source="examples/GearsBot/src/Commands/SetElevatorSetpoint.cpp" destination="src/Commands/SetElevatorSetpoint.cpp" />
+            <file source="examples/GearsBot/src/Commands/SetElevatorSetpoint.h" destination="src/Commands/SetElevatorSetpoint.h" />
+            <file source="examples/GearsBot/src/Commands/SetWristSetpoint.cpp" destination="src/Commands/SetWristSetpoint.cpp" />
+            <file source="examples/GearsBot/src/Commands/SetWristSetpoint.h" destination="src/Commands/SetWristSetpoint.h" />
+            <file source="examples/GearsBot/src/Commands/TankDriveWithJoystick.cpp" destination="src/Commands/TankDriveWithJoystick.cpp" />
+            <file source="examples/GearsBot/src/Commands/TankDriveWithJoystick.h" destination="src/Commands/TankDriveWithJoystick.h" />
+            <file source="examples/GearsBot/src/OI.cpp" destination="src/OI.cpp" />
+            <file source="examples/GearsBot/src/OI.h" destination="src/OI.h" />
+            <file source="examples/GearsBot/src/Robot.cpp" destination="src/Robot.cpp" />
+            <file source="examples/GearsBot/src/Robot.h" destination="src/Robot.h" />
+            <file source="examples/GearsBot/src/Subsystems/Claw.cpp" destination="src/Subsystems/Claw.cpp" />
+            <file source="examples/GearsBot/src/Subsystems/Claw.h" destination="src/Subsystems/Claw.h" />
+            <file source="examples/GearsBot/src/Subsystems/DriveTrain.cpp" destination="src/Subsystems/DriveTrain.cpp" />
+            <file source="examples/GearsBot/src/Subsystems/DriveTrain.h" destination="src/Subsystems/DriveTrain.h" />
+            <file source="examples/GearsBot/src/Subsystems/Elevator.cpp" destination="src/Subsystems/Elevator.cpp" />
+            <file source="examples/GearsBot/src/Subsystems/Elevator.h" destination="src/Subsystems/Elevator.h" />
+            <file source="examples/GearsBot/src/Subsystems/Wrist.cpp" destination="src/Subsystems/Wrist.cpp" />
+            <file source="examples/GearsBot/src/Subsystems/Wrist.h" destination="src/Subsystems/Wrist.h" />
+        </files>
+    </example>
+    <example>
+        <name>PacGoat</name>
+        <description>A fully functional example CommandBased program for FRC Team 190&amp;#39;s 2014
+            robot. This code can run on your computer if it supports simulation.</description>
+        <tags>
+            <tag>CommandBased Robot</tag>
+            <tag>Complete List</tag>
+        </tags>
+        <world>/usr/share/frcsim/worlds/PacGoat2014.world</world>
+        <packages>
+            <package>src</package>
+            <package>src/Commands</package>
+            <package>src/Subsystems</package>
+            <package>src/Triggers</package>
+        </packages>
+        <files>
+            <file source="examples/PacGoat/src/Commands/CheckForHotGoal.cpp" destination="src/Commands/CheckForHotGoal.cpp" />
+            <file source="examples/PacGoat/src/Commands/CheckForHotGoal.h" destination="src/Commands/CheckForHotGoal.h" />
+            <file source="examples/PacGoat/src/Commands/CloseClaw.cpp" destination="src/Commands/CloseClaw.cpp" />
+            <file source="examples/PacGoat/src/Commands/CloseClaw.h" destination="src/Commands/CloseClaw.h" />
+            <file source="examples/PacGoat/src/Commands/Collect.cpp" destination="src/Commands/Collect.cpp" />
+            <file source="examples/PacGoat/src/Commands/Collect.h" destination="src/Commands/Collect.h" />
+            <file source="examples/PacGoat/src/Commands/DriveAndShootAutonomous.cpp" destination="src/Commands/DriveAndShootAutonomous.cpp" />
+            <file source="examples/PacGoat/src/Commands/DriveAndShootAutonomous.h" destination="src/Commands/DriveAndShootAutonomous.h" />
+            <file source="examples/PacGoat/src/Commands/DriveForward.cpp" destination="src/Commands/DriveForward.cpp" />
+            <file source="examples/PacGoat/src/Commands/DriveForward.h" destination="src/Commands/DriveForward.h" />
+            <file source="examples/PacGoat/src/Commands/DriveWithJoystick.cpp" destination="src/Commands/DriveWithJoystick.cpp" />
+            <file source="examples/PacGoat/src/Commands/DriveWithJoystick.h" destination="src/Commands/DriveWithJoystick.h" />
+            <file source="examples/PacGoat/src/Commands/ExtendShooter.cpp" destination="src/Commands/ExtendShooter.cpp" />
+            <file source="examples/PacGoat/src/Commands/ExtendShooter.h" destination="src/Commands/ExtendShooter.h" />
+            <file source="examples/PacGoat/src/Commands/LowGoal.cpp" destination="src/Commands/LowGoal.cpp" />
+            <file source="examples/PacGoat/src/Commands/LowGoal.h" destination="src/Commands/LowGoal.h" />
+            <file source="examples/PacGoat/src/Commands/OpenClaw.cpp" destination="src/Commands/OpenClaw.cpp" />
+            <file source="examples/PacGoat/src/Commands/OpenClaw.h" destination="src/Commands/OpenClaw.h" />
+            <file source="examples/PacGoat/src/Commands/SetCollectionSpeed.cpp" destination="src/Commands/SetCollectionSpeed.cpp" />
+            <file source="examples/PacGoat/src/Commands/SetCollectionSpeed.h" destination="src/Commands/SetCollectionSpeed.h" />
+            <file source="examples/PacGoat/src/Commands/SetPivotSetpoint.cpp" destination="src/Commands/SetPivotSetpoint.cpp" />
+            <file source="examples/PacGoat/src/Commands/SetPivotSetpoint.h" destination="src/Commands/SetPivotSetpoint.h" />
+            <file source="examples/PacGoat/src/Commands/Shoot.cpp" destination="src/Commands/Shoot.cpp" />
+            <file source="examples/PacGoat/src/Commands/Shoot.h" destination="src/Commands/Shoot.h" />
+            <file source="examples/PacGoat/src/Commands/WaitForBall.cpp" destination="src/Commands/WaitForBall.cpp" />
+            <file source="examples/PacGoat/src/Commands/WaitForBall.h" destination="src/Commands/WaitForBall.h" />
+            <file source="examples/PacGoat/src/Commands/WaitForPressure.cpp" destination="src/Commands/WaitForPressure.cpp" />
+            <file source="examples/PacGoat/src/Commands/WaitForPressure.h" destination="src/Commands/WaitForPressure.h" />
+            <file source="examples/PacGoat/src/OI.cpp" destination="src/OI.cpp" />
+            <file source="examples/PacGoat/src/OI.h" destination="src/OI.h" />
+            <file source="examples/PacGoat/src/Robot.cpp" destination="src/Robot.cpp" />
+            <file source="examples/PacGoat/src/Robot.h" destination="src/Robot.h" />
+            <file source="examples/PacGoat/src/Subsystems/Collector.cpp" destination="src/Subsystems/Collector.cpp" />
+            <file source="examples/PacGoat/src/Subsystems/Collector.h" destination="src/Subsystems/Collector.h" />
+            <file source="examples/PacGoat/src/Subsystems/DriveTrain.cpp" destination="src/Subsystems/DriveTrain.cpp" />
+            <file source="examples/PacGoat/src/Subsystems/DriveTrain.h" destination="src/Subsystems/DriveTrain.h" />
+            <file source="examples/PacGoat/src/Subsystems/Pivot.cpp" destination="src/Subsystems/Pivot.cpp" />
+            <file source="examples/PacGoat/src/Subsystems/Pivot.h" destination="src/Subsystems/Pivot.h" />
+            <file source="examples/PacGoat/src/Subsystems/Pneumatics.cpp" destination="src/Subsystems/Pneumatics.cpp" />
+            <file source="examples/PacGoat/src/Subsystems/Pneumatics.h" destination="src/Subsystems/Pneumatics.h" />
+            <file source="examples/PacGoat/src/Subsystems/Shooter.cpp" destination="src/Subsystems/Shooter.cpp" />
+            <file source="examples/PacGoat/src/Subsystems/Shooter.h" destination="src/Subsystems/Shooter.h" />
+            <file source="examples/PacGoat/src/Triggers/DoubleButton.cpp" destination="src/Triggers/DoubleButton.cpp" />
+            <file source="examples/PacGoat/src/Triggers/DoubleButton.h" destination="src/Triggers/DoubleButton.h" />
+        </files>
+    </example>
+</examples>
diff --git a/third_party/allwpilib_2018/wpilibcExamples/publish.gradle b/third_party/allwpilib_2018/wpilibcExamples/publish.gradle
new file mode 100644
index 0000000..a6558a8
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/publish.gradle
@@ -0,0 +1,74 @@
+apply plugin: 'maven-publish'
+apply plugin: 'edu.wpi.first.wpilib.versioning.WPILibVersioningPlugin'
+
+if (!hasProperty('releaseType')) {
+    WPILibVersion {
+        releaseType = 'dev'
+    }
+}
+
+def pubVersion
+if (project.hasProperty("publishVersion")) {
+    pubVersion = project.publishVersion
+} else {
+    pubVersion = WPILibVersion.version
+}
+
+def baseExamplesArtifactId = 'examples'
+def baseTemplatesArtifactId = 'templates'
+def artifactGroupId = 'edu.wpi.first.wpilibc'
+
+def outputsFolder = file("$project.buildDir/outputs")
+
+task cppExamplesZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = 'wpilibc-examples'
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/cpp/examples') {
+        into 'examples'
+    }
+
+    from ('examples.xml') {
+        into 'examples'
+    }
+}
+
+task cppTemplatesZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = 'wpilibc-templates'
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/cpp/templates') {
+        into 'templates'
+    }
+}
+
+build.dependsOn cppTemplatesZip
+build.dependsOn cppExamplesZip
+
+publishing {
+    publications {
+        examples(MavenPublication) {
+            artifact cppExamplesZip
+
+            artifactId = baseExamplesArtifactId
+            groupId artifactGroupId
+            version pubVersion
+        }
+
+        templates(MavenPublication) {
+            artifact cppTemplatesZip
+
+            artifactId = baseTemplatesArtifactId
+            groupId artifactGroupId
+            version pubVersion
+        }
+    }
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/src/Robot.cpp
new file mode 100644
index 0000000..5632db3
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/src/Robot.cpp
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <Drive/DifferentialDrive.h>
+#include <IterativeRobot.h>
+#include <Joystick.h>
+#include <Spark.h>
+
+/**
+ * This is a demo program showing the use of the DifferentialDrive class.
+ * Runs the motors with arcade steering.
+ */
+class Robot : public frc::IterativeRobot {
+	frc::Spark m_leftMotor{0};
+	frc::Spark m_rightMotor{1};
+	frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
+	frc::Joystick m_stick{0};
+
+public:
+	void TeleopPeriodic() {
+		// drive with arcade style
+		m_robotDrive.ArcadeDrive(m_stick.GetY(), m_stick.GetX());
+	}
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/AxisCameraSample/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/AxisCameraSample/src/Robot.cpp
new file mode 100644
index 0000000..22dc823
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/AxisCameraSample/src/Robot.cpp
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <CameraServer.h>
+#include <IterativeRobot.h>
+#include <opencv2/core/core.hpp>
+#include <opencv2/core/types.hpp>
+#include <opencv2/imgproc/imgproc.hpp>
+
+/**
+ * This is a demo program showing the use of OpenCV to do vision processing. The
+ * image is acquired from the Axis camera, then a rectangle is put on the image
+ * and
+ * sent to the dashboard. OpenCV has many methods for different types of
+ * processing.
+ */
+class Robot : public frc::IterativeRobot {
+private:
+	static void VisionThread() {
+		// Get the Axis camera from CameraServer
+		cs::AxisCamera camera =
+				CameraServer::GetInstance()->AddAxisCamera(
+						"axis-camera.local");
+		// Set the resolution
+		camera.SetResolution(640, 480);
+
+		// Get a CvSink. This will capture Mats from the Camera
+		cs::CvSink cvSink = CameraServer::GetInstance()->GetVideo();
+		// Setup a CvSource. This will send images back to the Dashboard
+		cs::CvSource outputStream =
+				CameraServer::GetInstance()->PutVideo(
+						"Rectangle", 640, 480);
+
+		// Mats are very memory expensive. Lets reuse this Mat.
+		cv::Mat mat;
+
+		while (true) {
+			// Tell the CvSink to grab a frame from the camera and
+			// put it
+			// in the source mat.  If there is an error notify the
+			// output.
+			if (cvSink.GrabFrame(mat) == 0) {
+				// Send the output the error.
+				outputStream.NotifyError(cvSink.GetError());
+				// skip the rest of the current iteration
+				continue;
+			}
+			// Put a rectangle on the image
+			rectangle(mat, cv::Point(100, 100), cv::Point(400, 400),
+					cv::Scalar(255, 255, 255), 5);
+			// Give the output stream a new image to display
+			outputStream.PutFrame(mat);
+		}
+	}
+
+	void RobotInit() {
+		// We need to run our vision program in a separate Thread.
+		// If not, our robot program will not run
+		std::thread visionThread(VisionThread);
+		visionThread.detach();
+	}
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/CANPDP/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/CANPDP/src/Robot.cpp
new file mode 100644
index 0000000..07f01fb
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/CANPDP/src/Robot.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <IterativeRobot.h>
+#include <PowerDistributionPanel.h>
+#include <SmartDashboard/SmartDashboard.h>
+
+/**
+ * This is a sample program showing how to retrieve information from the Power
+ * Distribution Panel via CAN. The information will be displayed under variables
+ * through the SmartDashboard.
+ */
+class Robot : public frc::IterativeRobot {
+public:
+	void TeleopPeriodic() override {
+		/* Get the current going through channel 7, in Amperes. The PDP
+		 * returns the current in increments of 0.125A. At low currents
+		 * the
+		 * current readings tend to be less accurate.
+		 */
+		frc::SmartDashboard::PutNumber(
+				"Current Channel 7", m_pdp.GetCurrent(7));
+
+		/* Get the voltage going into the PDP, in Volts.
+		 * The PDP returns the voltage in increments of 0.05 Volts.
+		 */
+		frc::SmartDashboard::PutNumber("Voltage", m_pdp.GetVoltage());
+
+		// Retrieves the temperature of the PDP, in degrees Celsius.
+		frc::SmartDashboard::PutNumber(
+				"Temperature", m_pdp.GetTemperature());
+	}
+
+private:
+	// Object for dealing with the Power Distribution Panel (PDP).
+	frc::PowerDistributionPanel m_pdp;
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Encoder/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Encoder/src/Robot.cpp
new file mode 100644
index 0000000..f31942f
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Encoder/src/Robot.cpp
@@ -0,0 +1,94 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <Encoder.h>
+#include <IterativeRobot.h>
+#include <SmartDashboard/SmartDashboard.h>
+
+/**
+ * Sample program displaying the value of a quadrature encoder on the
+ *   SmartDashboard.
+ * Quadrature Encoders are digital sensors which can detect the amount the
+ *   encoder has rotated since starting as well as the direction in which the
+ *   encoder shaft is rotating. However, encoders can not tell you the absolute
+ *   position of the encoder shaft (ie, it considers where it starts to be the
+ *   zero position, no matter where it starts), and so can only tell you how
+ *   much the encoder has rotated since starting.
+ * Depending on the precision of an encoder, it will have fewer or greater
+ *   ticks per revolution; the number of ticks per revolution will affect the
+ *   conversion between ticks and distance, as specified by DistancePerPulse.
+ * One of the most common uses of encoders is in the drivetrain, so that the
+ *   distance that the robot drives can be precisely controlled during the
+ *   autonomous mode.
+ */
+class Robot : public frc::IterativeRobot {
+public:
+	Robot() {
+		/* Defines the number of samples to average when determining the
+		 * rate.
+		 * On a quadrature encoder, values range from 1-255; larger
+		 * values
+		 *   result in smoother but potentially less accurate rates than
+		 * lower
+		 *   values.
+		 */
+		m_encoder.SetSamplesToAverage(5);
+
+		/* Defines how far the mechanism attached to the encoder moves
+		 * per pulse.
+		 * In this case, we assume that a 360 count encoder is directly
+		 * attached
+		 * to a 3 inch diameter (1.5inch radius) wheel, and that we want
+		 * to
+		 * measure distance in inches.
+		 */
+		m_encoder.SetDistancePerPulse(1.0 / 360.0 * 2.0 * 3.1415 * 1.5);
+
+		/* Defines the lowest rate at which the encoder will not be
+		 * considered
+		 *   stopped, for the purposes of the GetStopped() method.
+		 * Units are in distance / second, where distance refers to the
+		 * units
+		 *   of distance that you are using, in this case inches.
+		 */
+		m_encoder.SetMinRate(1.0);
+	}
+
+	void TeleopPeriodic() override {
+		// Retrieve the net displacement of the Encoder since the last
+		// Reset.
+		frc::SmartDashboard::PutNumber(
+				"Encoder Distance", m_encoder.GetDistance());
+
+		// Retrieve the current rate of the encoder.
+		frc::SmartDashboard::PutNumber(
+				"Encoder Rate", m_encoder.GetRate());
+	}
+
+private:
+	/**
+	 * The Encoder object is constructed with 4 parameters, the last two
+	 * being
+	 *   optional.
+	 * The first two parameters (1, 2 in this case) refer to the ports on
+	 * the
+	 *   roboRIO which the encoder uses. Because a quadrature encoder has
+	 *   two signal wires, the signal from two DIO ports on the roboRIO are
+	 * used.
+	 * The third (optional) parameter is a boolean which defaults to false.
+	 *   If you set this parameter to true, the direction of the encoder
+	 * will
+	 *   be reversed, in case it makes more sense mechanically.
+	 * The final (optional) parameter specifies encoding rate (k1X, k2X, or
+	 * k4X)
+	 *   and defaults to k4X. Faster (k4X) encoding gives greater positional
+	 *   precision but more noise in the rate.
+	 */
+	frc::Encoder m_encoder{1, 2, false, Encoder::k4X};
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Autonomous.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Autonomous.cpp
new file mode 100644
index 0000000..c6ce399
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Autonomous.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Autonomous.h"
+
+#include "CloseClaw.h"
+#include "DriveStraight.h"
+#include "Pickup.h"
+#include "Place.h"
+#include "PrepareToPickup.h"
+#include "SetDistanceToBox.h"
+#include "SetWristSetpoint.h"
+
+Autonomous::Autonomous()
+    : frc::CommandGroup("Autonomous") {
+	AddSequential(new PrepareToPickup());
+	AddSequential(new Pickup());
+	AddSequential(new SetDistanceToBox(0.10));
+	// AddSequential(new DriveStraight(4));  // Use Encoders if ultrasonic
+	// is broken
+	AddSequential(new Place());
+	AddSequential(new SetDistanceToBox(0.60));
+	// AddSequential(new DriveStraight(-2));  // Use Encoders if ultrasonic
+	// is broken
+	AddParallel(new SetWristSetpoint(-45));
+	AddSequential(new CloseClaw());
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Autonomous.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Autonomous.h
new file mode 100644
index 0000000..44bff14
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Autonomous.h
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/CommandGroup.h>
+
+/**
+ * The main autonomous command to pickup and deliver the soda to the box.
+ */
+class Autonomous : public frc::CommandGroup {
+public:
+	Autonomous();
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/CloseClaw.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/CloseClaw.cpp
new file mode 100644
index 0000000..732fc80
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/CloseClaw.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 "CloseClaw.h"
+
+#include "../Robot.h"
+
+CloseClaw::CloseClaw()
+    : frc::Command("CloseClaw") {
+	Requires(&Robot::claw);
+}
+
+// Called just before this Command runs the first time
+void CloseClaw::Initialize() {
+	Robot::claw.Close();
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool CloseClaw::IsFinished() {
+	return Robot::claw.IsGripping();
+}
+
+// Called once after isFinished returns true
+void CloseClaw::End() {
+// NOTE: Doesn't stop in simulation due to lower friction causing the can to
+// fall out
+// + there is no need to worry about stalling the motor or crushing the can.
+#ifndef SIMULATION
+	Robot::claw.Stop();
+#endif
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/CloseClaw.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/CloseClaw.h
new file mode 100644
index 0000000..350ddb8
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/CloseClaw.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+/**
+ * Opens the claw for one second. Real robots should use sensors, stalling
+ * motors is BAD!
+ */
+class CloseClaw : public frc::Command {
+public:
+	CloseClaw();
+	void Initialize() override;
+	bool IsFinished() override;
+	void End() override;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/DriveStraight.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/DriveStraight.cpp
new file mode 100644
index 0000000..cb4ea73
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/DriveStraight.cpp
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DriveStraight.h"
+
+#include "../Robot.h"
+
+DriveStraight::DriveStraight(double distance) {
+	Requires(&Robot::drivetrain);
+	m_pid.SetAbsoluteTolerance(0.01);
+	m_pid.SetSetpoint(distance);
+}
+
+// Called just before this Command runs the first time
+void DriveStraight::Initialize() {
+	// Get everything in a safe starting state.
+	Robot::drivetrain.Reset();
+	m_pid.Reset();
+	m_pid.Enable();
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool DriveStraight::IsFinished() {
+	return m_pid.OnTarget();
+}
+
+// Called once after isFinished returns true
+void DriveStraight::End() {
+	// Stop PID and the wheels
+	m_pid.Disable();
+	Robot::drivetrain.Drive(0, 0);
+}
+
+double DriveStraight::DriveStraightPIDSource::PIDGet() {
+	return Robot::drivetrain.GetDistance();
+}
+
+void DriveStraight::DriveStraightPIDOutput::PIDWrite(double d) {
+	Robot::drivetrain.Drive(d, d);
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/DriveStraight.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/DriveStraight.h
new file mode 100644
index 0000000..8cdfc84
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/DriveStraight.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+#include <PIDController.h>
+#include <PIDOutput.h>
+#include <PIDSource.h>
+
+/**
+ * Drive the given distance straight (negative values go backwards).
+ * Uses a local PID controller to run a simple PID loop that is only
+ * enabled while this command is running. The input is the averaged
+ * values of the left and right encoders.
+ */
+class DriveStraight : public frc::Command {
+public:
+	explicit DriveStraight(double distance);
+	void Initialize() override;
+	bool IsFinished() override;
+	void End() override;
+
+	class DriveStraightPIDSource : public frc::PIDSource {
+	public:
+		virtual ~DriveStraightPIDSource() = default;
+		double PIDGet() override;
+	};
+
+	class DriveStraightPIDOutput : public frc::PIDOutput {
+	public:
+		virtual ~DriveStraightPIDOutput() = default;
+		void PIDWrite(double d) override;
+	};
+
+private:
+	DriveStraightPIDSource m_source;
+	DriveStraightPIDOutput m_output;
+	frc::PIDController m_pid{4, 0, 0, &m_source, &m_output};
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/OpenClaw.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/OpenClaw.cpp
new file mode 100644
index 0000000..b522640
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/OpenClaw.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "OpenClaw.h"
+
+#include "../Robot.h"
+
+OpenClaw::OpenClaw()
+    : frc::Command("OpenClaw") {
+	Requires(&Robot::claw);
+	SetTimeout(1);
+}
+
+// Called just before this Command runs the first time
+void OpenClaw::Initialize() {
+	Robot::claw.Open();
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool OpenClaw::IsFinished() {
+	return IsTimedOut();
+}
+
+// Called once after isFinished returns true
+void OpenClaw::End() {
+	Robot::claw.Stop();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/OpenClaw.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/OpenClaw.h
new file mode 100644
index 0000000..3e0aa2f
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/OpenClaw.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+/**
+ * Opens the claw for one second. Real robots should use sensors, stalling
+ * motors is BAD!
+ */
+class OpenClaw : public frc::Command {
+public:
+	OpenClaw();
+	void Initialize() override;
+	bool IsFinished() override;
+	void End() override;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Pickup.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Pickup.cpp
new file mode 100644
index 0000000..aef208f
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Pickup.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Pickup.h"
+
+#include "CloseClaw.h"
+#include "SetElevatorSetpoint.h"
+#include "SetWristSetpoint.h"
+
+Pickup::Pickup()
+    : frc::CommandGroup("Pickup") {
+	AddSequential(new CloseClaw());
+	AddParallel(new SetWristSetpoint(-45));
+	AddSequential(new SetElevatorSetpoint(0.25));
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Pickup.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Pickup.h
new file mode 100644
index 0000000..f407690
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Pickup.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/CommandGroup.h>
+
+/**
+ * Pickup a soda can (if one is between the open claws) and
+ * get it in a safe state to drive around.
+ */
+class Pickup : public frc::CommandGroup {
+public:
+	Pickup();
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Place.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Place.cpp
new file mode 100644
index 0000000..d3dfedc
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Place.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Place.h"
+
+#include "OpenClaw.h"
+#include "SetElevatorSetpoint.h"
+#include "SetWristSetpoint.h"
+
+Place::Place()
+    : frc::CommandGroup("Place") {
+	AddSequential(new SetElevatorSetpoint(0.25));
+	AddSequential(new SetWristSetpoint(0));
+	AddSequential(new OpenClaw());
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Place.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Place.h
new file mode 100644
index 0000000..ceeb3e3
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/Place.h
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/CommandGroup.h>
+
+/**
+ * Place a held soda can onto the platform.
+ */
+class Place : public frc::CommandGroup {
+public:
+	Place();
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/PrepareToPickup.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/PrepareToPickup.cpp
new file mode 100644
index 0000000..c3d6781
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/PrepareToPickup.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "PrepareToPickup.h"
+
+#include "OpenClaw.h"
+#include "SetElevatorSetpoint.h"
+#include "SetWristSetpoint.h"
+
+PrepareToPickup::PrepareToPickup()
+    : frc::CommandGroup("PrepareToPickup") {
+	AddParallel(new OpenClaw());
+	AddParallel(new SetWristSetpoint(0));
+	AddSequential(new SetElevatorSetpoint(0));
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/PrepareToPickup.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/PrepareToPickup.h
new file mode 100644
index 0000000..13ac8b4
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/PrepareToPickup.h
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/CommandGroup.h>
+
+/**
+ * Make sure the robot is in a state to pickup soda cans.
+ */
+class PrepareToPickup : public frc::CommandGroup {
+public:
+	PrepareToPickup();
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetDistanceToBox.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetDistanceToBox.cpp
new file mode 100644
index 0000000..7ce503d
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetDistanceToBox.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SetDistanceToBox.h"
+
+#include <PIDController.h>
+
+#include "../Robot.h"
+
+SetDistanceToBox::SetDistanceToBox(double distance) {
+	Requires(&Robot::drivetrain);
+	m_pid.SetAbsoluteTolerance(0.01);
+	m_pid.SetSetpoint(distance);
+}
+
+// Called just before this Command runs the first time
+void SetDistanceToBox::Initialize() {
+	// Get everything in a safe starting state.
+	Robot::drivetrain.Reset();
+	m_pid.Reset();
+	m_pid.Enable();
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool SetDistanceToBox::IsFinished() {
+	return m_pid.OnTarget();
+}
+
+// Called once after isFinished returns true
+void SetDistanceToBox::End() {
+	// Stop PID and the wheels
+	m_pid.Disable();
+	Robot::drivetrain.Drive(0, 0);
+}
+
+double SetDistanceToBox::SetDistanceToBoxPIDSource::PIDGet() {
+	return Robot::drivetrain.GetDistanceToObstacle();
+}
+
+void SetDistanceToBox::SetDistanceToBoxPIDOutput::PIDWrite(double d) {
+	Robot::drivetrain.Drive(d, d);
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetDistanceToBox.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetDistanceToBox.h
new file mode 100644
index 0000000..7c0ce86
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetDistanceToBox.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+#include <PIDController.h>
+#include <PIDOutput.h>
+#include <PIDSource.h>
+
+/**
+ * Drive until the robot is the given distance away from the box. Uses a local
+ * PID controller to run a simple PID loop that is only enabled while this
+ * command is running. The input is the averaged values of the left and right
+ * encoders.
+ */
+class SetDistanceToBox : public frc::Command {
+public:
+	explicit SetDistanceToBox(double distance);
+	void Initialize() override;
+	bool IsFinished() override;
+	void End() override;
+
+	class SetDistanceToBoxPIDSource : public frc::PIDSource {
+	public:
+		virtual ~SetDistanceToBoxPIDSource() = default;
+		double PIDGet() override;
+	};
+
+	class SetDistanceToBoxPIDOutput : public frc::PIDOutput {
+	public:
+		virtual ~SetDistanceToBoxPIDOutput() = default;
+		void PIDWrite(double d) override;
+	};
+
+private:
+	SetDistanceToBoxPIDSource m_source;
+	SetDistanceToBoxPIDOutput m_output;
+	frc::PIDController m_pid{-2, 0, 0, &m_source, &m_output};
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetElevatorSetpoint.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetElevatorSetpoint.cpp
new file mode 100644
index 0000000..daef19c
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetElevatorSetpoint.cpp
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SetElevatorSetpoint.h"
+
+#include <cmath>
+
+#include "../Robot.h"
+
+SetElevatorSetpoint::SetElevatorSetpoint(double setpoint)
+    : frc::Command("SetElevatorSetpoint") {
+	m_setpoint = setpoint;
+	Requires(&Robot::elevator);
+}
+
+// Called just before this Command runs the first time
+void SetElevatorSetpoint::Initialize() {
+	Robot::elevator.SetSetpoint(m_setpoint);
+	Robot::elevator.Enable();
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool SetElevatorSetpoint::IsFinished() {
+	return Robot::elevator.OnTarget();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetElevatorSetpoint.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetElevatorSetpoint.h
new file mode 100644
index 0000000..494d104
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetElevatorSetpoint.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+/**
+ * Move the elevator to a given location. This command finishes when it is
+ * within
+ * the tolerance, but leaves the PID loop running to maintain the position.
+ * Other
+ * commands using the elevator should make sure they disable PID!
+ */
+class SetElevatorSetpoint : public frc::Command {
+public:
+	explicit SetElevatorSetpoint(double setpoint);
+	void Initialize() override;
+	bool IsFinished() override;
+
+private:
+	double m_setpoint;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetWristSetpoint.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetWristSetpoint.cpp
new file mode 100644
index 0000000..be8da58
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetWristSetpoint.cpp
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SetWristSetpoint.h"
+
+#include "../Robot.h"
+
+SetWristSetpoint::SetWristSetpoint(double setpoint)
+    : frc::Command("SetWristSetpoint") {
+	m_setpoint = setpoint;
+	Requires(&Robot::wrist);
+}
+
+// Called just before this Command runs the first time
+void SetWristSetpoint::Initialize() {
+	Robot::wrist.SetSetpoint(m_setpoint);
+	Robot::wrist.Enable();
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool SetWristSetpoint::IsFinished() {
+	return Robot::wrist.OnTarget();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetWristSetpoint.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetWristSetpoint.h
new file mode 100644
index 0000000..ccc698a
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/SetWristSetpoint.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+/**
+ * Move the wrist to a given angle. This command finishes when it is within
+ * the tolerance, but leaves the PID loop running to maintain the position.
+ * Other commands using the wrist should make sure they disable PID!
+ */
+class SetWristSetpoint : public frc::Command {
+public:
+	explicit SetWristSetpoint(double setpoint);
+	void Initialize() override;
+	bool IsFinished() override;
+
+private:
+	double m_setpoint;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/TankDriveWithJoystick.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/TankDriveWithJoystick.cpp
new file mode 100644
index 0000000..e0a22dc
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/TankDriveWithJoystick.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "TankDriveWithJoystick.h"
+
+#include "../Robot.h"
+
+TankDriveWithJoystick::TankDriveWithJoystick()
+    : frc::Command("TankDriveWithJoystick") {
+	Requires(&Robot::drivetrain);
+}
+
+// Called repeatedly when this Command is scheduled to run
+void TankDriveWithJoystick::Execute() {
+	auto& joystick = Robot::oi.GetJoystick();
+	Robot::drivetrain.Drive(-joystick.GetY(), -joystick.GetRawAxis(4));
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool TankDriveWithJoystick::IsFinished() {
+	return false;
+}
+
+// Called once after isFinished returns true
+void TankDriveWithJoystick::End() {
+	Robot::drivetrain.Drive(0, 0);
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/TankDriveWithJoystick.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/TankDriveWithJoystick.h
new file mode 100644
index 0000000..4beae78
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Commands/TankDriveWithJoystick.h
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+/**
+ * Have the robot drive tank style using the PS3 Joystick until interrupted.
+ */
+class TankDriveWithJoystick : public frc::Command {
+public:
+	TankDriveWithJoystick();
+	void Execute() override;
+	bool IsFinished() override;
+	void End() override;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/OI.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/OI.cpp
new file mode 100644
index 0000000..34906a8
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/OI.cpp
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "OI.h"
+
+#include <SmartDashboard/SmartDashboard.h>
+
+#include "Commands/Autonomous.h"
+#include "Commands/CloseClaw.h"
+#include "Commands/OpenClaw.h"
+#include "Commands/Pickup.h"
+#include "Commands/Place.h"
+#include "Commands/PrepareToPickup.h"
+#include "Commands/SetElevatorSetpoint.h"
+
+OI::OI() {
+	frc::SmartDashboard::PutData("Open Claw", new OpenClaw());
+	frc::SmartDashboard::PutData("Close Claw", new CloseClaw());
+
+	// Connect the buttons to commands
+	m_dUp.WhenPressed(new SetElevatorSetpoint(0.2));
+	m_dDown.WhenPressed(new SetElevatorSetpoint(-0.2));
+	m_dRight.WhenPressed(new CloseClaw());
+	m_dLeft.WhenPressed(new OpenClaw());
+
+	m_r1.WhenPressed(new PrepareToPickup());
+	m_r2.WhenPressed(new Pickup());
+	m_l1.WhenPressed(new Place());
+	m_l2.WhenPressed(new Autonomous());
+}
+
+frc::Joystick& OI::GetJoystick() {
+	return m_joy;
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/OI.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/OI.h
new file mode 100644
index 0000000..a63e570
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/OI.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Buttons/JoystickButton.h>
+#include <Joystick.h>
+
+class OI {
+public:
+	OI();
+	frc::Joystick& GetJoystick();
+
+private:
+	frc::Joystick m_joy{0};
+
+	// Create some buttons
+	frc::JoystickButton m_dUp{&m_joy, 5};
+	frc::JoystickButton m_dRight{&m_joy, 6};
+	frc::JoystickButton m_dDown{&m_joy, 7};
+	frc::JoystickButton m_dLeft{&m_joy, 8};
+	frc::JoystickButton m_l2{&m_joy, 9};
+	frc::JoystickButton m_r2{&m_joy, 10};
+	frc::JoystickButton m_l1{&m_joy, 11};
+	frc::JoystickButton m_r1{&m_joy, 12};
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Robot.cpp
new file mode 100644
index 0000000..bce1f71
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Robot.cpp
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Robot.h"
+
+#include <iostream>
+
+DriveTrain Robot::drivetrain;
+Elevator Robot::elevator;
+Wrist Robot::wrist;
+Claw Robot::claw;
+OI Robot::oi;
+
+void Robot::RobotInit() {
+	// Show what command your subsystem is running on the SmartDashboard
+	frc::SmartDashboard::PutData(&drivetrain);
+	frc::SmartDashboard::PutData(&elevator);
+	frc::SmartDashboard::PutData(&wrist);
+	frc::SmartDashboard::PutData(&claw);
+}
+
+void Robot::AutonomousInit() {
+	m_autonomousCommand.Start();
+	std::cout << "Starting Auto" << std::endl;
+}
+
+void Robot::AutonomousPeriodic() {
+	frc::Scheduler::GetInstance()->Run();
+}
+
+void Robot::TeleopInit() {
+	// This makes sure that the autonomous stops running when
+	// teleop starts running. If you want the autonomous to
+	// continue until interrupted by another command, remove
+	// this line or comment it out.
+	m_autonomousCommand.Cancel();
+	std::cout << "Starting Teleop" << std::endl;
+}
+
+void Robot::TeleopPeriodic() {
+	frc::Scheduler::GetInstance()->Run();
+}
+
+void Robot::TestPeriodic() {}
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Robot.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Robot.h
new file mode 100644
index 0000000..65fd2e8
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Robot.h
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+#include <Commands/Scheduler.h>
+#include <IterativeRobot.h>
+#include <LiveWindow/LiveWindow.h>
+#include <SmartDashboard/SmartDashboard.h>
+
+#include "Commands/Autonomous.h"
+#include "OI.h"
+#include "Subsystems/Claw.h"
+#include "Subsystems/DriveTrain.h"
+#include "Subsystems/Elevator.h"
+#include "Subsystems/Wrist.h"
+
+class Robot : public frc::IterativeRobot {
+public:
+	static DriveTrain drivetrain;
+	static Elevator elevator;
+	static Wrist wrist;
+	static Claw claw;
+	static OI oi;
+
+private:
+	Autonomous m_autonomousCommand;
+	frc::LiveWindow& m_lw = *frc::LiveWindow::GetInstance();
+
+	void RobotInit() override;
+	void AutonomousInit() override;
+	void AutonomousPeriodic() override;
+	void TeleopInit() override;
+	void TeleopPeriodic() override;
+	void TestPeriodic() override;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Claw.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Claw.cpp
new file mode 100644
index 0000000..768d0d3
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Claw.cpp
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Claw.h"
+
+Claw::Claw()
+    : frc::Subsystem("Claw") {
+	// Let's show everything on the LiveWindow
+	AddChild("Motor", m_motor);
+}
+
+void Claw::InitDefaultCommand() {}
+
+void Claw::Open() {
+	m_motor.Set(-1);
+}
+
+void Claw::Close() {
+	m_motor.Set(1);
+}
+
+void Claw::Stop() {
+	m_motor.Set(0);
+}
+
+bool Claw::IsGripping() {
+	return m_contact.Get();
+}
+
+void Claw::Log() {}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Claw.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Claw.h
new file mode 100644
index 0000000..6d4b264
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Claw.h
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Subsystem.h>
+#include <DigitalInput.h>
+#include <Spark.h>
+
+/**
+ * The claw subsystem is a simple system with a motor for opening and closing.
+ * If using stronger motors, you should probably use a sensor so that the
+ * motors don't stall.
+ */
+class Claw : public frc::Subsystem {
+public:
+	Claw();
+
+	void InitDefaultCommand() override;
+
+	/**
+	 * Set the claw motor to move in the open direction.
+	 */
+	void Open();
+
+	/**
+	 * Set the claw motor to move in the close direction.
+	 */
+	void Close();
+
+	/**
+	 * Stops the claw motor from moving.
+	 */
+	void Stop();
+
+	/**
+	 * Return true when the robot is grabbing an object hard enough
+	 * to trigger the limit switch.
+	 */
+	bool IsGripping();
+
+	void Log();
+
+private:
+	frc::Spark m_motor{7};
+	frc::DigitalInput m_contact{5};
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/DriveTrain.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/DriveTrain.cpp
new file mode 100644
index 0000000..a732782
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/DriveTrain.cpp
@@ -0,0 +1,87 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DriveTrain.h"
+
+#include <Joystick.h>
+#include <SmartDashboard/SmartDashboard.h>
+
+#include "../Commands/TankDriveWithJoystick.h"
+
+DriveTrain::DriveTrain()
+    : frc::Subsystem("DriveTrain") {
+// Encoders may measure differently in the real world and in
+// simulation. In this example the robot moves 0.042 barleycorns
+// per tick in the real world, but the simulated encoders
+// simulate 360 tick encoders. This if statement allows for the
+// real robot to handle this difference in devices.
+#ifndef SIMULATION
+	m_leftEncoder.SetDistancePerPulse(0.042);
+	m_rightEncoder.SetDistancePerPulse(0.042);
+#else
+	// Circumference in ft = 4in/12(in/ft)*PI
+	m_leftEncoder.SetDistancePerPulse(
+			static_cast<double>(4.0 / 12.0 * M_PI) / 360.0);
+	m_rightEncoder.SetDistancePerPulse(
+			static_cast<double>(4.0 / 12.0 * M_PI) / 360.0);
+#endif
+
+	// Let's show everything on the LiveWindow
+	// AddChild("Front_Left Motor", m_frontLeft);
+	// AddChild("Rear Left Motor", m_rearLeft);
+	// AddChild("Front Right Motor", m_frontRight);
+	// AddChild("Rear Right Motor", m_rearRight);
+	AddChild("Left Encoder", m_leftEncoder);
+	AddChild("Right Encoder", m_rightEncoder);
+	AddChild("Rangefinder", m_rangefinder);
+	AddChild("Gyro", m_gyro);
+}
+
+/**
+ * When no other command is running let the operator drive around
+ * using the PS3 joystick.
+ */
+void DriveTrain::InitDefaultCommand() {
+	SetDefaultCommand(new TankDriveWithJoystick());
+}
+
+/**
+ * The log method puts interesting information to the SmartDashboard.
+ */
+void DriveTrain::Log() {
+	frc::SmartDashboard::PutNumber(
+			"Left Distance", m_leftEncoder.GetDistance());
+	frc::SmartDashboard::PutNumber(
+			"Right Distance", m_rightEncoder.GetDistance());
+	frc::SmartDashboard::PutNumber("Left Speed", m_leftEncoder.GetRate());
+	frc::SmartDashboard::PutNumber("Right Speed", m_rightEncoder.GetRate());
+	frc::SmartDashboard::PutNumber("Gyro", m_gyro.GetAngle());
+}
+
+void DriveTrain::Drive(double left, double right) {
+	m_robotDrive.TankDrive(left, right);
+}
+
+double DriveTrain::GetHeading() {
+	return m_gyro.GetAngle();
+}
+
+void DriveTrain::Reset() {
+	m_gyro.Reset();
+	m_leftEncoder.Reset();
+	m_rightEncoder.Reset();
+}
+
+double DriveTrain::GetDistance() {
+	return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance())
+	       / 2.0;
+}
+
+double DriveTrain::GetDistanceToObstacle() {
+	// Really meters in simulation since it's a rangefinder...
+	return m_rangefinder.GetAverageVoltage();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/DriveTrain.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/DriveTrain.h
new file mode 100644
index 0000000..9b02849
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/DriveTrain.h
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <AnalogGyro.h>
+#include <AnalogInput.h>
+#include <Commands/Subsystem.h>
+#include <Drive/DifferentialDrive.h>
+#include <Encoder.h>
+#include <Spark.h>
+#include <SpeedControllerGroup.h>
+
+namespace frc {
+class Joystick;
+}  // namespace frc
+
+/**
+ * The DriveTrain subsystem incorporates the sensors and actuators attached to
+ * the robots chassis. These include four drive motors, a left and right encoder
+ * and a gyro.
+ */
+class DriveTrain : public frc::Subsystem {
+public:
+	DriveTrain();
+
+	/**
+	 * When no other command is running let the operator drive around
+	 * using the PS3 joystick.
+	 */
+	void InitDefaultCommand() override;
+
+	/**
+	 * The log method puts interesting information to the SmartDashboard.
+	 */
+	void Log();
+
+	/**
+	 * Tank style driving for the DriveTrain.
+	 * @param left Speed in range [-1,1]
+	 * @param right Speed in range [-1,1]
+	 */
+	void Drive(double left, double right);
+
+	/**
+	 * @return The robots heading in degrees.
+	 */
+	double GetHeading();
+
+	/**
+	 * Reset the robots sensors to the zero states.
+	 */
+	void Reset();
+
+	/**
+	 * @return The distance driven (average of left and right encoders).
+	 */
+	double GetDistance();
+
+	/**
+	 * @return The distance to the obstacle detected by the rangefinder.
+	 */
+	double GetDistanceToObstacle();
+
+private:
+	frc::Spark m_frontLeft{1};
+	frc::Spark m_rearLeft{2};
+	frc::SpeedControllerGroup m_left{m_frontLeft, m_rearLeft};
+
+	frc::Spark m_frontRight{3};
+	frc::Spark m_rearRight{4};
+	frc::SpeedControllerGroup m_right{m_frontRight, m_rearRight};
+
+	frc::DifferentialDrive m_robotDrive{m_left, m_right};
+
+	frc::Encoder m_leftEncoder{1, 2};
+	frc::Encoder m_rightEncoder{3, 4};
+	frc::AnalogInput m_rangefinder{6};
+	frc::AnalogGyro m_gyro{1};
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Elevator.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Elevator.cpp
new file mode 100644
index 0000000..4ff59e3
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Elevator.cpp
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Elevator.h"
+
+#include <LiveWindow/LiveWindow.h>
+#include <SmartDashboard/SmartDashboard.h>
+
+Elevator::Elevator()
+    : frc::PIDSubsystem("Elevator", kP_real, kI_real, 0.0) {
+#ifdef SIMULATION  // Check for simulation and update PID values
+	GetPIDController()->SetPID(kP_simulation, kI_simulation, 0, 0);
+#endif
+	SetAbsoluteTolerance(0.005);
+
+	// Let's show everything on the LiveWindow
+	AddChild("Motor", m_motor);
+	AddChild("Pot", &m_pot);
+}
+
+void Elevator::InitDefaultCommand() {}
+
+void Elevator::Log() {
+	// frc::SmartDashboard::PutData("Wrist Pot", &m_pot);
+}
+
+double Elevator::ReturnPIDInput() {
+	return m_pot.Get();
+}
+
+void Elevator::UsePIDOutput(double d) {
+	m_motor.Set(d);
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Elevator.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Elevator.h
new file mode 100644
index 0000000..a77bd0e
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Elevator.h
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <AnalogPotentiometer.h>
+#include <Commands/PIDSubsystem.h>
+#include <Spark.h>
+
+/**
+ * The elevator subsystem uses PID to go to a given height. Unfortunately, in
+ * it's current
+ * state PID values for simulation are different than in the real world do to
+ * minor differences.
+ */
+class Elevator : public frc::PIDSubsystem {
+public:
+	Elevator();
+
+	void InitDefaultCommand() override;
+
+	/**
+	 * The log method puts interesting information to the SmartDashboard.
+	 */
+	void Log();
+
+	/**
+	 * Use the potentiometer as the PID sensor. This method is automatically
+	 * called by the subsystem.
+	 */
+	double ReturnPIDInput();
+
+	/**
+	 * Use the motor as the PID output. This method is automatically called
+	 * by
+	 * the subsystem.
+	 */
+	void UsePIDOutput(double d);
+
+private:
+	frc::Spark m_motor{5};
+
+// Conversion value of potentiometer varies between the real world and
+// simulation
+#ifndef SIMULATION
+	frc::AnalogPotentiometer m_pot{2, -2.0 / 5};
+#else
+	frc::AnalogPotentiometer m_pot{2};  // Defaults to meters
+#endif
+
+	static constexpr double kP_real = 4;
+	static constexpr double kI_real = 0.07;
+	static constexpr double kP_simulation = 18;
+	static constexpr double kI_simulation = 0.2;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Wrist.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Wrist.cpp
new file mode 100644
index 0000000..b1be1dc
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Wrist.cpp
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Wrist.h"
+
+#include <SmartDashboard/SmartDashboard.h>
+
+Wrist::Wrist()
+    : frc::PIDSubsystem("Wrist", kP_real, 0.0, 0.0) {
+#ifdef SIMULATION  // Check for simulation and update PID values
+	GetPIDController()->SetPID(kP_simulation, 0, 0, 0);
+#endif
+	SetAbsoluteTolerance(2.5);
+
+	// Let's show everything on the LiveWindow
+	AddChild("Motor", m_motor);
+	AddChild("Pot", m_pot);
+}
+
+void Wrist::InitDefaultCommand() {}
+
+void Wrist::Log() {
+	// frc::SmartDashboard::PutData("Wrist Angle", &m_pot);
+}
+
+double Wrist::ReturnPIDInput() {
+	return m_pot.Get();
+}
+
+void Wrist::UsePIDOutput(double d) {
+	m_motor.Set(d);
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Wrist.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Wrist.h
new file mode 100644
index 0000000..2cd5a64
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GearsBot/src/Subsystems/Wrist.h
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <AnalogPotentiometer.h>
+#include <Commands/PIDSubsystem.h>
+#include <Spark.h>
+
+/**
+ * The wrist subsystem is like the elevator, but with a rotational joint instead
+ * of a linear joint.
+ */
+class Wrist : public PIDSubsystem {
+public:
+	Wrist();
+
+	void InitDefaultCommand() override;
+
+	/**
+	 * The log method puts interesting information to the SmartDashboard.
+	 */
+	void Log();
+
+	/**
+	 * Use the potentiometer as the PID sensor. This method is automatically
+	 * called by the subsystem.
+	 */
+	double ReturnPIDInput() override;
+
+	/**
+	 * Use the motor as the PID output. This method is automatically called
+	 * by
+	 * the subsystem.
+	 */
+	void UsePIDOutput(double d) override;
+
+private:
+	frc::Spark m_motor{6};
+
+// Conversion value of potentiometer varies between the real world and
+// simulation
+#ifndef SIMULATION
+	frc::AnalogPotentiometer m_pot{3, -270.0 / 5};
+#else
+	frc::AnalogPotentiometer m_pot{3};  // Defaults to degrees
+#endif
+
+	static constexpr double kP_real = 1;
+	static constexpr double kP_simulation = 0.05;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GettingStarted/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GettingStarted/src/Robot.cpp
new file mode 100644
index 0000000..e0bebe5
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GettingStarted/src/Robot.cpp
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <Drive/DifferentialDrive.h>
+#include <IterativeRobot.h>
+#include <Joystick.h>
+#include <LiveWindow/LiveWindow.h>
+#include <Spark.h>
+#include <Timer.h>
+
+class Robot : public frc::IterativeRobot {
+public:
+	Robot() {
+		m_robotDrive.SetExpiration(0.1);
+		m_timer.Start();
+	}
+
+	void AutonomousInit() override {
+		m_timer.Reset();
+		m_timer.Start();
+	}
+
+	void AutonomousPeriodic() override {
+		// Drive for 2 seconds
+		if (m_timer.Get() < 2.0) {
+			// Drive forwards half speed
+			m_robotDrive.ArcadeDrive(-0.5, 0.0);
+		} else {
+			// Stop robot
+			m_robotDrive.ArcadeDrive(0.0, 0.0);
+		}
+	}
+
+	void TeleopInit() override {}
+
+	void TeleopPeriodic() override {
+		// Drive with arcade style (use right stick)
+		m_robotDrive.ArcadeDrive(m_stick.GetY(), m_stick.GetX());
+	}
+
+	void TestPeriodic() override {}
+
+private:
+	// Robot drive system
+	frc::Spark m_left{0};
+	frc::Spark m_right{1};
+	frc::DifferentialDrive m_robotDrive{m_left, m_right};
+
+	frc::Joystick m_stick{0};
+	frc::LiveWindow& m_lw = *frc::LiveWindow::GetInstance();
+	frc::Timer m_timer;
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Gyro/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Gyro/src/Robot.cpp
new file mode 100644
index 0000000..b67ea86
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Gyro/src/Robot.cpp
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <cmath>
+
+#include <AnalogGyro.h>
+#include <Drive/DifferentialDrive.h>
+#include <IterativeRobot.h>
+#include <Joystick.h>
+#include <Spark.h>
+
+/**
+ * This is a sample program to demonstrate how to use a gyro sensor to make a
+ * robot drive straight. This program uses a joystick to drive forwards and
+ * backwards while the gyro is used for direction keeping.
+ */
+class Robot : public frc::IterativeRobot {
+public:
+	void RobotInit() override {
+		m_gyro.SetSensitivity(kVoltsPerDegreePerSecond);
+	}
+
+	/**
+	 * The motor speed is set from the joystick while the DifferentialDrive
+	 * turning value is assigned from the error between the setpoint and the
+	 * gyro angle.
+	 */
+	void TeleopPeriodic() override {
+		double turningValue = (kAngleSetpoint - m_gyro.GetAngle()) * kP;
+		// Invert the direction of the turn if we are going backwards
+		turningValue = std::copysign(turningValue, m_joystick.GetY());
+		m_robotDrive.ArcadeDrive(m_joystick.GetY(), turningValue);
+	}
+
+private:
+	static constexpr double kAngleSetpoint = 0.0;
+	static constexpr double kP = 0.005;  // Proportional turning constant
+
+	// Gyro calibration constant, may need to be adjusted
+	// Gyro value of 360 is set to correspond to one full revolution
+	static constexpr double kVoltsPerDegreePerSecond = 0.0128;
+
+	static constexpr int kLeftMotorPort = 0;
+	static constexpr int kRightMotorPort = 1;
+	static constexpr int kGyroPort = 0;
+	static constexpr int kJoystickPort = 0;
+
+	frc::Spark m_left{kLeftMotorPort};
+	frc::Spark m_right{kRightMotorPort};
+	frc::DifferentialDrive m_robotDrive{m_left, m_right};
+
+	frc::AnalogGyro m_gyro{kGyroPort};
+	frc::Joystick m_joystick{kJoystickPort};
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GyroMecanum/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GyroMecanum/src/Robot.cpp
new file mode 100644
index 0000000..47ae63a
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/GyroMecanum/src/Robot.cpp
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <AnalogGyro.h>
+#include <Drive/MecanumDrive.h>
+#include <IterativeRobot.h>
+#include <Joystick.h>
+#include <Spark.h>
+
+/**
+ * This is a sample program that uses mecanum drive with a gyro sensor to
+ * maintian rotation vectorsin relation to the starting orientation of the robot
+ * (field-oriented controls).
+ */
+class Robot : public frc::IterativeRobot {
+public:
+	void RobotInit() override {
+		// invert the left side motors
+		// you may need to change or remove this to match your robot
+		m_frontLeft.SetInverted(true);
+		m_rearLeft.SetInverted(true);
+
+		m_gyro.SetSensitivity(kVoltsPerDegreePerSecond);
+	}
+
+	/**
+	 * Mecanum drive is used with the gyro angle as an input.
+	 */
+	void TeleopPeriodic() override {
+		m_robotDrive.DriveCartesian(m_joystick.GetX(),
+				m_joystick.GetY(), m_joystick.GetZ(),
+				m_gyro.GetAngle());
+	}
+
+private:
+	// Gyro calibration constant, may need to be adjusted
+	// Gyro value of 360 is set to correspond to one full revolution
+	static constexpr double kVoltsPerDegreePerSecond = 0.0128;
+
+	static constexpr int kFrontLeftMotorPort = 0;
+	static constexpr int kRearLeftMotorPort = 1;
+	static constexpr int kFrontRightMotorPort = 2;
+	static constexpr int kRearRightMotorPort = 3;
+	static constexpr int kGyroPort = 0;
+	static constexpr int kJoystickPort = 0;
+
+	frc::Spark m_frontLeft{kFrontLeftMotorPort};
+	frc::Spark m_rearLeft{kRearLeftMotorPort};
+	frc::Spark m_frontRight{kFrontRightMotorPort};
+	frc::Spark m_rearRight{kRearRightMotorPort};
+	frc::MecanumDrive m_robotDrive{
+			m_frontLeft, m_rearLeft, m_frontRight, m_rearRight};
+
+	frc::AnalogGyro m_gyro{kGyroPort};
+	frc::Joystick m_joystick{kJoystickPort};
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/IntermediateVision/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/IntermediateVision/src/Robot.cpp
new file mode 100644
index 0000000..808574d
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/IntermediateVision/src/Robot.cpp
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <thread>
+
+#include <CameraServer.h>
+#include <IterativeRobot.h>
+#include <opencv2/core/core.hpp>
+#include <opencv2/core/types.hpp>
+#include <opencv2/imgproc/imgproc.hpp>
+
+/**
+ * This is a demo program showing the use of OpenCV to do vision processing. The
+ * image is acquired from the USB camera, then a rectangle is put on the image
+ * and
+ * sent to the dashboard. OpenCV has many methods for different types of
+ * processing.
+ */
+class Robot : public frc::IterativeRobot {
+private:
+	static void VisionThread() {
+		// Get the USB camera from CameraServer
+		cs::UsbCamera camera =
+				CameraServer::GetInstance()
+						->StartAutomaticCapture();
+		// Set the resolution
+		camera.SetResolution(640, 480);
+
+		// Get a CvSink. This will capture Mats from the Camera
+		cs::CvSink cvSink = CameraServer::GetInstance()->GetVideo();
+		// Setup a CvSource. This will send images back to the Dashboard
+		cs::CvSource outputStream =
+				CameraServer::GetInstance()->PutVideo(
+						"Rectangle", 640, 480);
+
+		// Mats are very memory expensive. Lets reuse this Mat.
+		cv::Mat mat;
+
+		while (true) {
+			// Tell the CvSink to grab a frame from the camera and
+			// put it
+			// in the source mat.  If there is an error notify the
+			// output.
+			if (cvSink.GrabFrame(mat) == 0) {
+				// Send the output the error.
+				outputStream.NotifyError(cvSink.GetError());
+				// skip the rest of the current iteration
+				continue;
+			}
+			// Put a rectangle on the image
+			rectangle(mat, cv::Point(100, 100), cv::Point(400, 400),
+					cv::Scalar(255, 255, 255), 5);
+			// Give the output stream a new image to display
+			outputStream.PutFrame(mat);
+		}
+	}
+
+	void RobotInit() {
+		// We need to run our vision program in a separate Thread.
+		// If not, our robot program will not run
+		std::thread visionThread(VisionThread);
+		visionThread.detach();
+	}
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/MecanumDrive/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/MecanumDrive/src/Robot.cpp
new file mode 100644
index 0000000..6eb1a89
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/MecanumDrive/src/Robot.cpp
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <Drive/MecanumDrive.h>
+#include <IterativeRobot.h>
+#include <Joystick.h>
+#include <Spark.h>
+
+/**
+ * This is a demo program showing how to use Mecanum control with the
+ * MecanumDrive class.
+ */
+class Robot : public frc::IterativeRobot {
+public:
+	void RobotInit() {
+		// Invert the left side motors
+		// You may need to change or remove this to match your robot
+		m_frontLeft.SetInverted(true);
+		m_rearLeft.SetInverted(true);
+	}
+
+	void TeleopPeriodic() override {
+		/* Use the joystick X axis for lateral movement, Y axis for
+		 * forward
+		 * movement, and Z axis for rotation.
+		 */
+		m_robotDrive.DriveCartesian(
+				m_stick.GetX(), m_stick.GetY(), m_stick.GetZ());
+	}
+
+private:
+	static constexpr int kFrontLeftChannel = 0;
+	static constexpr int kRearLeftChannel = 1;
+	static constexpr int kFrontRightChannel = 2;
+	static constexpr int kRearRightChannel = 3;
+
+	static constexpr int kJoystickChannel = 0;
+
+	frc::Spark m_frontLeft{kFrontLeftChannel};
+	frc::Spark m_rearLeft{kRearLeftChannel};
+	frc::Spark m_frontRight{kFrontRightChannel};
+	frc::Spark m_rearRight{kRearRightChannel};
+	frc::MecanumDrive m_robotDrive{
+			m_frontLeft, m_rearLeft, m_frontRight, m_rearRight};
+
+	frc::Joystick m_stick{kJoystickChannel};
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/MotorControl/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/MotorControl/src/Robot.cpp
new file mode 100644
index 0000000..7247fae
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/MotorControl/src/Robot.cpp
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <IterativeRobot.h>
+#include <Joystick.h>
+#include <Spark.h>
+
+/**
+ * This sample program shows how to control a motor using a joystick. In the
+ * operator control part of the program, the joystick is read and the value is
+ * written to the motor.
+ *
+ * Joystick analog values range from -1 to 1 and speed controller inputs as
+ * range from -1 to 1 making it easy to work together.
+ */
+class Robot : public frc::IterativeRobot {
+public:
+	void TeleopPeriodic() override { m_motor.Set(m_stick.GetY()); }
+
+private:
+	frc::Joystick m_stick{0};
+	frc::Spark m_motor{0};
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/CheckForHotGoal.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/CheckForHotGoal.cpp
new file mode 100644
index 0000000..54fd249
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/CheckForHotGoal.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "CheckForHotGoal.h"
+
+#include "../Robot.h"
+
+CheckForHotGoal::CheckForHotGoal(double time) {
+	SetTimeout(time);
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool CheckForHotGoal::IsFinished() {
+	return IsTimedOut() || Robot::shooter.GoalIsHot();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/CheckForHotGoal.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/CheckForHotGoal.h
new file mode 100644
index 0000000..7f67990
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/CheckForHotGoal.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+/**
+ * This command looks for the hot goal and waits until it's detected or timed
+ * out. The timeout is because it's better to shoot and get some autonomous
+ * points than get none. When called sequentially, this command will block until
+ * the hot goal is detected or until it is timed out.
+ */
+class CheckForHotGoal : public frc::Command {
+public:
+	explicit CheckForHotGoal(double time);
+	bool IsFinished() override;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/CloseClaw.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/CloseClaw.cpp
new file mode 100644
index 0000000..8305521
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/CloseClaw.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "CloseClaw.h"
+
+#include "../Robot.h"
+
+CloseClaw::CloseClaw() {
+	Requires(&Robot::collector);
+}
+
+// Called just before this Command runs the first time
+void CloseClaw::Initialize() {
+	Robot::collector.Close();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/CloseClaw.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/CloseClaw.h
new file mode 100644
index 0000000..0e3edac
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/CloseClaw.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/InstantCommand.h>
+
+/**
+ * Close the claw.
+ *
+ * NOTE: It doesn't wait for the claw to close since there is no sensor to
+ * detect that.
+ */
+class CloseClaw : public frc::InstantCommand {
+public:
+	CloseClaw();
+	void Initialize() override;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/Collect.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/Collect.cpp
new file mode 100644
index 0000000..1c22657
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/Collect.cpp
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Collect.h"
+
+#include "../Robot.h"
+#include "CloseClaw.h"
+#include "SetCollectionSpeed.h"
+#include "SetPivotSetpoint.h"
+#include "WaitForBall.h"
+
+Collect::Collect() {
+	AddSequential(new SetCollectionSpeed(Collector::kForward));
+	AddParallel(new CloseClaw());
+	AddSequential(new SetPivotSetpoint(Pivot::kCollect));
+	AddSequential(new WaitForBall());
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/Collect.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/Collect.h
new file mode 100644
index 0000000..496a65f
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/Collect.h
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/CommandGroup.h>
+
+/**
+ * Get the robot set to collect balls.
+ */
+class Collect : public frc::CommandGroup {
+public:
+	Collect();
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveAndShootAutonomous.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveAndShootAutonomous.cpp
new file mode 100644
index 0000000..2b9341b
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveAndShootAutonomous.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DriveAndShootAutonomous.h"
+
+#include "../Robot.h"
+#include "CheckForHotGoal.h"
+#include "CloseClaw.h"
+#include "DriveForward.h"
+#include "SetPivotSetpoint.h"
+#include "Shoot.h"
+#include "WaitForPressure.h"
+
+DriveAndShootAutonomous::DriveAndShootAutonomous() {
+	AddSequential(new CloseClaw());
+	AddSequential(new WaitForPressure(), 2);
+#ifndef SIMULATION
+	// NOTE: Simulation doesn't currently have the concept of hot.
+	AddSequential(new CheckForHotGoal(2));
+#endif
+	AddSequential(new SetPivotSetpoint(45));
+	AddSequential(new DriveForward(8, 0.3));
+	AddSequential(new Shoot());
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveAndShootAutonomous.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveAndShootAutonomous.h
new file mode 100644
index 0000000..0df3975
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveAndShootAutonomous.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/CommandGroup.h>
+
+/**
+ * Drive over the line and then shoot the ball. If the hot goal is not detected,
+ * it will wait briefly.
+ */
+class DriveAndShootAutonomous : public frc::CommandGroup {
+public:
+	DriveAndShootAutonomous();
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveForward.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveForward.cpp
new file mode 100644
index 0000000..a0d4442
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveForward.cpp
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DriveForward.h"
+
+#include <cmath>
+
+#include "../Robot.h"
+
+void DriveForward::init(double dist, double maxSpeed) {
+	Requires(&Robot::drivetrain);
+	m_distance = dist;
+	m_driveForwardSpeed = maxSpeed;
+}
+
+DriveForward::DriveForward() {
+	init(10, 0.5);
+}
+
+DriveForward::DriveForward(double dist) {
+	init(dist, 0.5);
+}
+
+DriveForward::DriveForward(double dist, double maxSpeed) {
+	init(dist, maxSpeed);
+}
+
+// Called just before this Command runs the first time
+void DriveForward::Initialize() {
+	Robot::drivetrain.GetRightEncoder().Reset();
+	SetTimeout(2);
+}
+
+// Called repeatedly when this Command is scheduled to run
+void DriveForward::Execute() {
+	m_error = (m_distance
+			- Robot::drivetrain.GetRightEncoder().GetDistance());
+	if (m_driveForwardSpeed * kP * m_error >= m_driveForwardSpeed) {
+		Robot::drivetrain.TankDrive(
+				m_driveForwardSpeed, m_driveForwardSpeed);
+	} else {
+		Robot::drivetrain.TankDrive(m_driveForwardSpeed * kP * m_error,
+				m_driveForwardSpeed * kP * m_error);
+	}
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool DriveForward::IsFinished() {
+	return (std::fabs(m_error) <= kTolerance) || IsTimedOut();
+}
+
+// Called once after isFinished returns true
+void DriveForward::End() {
+	Robot::drivetrain.Stop();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveForward.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveForward.h
new file mode 100644
index 0000000..248c865
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveForward.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+/**
+ * This command drives the robot over a given distance with simple proportional
+ * control This command will drive a given distance limiting to a maximum speed.
+ */
+class DriveForward : public frc::Command {
+public:
+	DriveForward();
+	explicit DriveForward(double dist);
+	DriveForward(double dist, double maxSpeed);
+	void Initialize() override;
+	void Execute() override;
+	bool IsFinished() override;
+	void End() override;
+
+private:
+	double m_driveForwardSpeed;
+	double m_distance;
+	double m_error = 0;
+	static constexpr double kTolerance = 0.1;
+	static constexpr double kP = -1.0 / 5.0;
+
+	void init(double dist, double maxSpeed);
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveWithJoystick.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveWithJoystick.cpp
new file mode 100644
index 0000000..f07e129
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveWithJoystick.cpp
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DriveWithJoystick.h"
+
+#include "../Robot.h"
+
+DriveWithJoystick::DriveWithJoystick() {
+	Requires(&Robot::drivetrain);
+}
+
+// Called repeatedly when this Command is scheduled to run
+void DriveWithJoystick::Execute() {
+	auto& joystick = Robot::oi.GetJoystick();
+	Robot::drivetrain.TankDrive(joystick.GetY(), joystick.GetRawAxis(4));
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool DriveWithJoystick::IsFinished() {
+	return false;
+}
+
+// Called once after isFinished returns true
+void DriveWithJoystick::End() {
+	Robot::drivetrain.Stop();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveWithJoystick.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveWithJoystick.h
new file mode 100644
index 0000000..79ae75f
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/DriveWithJoystick.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+/**
+ * This command allows PS3 joystick to drive the robot. It is always running
+ * except when interrupted by another command.
+ */
+class DriveWithJoystick : public frc::Command {
+public:
+	DriveWithJoystick();
+	void Execute() override;
+	bool IsFinished() override;
+	void End() override;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/ExtendShooter.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/ExtendShooter.cpp
new file mode 100644
index 0000000..a2fe843
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/ExtendShooter.cpp
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ExtendShooter.h"
+
+#include "../Robot.h"
+
+ExtendShooter::ExtendShooter()
+    : frc::TimedCommand(1.0) {
+	Requires(&Robot::shooter);
+}
+
+// Called just before this Command runs the first time
+void ExtendShooter::Initialize() {
+	Robot::shooter.ExtendBoth();
+}
+
+// Called once after isFinished returns true
+void ExtendShooter::End() {
+	Robot::shooter.RetractBoth();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/ExtendShooter.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/ExtendShooter.h
new file mode 100644
index 0000000..c129e60
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/ExtendShooter.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/TimedCommand.h>
+
+/**
+ * Extend the shooter and then retract it after a second.
+ */
+class ExtendShooter : public frc::TimedCommand {
+public:
+	ExtendShooter();
+	void Initialize() override;
+	void End() override;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/LowGoal.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/LowGoal.cpp
new file mode 100644
index 0000000..ce9068c
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/LowGoal.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "LowGoal.h"
+
+#include "../Robot.h"
+#include "ExtendShooter.h"
+#include "SetCollectionSpeed.h"
+#include "SetPivotSetpoint.h"
+
+LowGoal::LowGoal() {
+	AddSequential(new SetPivotSetpoint(Pivot::kLowGoal));
+	AddSequential(new SetCollectionSpeed(Collector::kReverse));
+	AddSequential(new ExtendShooter());
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/LowGoal.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/LowGoal.h
new file mode 100644
index 0000000..361e8eb
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/LowGoal.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/CommandGroup.h>
+
+/**
+ * Spit the ball out into the low goal assuming that the robot is in front of
+ * it.
+ */
+class LowGoal : public frc::CommandGroup {
+public:
+	LowGoal();
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/OpenClaw.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/OpenClaw.cpp
new file mode 100644
index 0000000..5a36e58
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/OpenClaw.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "OpenClaw.h"
+
+#include "../Robot.h"
+
+OpenClaw::OpenClaw() {
+	Requires(&Robot::collector);
+}
+
+// Called just before this Command runs the first time
+void OpenClaw::Initialize() {
+	Robot::collector.Open();
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool OpenClaw::IsFinished() {
+	return Robot::collector.IsOpen();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/OpenClaw.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/OpenClaw.h
new file mode 100644
index 0000000..0485d35
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/OpenClaw.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+/**
+ * Opens the claw
+ */
+class OpenClaw : public frc::Command {
+public:
+	OpenClaw();
+	void Initialize() override;
+	bool IsFinished() override;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/SetCollectionSpeed.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/SetCollectionSpeed.cpp
new file mode 100644
index 0000000..1e26121
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/SetCollectionSpeed.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SetCollectionSpeed.h"
+
+#include "../Robot.h"
+
+SetCollectionSpeed::SetCollectionSpeed(double speed) {
+	Requires(&Robot::collector);
+	m_speed = speed;
+}
+
+// Called just before this Command runs the first time
+void SetCollectionSpeed::Initialize() {
+	Robot::collector.SetSpeed(m_speed);
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/SetCollectionSpeed.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/SetCollectionSpeed.h
new file mode 100644
index 0000000..07de772
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/SetCollectionSpeed.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/InstantCommand.h>
+
+/**
+ * This command sets the collector rollers spinning at the given speed. Since
+ * there is no sensor for detecting speed, it finishes immediately. As a result,
+ * the spinners may still be adjusting their speed.
+ */
+class SetCollectionSpeed : public frc::InstantCommand {
+public:
+	explicit SetCollectionSpeed(double speed);
+	void Initialize() override;
+
+private:
+	double m_speed;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/SetPivotSetpoint.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/SetPivotSetpoint.cpp
new file mode 100644
index 0000000..ce30562
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/SetPivotSetpoint.cpp
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SetPivotSetpoint.h"
+
+#include "../Robot.h"
+
+SetPivotSetpoint::SetPivotSetpoint(double setpoint) {
+	m_setpoint = setpoint;
+	Requires(&Robot::pivot);
+}
+
+// Called just before this Command runs the first time
+void SetPivotSetpoint::Initialize() {
+	Robot::pivot.Enable();
+	Robot::pivot.SetSetpoint(m_setpoint);
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool SetPivotSetpoint::IsFinished() {
+	return Robot::pivot.OnTarget();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/SetPivotSetpoint.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/SetPivotSetpoint.h
new file mode 100644
index 0000000..681417e
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/SetPivotSetpoint.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+/**
+ * Moves the  pivot to a given angle. This command finishes when it is within
+ * the tolerance, but leaves the PID loop running to maintain the position.
+ * Other commands using the pivot should make sure they disable PID!
+ */
+class SetPivotSetpoint : public frc::Command {
+public:
+	explicit SetPivotSetpoint(double setpoint);
+	void Initialize() override;
+	bool IsFinished() override;
+
+private:
+	double m_setpoint;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/Shoot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/Shoot.cpp
new file mode 100644
index 0000000..fa47d36
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/Shoot.cpp
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Shoot.h"
+
+#include "../Robot.h"
+#include "ExtendShooter.h"
+#include "OpenClaw.h"
+#include "SetCollectionSpeed.h"
+#include "WaitForPressure.h"
+
+Shoot::Shoot() {
+	AddSequential(new WaitForPressure());
+	AddSequential(new SetCollectionSpeed(Collector::kStop));
+	AddSequential(new OpenClaw());
+	AddSequential(new ExtendShooter());
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/Shoot.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/Shoot.h
new file mode 100644
index 0000000..b652104
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/Shoot.h
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/CommandGroup.h>
+
+/**
+ * Shoot the ball at the current angle.
+ */
+class Shoot : public frc::CommandGroup {
+public:
+	Shoot();
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/WaitForBall.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/WaitForBall.cpp
new file mode 100644
index 0000000..9a5d83c
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/WaitForBall.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "WaitForBall.h"
+
+#include "../Robot.h"
+
+WaitForBall::WaitForBall() {
+	Requires(&Robot::collector);
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool WaitForBall::IsFinished() {
+	return Robot::collector.HasBall();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/WaitForBall.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/WaitForBall.h
new file mode 100644
index 0000000..82017e1
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/WaitForBall.h
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+/**
+ * Wait until the collector senses that it has the ball. This command does
+ * nothing and is intended to be used in command groups to wait for this
+ * condition.
+ */
+class WaitForBall : public frc::Command {
+public:
+	WaitForBall();
+	bool IsFinished() override;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/WaitForPressure.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/WaitForPressure.cpp
new file mode 100644
index 0000000..a3d60a0
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/WaitForPressure.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "WaitForPressure.h"
+
+#include "../Robot.h"
+
+WaitForPressure::WaitForPressure() {
+	Requires(&Robot::pneumatics);
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool WaitForPressure::IsFinished() {
+	return Robot::pneumatics.IsPressurized();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/WaitForPressure.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/WaitForPressure.h
new file mode 100644
index 0000000..95bdfe0
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Commands/WaitForPressure.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+/**
+ * Wait until the pneumatics are fully pressurized. This command does nothing
+ * and is intended to be used in command groups to wait for this condition.
+ */
+class WaitForPressure : public frc::Command {
+public:
+	WaitForPressure();
+	bool IsFinished() override;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/OI.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/OI.cpp
new file mode 100644
index 0000000..d3d6f1a
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/OI.cpp
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "OI.h"
+
+#include "Commands/Collect.h"
+#include "Commands/DriveForward.h"
+#include "Commands/LowGoal.h"
+#include "Commands/SetCollectionSpeed.h"
+#include "Commands/SetPivotSetpoint.h"
+#include "Commands/Shoot.h"
+#include "SmartDashboard/SmartDashboard.h"
+#include "Subsystems/Collector.h"
+#include "Subsystems/Pivot.h"
+
+OI::OI() {
+	m_r1.WhenPressed(new LowGoal());
+	m_r2.WhenPressed(new Collect());
+
+	m_l1.WhenPressed(new SetPivotSetpoint(Pivot::kShoot));
+	m_l2.WhenPressed(new SetPivotSetpoint(Pivot::kShootNear));
+
+	m_sticks.WhenActive(new Shoot());
+
+	// SmartDashboard Buttons
+	frc::SmartDashboard::PutData("Drive Forward", new DriveForward(2.25));
+	frc::SmartDashboard::PutData("Drive Backward", new DriveForward(-2.25));
+	frc::SmartDashboard::PutData("Start Rollers",
+			new SetCollectionSpeed(Collector::kForward));
+	frc::SmartDashboard::PutData("Stop Rollers",
+			new SetCollectionSpeed(Collector::kStop));
+	frc::SmartDashboard::PutData("Reverse Rollers",
+			new SetCollectionSpeed(Collector::kReverse));
+}
+
+frc::Joystick& OI::GetJoystick() {
+	return m_joystick;
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/OI.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/OI.h
new file mode 100644
index 0000000..b3228aa
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/OI.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Buttons/JoystickButton.h>
+#include <Joystick.h>
+
+#include "Triggers/DoubleButton.h"
+
+class OI {
+public:
+	OI();
+	frc::Joystick& GetJoystick();
+
+private:
+	frc::Joystick m_joystick{0};
+
+	frc::JoystickButton m_l1{&m_joystick, 11};
+	frc::JoystickButton m_l2{&m_joystick, 9};
+	frc::JoystickButton m_r1{&m_joystick, 12};
+	frc::JoystickButton m_r2{&m_joystick, 10};
+
+	DoubleButton m_sticks{&m_joystick, 2, 3};
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Robot.cpp
new file mode 100644
index 0000000..fb90037
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Robot.cpp
@@ -0,0 +1,87 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Robot.h"
+
+#include <iostream>
+
+#include <Commands/Scheduler.h>
+#include <LiveWindow/LiveWindow.h>
+#include <SmartDashboard/SmartDashboard.h>
+
+DriveTrain Robot::drivetrain;
+Pivot Robot::pivot;
+Collector Robot::collector;
+Shooter Robot::shooter;
+Pneumatics Robot::pneumatics;
+OI Robot::oi;
+
+void Robot::RobotInit() {
+	// Show what command your subsystem is running on the SmartDashboard
+	frc::SmartDashboard::PutData(&drivetrain);
+	frc::SmartDashboard::PutData(&pivot);
+	frc::SmartDashboard::PutData(&collector);
+	frc::SmartDashboard::PutData(&shooter);
+	frc::SmartDashboard::PutData(&pneumatics);
+
+	// instantiate the command used for the autonomous period
+	m_autoChooser.AddDefault("Drive and Shoot", &m_driveAndShootAuto);
+	m_autoChooser.AddObject("Drive Forward", &m_driveForwardAuto);
+	frc::SmartDashboard::PutData("Auto Mode", &m_autoChooser);
+
+	pneumatics.Start();  // Pressurize the pneumatics.
+}
+
+void Robot::AutonomousInit() {
+	m_autonomousCommand = m_autoChooser.GetSelected();
+	m_autonomousCommand->Start();
+}
+
+void Robot::AutonomousPeriodic() {
+	frc::Scheduler::GetInstance()->Run();
+	Log();
+}
+
+void Robot::TeleopInit() {
+	// This makes sure that the autonomous stops running when
+	// teleop starts running. If you want the autonomous to
+	// continue until interrupted by another command, remove
+	// this line or comment it out.
+	if (m_autonomousCommand != nullptr) {
+		m_autonomousCommand->Cancel();
+	}
+	std::cout << "Starting Teleop" << std::endl;
+}
+
+void Robot::TeleopPeriodic() {
+	frc::Scheduler::GetInstance()->Run();
+	Log();
+}
+
+void Robot::TestPeriodic() {}
+
+void Robot::DisabledInit() {
+	shooter.Unlatch();
+}
+
+void Robot::DisabledPeriodic() {
+	Log();
+}
+
+/**
+ * Log interesting values to the SmartDashboard.
+ */
+void Robot::Log() {
+	Robot::pneumatics.WritePressure();
+	frc::SmartDashboard::PutNumber("Pivot Pot Value", pivot.GetAngle());
+	frc::SmartDashboard::PutNumber("Left Distance",
+			drivetrain.GetLeftEncoder().GetDistance());
+	frc::SmartDashboard::PutNumber("Right Distance",
+			drivetrain.GetRightEncoder().GetDistance());
+}
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Robot.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Robot.h
new file mode 100644
index 0000000..33c3073
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Robot.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+#include <IterativeRobot.h>
+#include <SmartDashboard/SendableChooser.h>
+
+#include "Commands/DriveAndShootAutonomous.h"
+#include "Commands/DriveForward.h"
+#include "OI.h"
+#include "Subsystems/Collector.h"
+#include "Subsystems/DriveTrain.h"
+#include "Subsystems/Pivot.h"
+#include "Subsystems/Pneumatics.h"
+#include "Subsystems/Shooter.h"
+
+class Robot : public IterativeRobot {
+public:
+	static DriveTrain drivetrain;
+	static Pivot pivot;
+	static Collector collector;
+	static Shooter shooter;
+	static Pneumatics pneumatics;
+	static OI oi;
+
+private:
+	frc::Command* m_autonomousCommand = nullptr;
+	DriveAndShootAutonomous m_driveAndShootAuto;
+	DriveForward m_driveForwardAuto;
+	SendableChooser<frc::Command*> m_autoChooser;
+
+	void RobotInit() override;
+	void AutonomousInit() override;
+	void AutonomousPeriodic() override;
+	void TeleopInit() override;
+	void TeleopPeriodic() override;
+	void TestPeriodic() override;
+	void DisabledInit() override;
+	void DisabledPeriodic() override;
+
+	void Log();
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Collector.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Collector.cpp
new file mode 100644
index 0000000..fa81dc1
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Collector.cpp
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Collector.h"
+
+#include <LiveWindow/LiveWindow.h>
+
+Collector::Collector()
+    : frc::Subsystem("Collector") {
+	// Put everything to the LiveWindow for testing.
+	AddChild("Roller Motor", m_rollerMotor);
+	AddChild("Ball Detector", m_ballDetector);
+	AddChild("Claw Open Detector", m_openDetector);
+	AddChild("Piston", m_piston);
+}
+
+bool Collector::HasBall() {
+	return m_ballDetector.Get();  // TODO: prepend ! to reflect real robot
+}
+
+void Collector::SetSpeed(double speed) {
+	m_rollerMotor.Set(-speed);
+}
+
+void Collector::Stop() {
+	m_rollerMotor.Set(0);
+}
+
+bool Collector::IsOpen() {
+	return m_openDetector.Get();  // TODO: prepend ! to reflect real robot
+}
+
+void Collector::Open() {
+	m_piston.Set(true);
+}
+
+void Collector::Close() {
+	m_piston.Set(false);
+}
+
+void Collector::InitDefaultCommand() {}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Collector.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Collector.h
new file mode 100644
index 0000000..e6ad0e4
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Collector.h
@@ -0,0 +1,76 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Subsystem.h>
+#include <DigitalInput.h>
+#include <Solenoid.h>
+#include <Spark.h>
+
+/**
+ * The Collector subsystem has one motor for the rollers, a limit switch for
+ * ball
+ * detection, a piston for opening and closing the claw, and a reed switch to
+ * check if the piston is open.
+ */
+class Collector : public frc::Subsystem {
+public:
+	// Constants for some useful speeds
+	static constexpr double kForward = 1;
+	static constexpr double kStop = 0;
+	static constexpr double kReverse = -1;
+
+	Collector();
+
+	/**
+	 * NOTE: The current simulation model uses the the lower part of the
+	 * claw
+	 * since the limit switch wasn't exported. At some point, this will be
+	 * updated.
+	 *
+	 * @return Whether or not the robot has the ball.
+	 */
+	bool HasBall();
+
+	/**
+	 * @param speed The speed to spin the rollers.
+	 */
+	void SetSpeed(double speed);
+
+	/**
+	 * Stop the rollers from spinning
+	 */
+	void Stop();
+
+	/**
+	 * @return Whether or not the claw is open.
+	 */
+	bool IsOpen();
+
+	/**
+	 * Open the claw up. (For shooting)
+	 */
+	void Open();
+
+	/**
+	 * Close the claw. (For collecting and driving)
+	 */
+	void Close();
+
+	/**
+	 * No default command.
+	 */
+	void InitDefaultCommand() override;
+
+private:
+	// Subsystem devices
+	frc::Spark m_rollerMotor{6};
+	frc::DigitalInput m_ballDetector{10};
+	frc::Solenoid m_piston{1};
+	frc::DigitalInput m_openDetector{6};
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/DriveTrain.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/DriveTrain.cpp
new file mode 100644
index 0000000..f0ac65a
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/DriveTrain.cpp
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DriveTrain.h"
+
+#include <cmath>
+
+#include <Joystick.h>
+
+#include "../Commands/DriveWithJoystick.h"
+
+DriveTrain::DriveTrain()
+    : frc::Subsystem("DriveTrain") {
+	// AddChild("Front Left CIM", m_frontLeftCIM);
+	// AddChild("Front Right CIM", m_frontRightCIM);
+	// AddChild("Back Left CIM", m_backLeftCIM);
+	// AddChild("Back Right CIM", m_backRightCIM);
+
+	// Configure the DifferentialDrive to reflect the fact that all our
+	// motors are wired backwards and our drivers sensitivity preferences.
+	m_robotDrive.SetSafetyEnabled(false);
+	m_robotDrive.SetExpiration(0.1);
+	m_robotDrive.SetMaxOutput(1.0);
+	m_leftCIMs.SetInverted(true);
+	m_rightCIMs.SetInverted(true);
+
+	// Configure encoders
+	m_rightEncoder.SetPIDSourceType(PIDSourceType::kDisplacement);
+	m_leftEncoder.SetPIDSourceType(PIDSourceType::kDisplacement);
+
+#ifndef SIMULATION
+	// Converts to feet
+	m_rightEncoder.SetDistancePerPulse(0.0785398);
+	m_leftEncoder.SetDistancePerPulse(0.0785398);
+#else
+	// Convert to feet 4in diameter wheels with 360 tick simulated encoders
+	m_rightEncoder.SetDistancePerPulse(
+			(4.0 /*in*/ * M_PI) / (360.0 * 12.0 /*in/ft*/));
+	m_leftEncoder.SetDistancePerPulse(
+			(4.0 /*in*/ * M_PI) / (360.0 * 12.0 /*in/ft*/));
+#endif
+
+	AddChild("Right Encoder", m_rightEncoder);
+	AddChild("Left Encoder", m_leftEncoder);
+
+// Configure gyro
+#ifndef SIMULATION
+	m_gyro.SetSensitivity(0.007);  // TODO: Handle more gracefully?
+#endif
+	AddChild("Gyro", m_gyro);
+}
+
+void DriveTrain::InitDefaultCommand() {
+	SetDefaultCommand(new DriveWithJoystick());
+}
+
+void DriveTrain::TankDrive(double leftAxis, double rightAxis) {
+	m_robotDrive.TankDrive(leftAxis, rightAxis);
+}
+
+void DriveTrain::Stop() {
+	m_robotDrive.TankDrive(0.0, 0.0);
+}
+
+Encoder& DriveTrain::GetLeftEncoder() {
+	return m_leftEncoder;
+}
+
+Encoder& DriveTrain::GetRightEncoder() {
+	return m_rightEncoder;
+}
+
+double DriveTrain::GetAngle() {
+	return m_gyro.GetAngle();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/DriveTrain.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/DriveTrain.h
new file mode 100644
index 0000000..b0eb100
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/DriveTrain.h
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <AnalogGyro.h>
+#include <Commands/Subsystem.h>
+#include <Drive/DifferentialDrive.h>
+#include <Encoder.h>
+#include <Spark.h>
+#include <SpeedControllerGroup.h>
+
+namespace frc {
+class Joystick;
+}  // namespace frc
+
+/**
+ * The DriveTrain subsystem controls the robot's chassis and reads in
+ * information about it's speed and position.
+ */
+class DriveTrain : public frc::Subsystem {
+public:
+	DriveTrain();
+
+	/**
+	 * When other commands aren't using the drivetrain, allow tank drive
+	 * with
+	 * the joystick.
+	 */
+	void InitDefaultCommand();
+
+	/**
+	 * @param leftAxis Left sides value
+	 * @param rightAxis Right sides value
+	 */
+	void TankDrive(double leftAxis, double rightAxis);
+
+	/**
+	 * Stop the drivetrain from moving.
+	 */
+	void Stop();
+
+	/**
+	 * @return The encoder getting the distance and speed of left side of
+	 * the drivetrain.
+	 */
+	Encoder& GetLeftEncoder();
+
+	/**
+	 * @return The encoder getting the distance and speed of right side of
+	 * the drivetrain.
+	 */
+	Encoder& GetRightEncoder();
+
+	/**
+	 * @return The current angle of the drivetrain.
+	 */
+	double GetAngle();
+
+private:
+	// Subsystem devices
+	frc::Spark m_frontLeftCIM{1};
+	frc::Spark m_rearLeftCIM{2};
+	frc::SpeedControllerGroup m_leftCIMs{m_frontLeftCIM, m_rearLeftCIM};
+
+	frc::Spark m_frontRightCIM{3};
+	frc::Spark m_rearRightCIM{4};
+	frc::SpeedControllerGroup m_rightCIMs{m_frontRightCIM, m_rearRightCIM};
+
+	frc::DifferentialDrive m_robotDrive{m_leftCIMs, m_rightCIMs};
+
+	frc::Encoder m_rightEncoder{1, 2, true, Encoder::k4X};
+	frc::Encoder m_leftEncoder{3, 4, false, Encoder::k4X};
+	frc::AnalogGyro m_gyro{0};
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Pivot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Pivot.cpp
new file mode 100644
index 0000000..1c2a4d7
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Pivot.cpp
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Pivot.h"
+
+Pivot::Pivot()
+    : frc::PIDSubsystem("Pivot", 7.0, 0.0, 8.0) {
+	SetAbsoluteTolerance(0.005);
+	GetPIDController()->SetContinuous(false);
+#ifdef SIMULATION
+	// PID is different in simulation.
+	GetPIDController()->SetPID(0.5, 0.001, 2);
+	SetAbsoluteTolerance(5);
+#endif
+
+	// Put everything to the LiveWindow for testing.
+	AddChild("Upper Limit Switch", m_upperLimitSwitch);
+	AddChild("Lower Limit Switch", m_lowerLimitSwitch);
+	AddChild("Pot", m_pot);
+	AddChild("Motor", m_motor);
+}
+
+void InitDefaultCommand() {}
+
+double Pivot::ReturnPIDInput() {
+	return m_pot.Get();
+}
+
+void Pivot::UsePIDOutput(double output) {
+	m_motor.PIDWrite(output);
+}
+
+bool Pivot::IsAtUpperLimit() {
+	return m_upperLimitSwitch.Get();  // TODO: inverted from real robot
+					  // (prefix with !)
+}
+
+bool Pivot::IsAtLowerLimit() {
+	return m_lowerLimitSwitch.Get();  // TODO: inverted from real robot
+					  // (prefix with !)
+}
+
+double Pivot::GetAngle() {
+	return m_pot.Get();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Pivot.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Pivot.h
new file mode 100644
index 0000000..b145caf
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Pivot.h
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <AnalogPotentiometer.h>
+#include <Commands/PIDSubsystem.h>
+#include <DigitalInput.h>
+#include <Spark.h>
+
+/**
+ * The Pivot subsystem contains the Van-door motor and the pot for PID control
+ * of angle of the pivot and claw.
+ */
+class Pivot : public frc::PIDSubsystem {
+public:
+	// Constants for some useful angles
+	static constexpr double kCollect = 105;
+	static constexpr double kLowGoal = 90;
+	static constexpr double kShoot = 45;
+	static constexpr double kShootNear = 30;
+
+	Pivot();
+
+	/**
+	 *  No default command, if PID is enabled, the current setpoint will be
+	 * maintained.
+	 */
+	void InitDefaultCommand() override {}
+
+	/**
+	 * @return The angle read in by the potentiometer
+	 */
+	double ReturnPIDInput() override;
+
+	/**
+	 * Set the motor speed based off of the PID output
+	 */
+	void UsePIDOutput(double output) override;
+
+	/**
+	 * @return If the pivot is at its upper limit.
+	 */
+	bool IsAtUpperLimit();
+
+	/**
+	 * @return If the pivot is at its lower limit.
+	 */
+	bool IsAtLowerLimit();
+
+	/**
+	 * @return The current angle of the pivot.
+	 */
+	double GetAngle();
+
+private:
+	// Subsystem devices
+
+	// Sensors for measuring the position of the pivot
+	frc::DigitalInput m_upperLimitSwitch{13};
+	frc::DigitalInput m_lowerLimitSwitch{12};
+
+	/* 0 degrees is vertical facing up.
+	 * Angle increases the more forward the pivot goes.
+	 */
+	frc::AnalogPotentiometer m_pot{1};
+
+	// Motor to move the pivot
+	frc::Spark m_motor{5};
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Pneumatics.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Pneumatics.cpp
new file mode 100644
index 0000000..9128b0d
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Pneumatics.cpp
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Pneumatics.h"
+
+#include <SmartDashboard/SmartDashboard.h>
+
+Pneumatics::Pneumatics()
+    : frc::Subsystem("Pneumatics") {
+	AddChild("Pressure Sensor", m_pressureSensor);
+}
+
+/**
+ * No default command
+ */
+void Pneumatics::InitDefaultCommand() {}
+
+/**
+ * Start the compressor going. The compressor automatically starts and stops as
+ * it goes above and below maximum pressure.
+ */
+void Pneumatics::Start() {
+#ifndef SIMULATION
+	m_compressor.Start();
+#endif
+}
+
+/**
+ * @return Whether or not the system is fully pressurized.
+ */
+bool Pneumatics::IsPressurized() {
+#ifndef SIMULATION
+	return kMaxPressure <= m_pressureSensor.GetVoltage();
+#else
+	return true;  // NOTE: Simulation always has full pressure
+#endif
+}
+
+/**
+ * Puts the pressure on the SmartDashboard.
+ */
+void Pneumatics::WritePressure() {
+	frc::SmartDashboard::PutNumber(
+			"Pressure", m_pressureSensor.GetVoltage());
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Pneumatics.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Pneumatics.h
new file mode 100644
index 0000000..4d8ba1d
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Pneumatics.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <AnalogInput.h>
+#include <Commands/Subsystem.h>
+#include <Compressor.h>
+
+/**
+ * The Pneumatics subsystem contains the compressor and a pressure sensor.
+ *
+ * NOTE: The simulator currently doesn't support the compressor or pressure
+ * sensors.
+ */
+class Pneumatics : public frc::Subsystem {
+public:
+	Pneumatics();
+
+	/**
+	 * No default command
+	 */
+	void InitDefaultCommand() override;
+
+	/**
+	 * Start the compressor going. The compressor automatically starts and
+	 * stops as it goes above and below maximum pressure.
+	 */
+	void Start();
+
+	/**
+	 * @return Whether or not the system is fully pressurized.
+	 */
+	bool IsPressurized();
+
+	/**
+	 * Puts the pressure on the SmartDashboard.
+	 */
+	void WritePressure();
+
+private:
+	frc::AnalogInput m_pressureSensor{3};
+
+#ifndef SIMULATION
+	frc::Compressor m_compressor{1};  // TODO: (1, 14, 1, 8);
+#endif
+
+	static constexpr double kMaxPressure = 2.55;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Shooter.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Shooter.cpp
new file mode 100644
index 0000000..b1d87a9
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Shooter.cpp
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Shooter.h"
+
+Shooter::Shooter()
+    : Subsystem("Shooter") {
+	// Put everything to the LiveWindow for testing.
+	AddChild("Hot Goal Sensor", m_hotGoalSensor);
+	AddChild("Piston1 Reed Switch Front ", m_piston1ReedSwitchFront);
+	AddChild("Piston1 Reed Switch Back ", m_piston1ReedSwitchBack);
+	AddChild("Latch Piston", m_latchPiston);
+}
+
+void Shooter::InitDefaultCommand() {
+	// Set the default command for a subsystem here.
+	// SetDefaultCommand(new MySpecialCommand());
+}
+
+void Shooter::ExtendBoth() {
+	m_piston1.Set(frc::DoubleSolenoid::kForward);
+	m_piston2.Set(frc::DoubleSolenoid::kForward);
+}
+
+void Shooter::RetractBoth() {
+	m_piston1.Set(frc::DoubleSolenoid::kReverse);
+	m_piston2.Set(frc::DoubleSolenoid::kReverse);
+}
+
+void Shooter::Extend1() {
+	m_piston1.Set(frc::DoubleSolenoid::kForward);
+}
+
+void Shooter::Retract1() {
+	m_piston1.Set(frc::DoubleSolenoid::kReverse);
+}
+
+void Shooter::Extend2() {
+	m_piston2.Set(frc::DoubleSolenoid::kReverse);
+}
+
+void Shooter::Retract2() {
+	m_piston2.Set(frc::DoubleSolenoid::kForward);
+}
+
+void Shooter::Off1() {
+	m_piston1.Set(frc::DoubleSolenoid::kOff);
+}
+
+void Shooter::Off2() {
+	m_piston2.Set(frc::DoubleSolenoid::kOff);
+}
+
+void Shooter::Unlatch() {
+	m_latchPiston.Set(true);
+}
+
+void Shooter::Latch() {
+	m_latchPiston.Set(false);
+}
+
+void Shooter::ToggleLatchPosition() {
+	m_latchPiston.Set(!m_latchPiston.Get());
+}
+
+bool Shooter::Piston1IsExtended() {
+	return !m_piston1ReedSwitchFront.Get();
+}
+
+bool Shooter::Piston1IsRetracted() {
+	return !m_piston1ReedSwitchBack.Get();
+}
+
+void Shooter::OffBoth() {
+	m_piston1.Set(frc::DoubleSolenoid::kOff);
+	m_piston2.Set(frc::DoubleSolenoid::kOff);
+}
+
+bool Shooter::GoalIsHot() {
+	return m_hotGoalSensor.Get();
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Shooter.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Shooter.h
new file mode 100644
index 0000000..c22c407
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Subsystems/Shooter.h
@@ -0,0 +1,127 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Subsystem.h>
+#include <DigitalInput.h>
+#include <DoubleSolenoid.h>
+#include <Solenoid.h>
+
+/**
+ * The Shooter subsystem handles shooting. The mechanism for shooting is
+ * slightly complicated because it has to pneumatic cylinders for shooting, and
+ * a third latch to allow the pressure to partially build up and reduce the
+ * effect of the airflow. For shorter shots, when full power isn't needed, only
+ * one cylinder fires.
+ *
+ * NOTE: Simulation currently approximates this as as single pneumatic cylinder
+ * and ignores the latch.
+ */
+class Shooter : public frc::Subsystem {
+public:
+	Shooter();
+	void InitDefaultCommand() override;
+
+	/**
+	 * Extend both solenoids to shoot.
+	 */
+	void ExtendBoth();
+
+	/**
+	 * Retract both solenoids to prepare to shoot.
+	 */
+	void RetractBoth();
+
+	/**
+	 * Extend solenoid 1 to shoot.
+	 */
+	void Extend1();
+
+	/**
+	 * Retract solenoid 1 to prepare to shoot.
+	 */
+	void Retract1();
+
+	/**
+	 * Extend solenoid 2 to shoot.
+	 */
+	void Extend2();
+
+	/**
+	 * Retract solenoid 2 to prepare to shoot.
+	 */
+	void Retract2();
+
+	/**
+	 * Turns off the piston1 double solenoid. This won't actuate anything
+	 * because double solenoids preserve their state when turned off. This
+	 * should be called in order to reduce the amount of time that the coils
+	 * are
+	 * powered.
+	 */
+	void Off1();
+
+	/**
+	 * Turns off the piston1 double solenoid. This won't actuate anything
+	 * because double solenoids preserve their state when turned off. This
+	 * should be called in order to reduce the amount of time that the coils
+	 * are
+	 * powered.
+	 */
+	void Off2();
+
+	/**
+	 * Release the latch so that we can shoot
+	 */
+	void Unlatch();
+
+	/**
+	 * Latch so that pressure can build up and we aren't limited by air
+	 * flow.
+	 */
+	void Latch();
+
+	/**
+	 * Toggles the latch postions
+	 */
+	void ToggleLatchPosition();
+
+	/**
+	 * @return Whether or not piston 1 is fully extended.
+	 */
+	bool Piston1IsExtended();
+
+	/**
+	 * @return Whether or not piston 1 is fully retracted.
+	 */
+	bool Piston1IsRetracted();
+
+	/**
+	 * Turns off all double solenoids. Double solenoids hold their position
+	 * when
+	 * they are turned off. We should turn them off whenever possible to
+	 * extend
+	 * the life of the coils
+	 */
+	void OffBoth();
+
+	/**
+	 * @return Whether or not the goal is hot as read by the banner sensor
+	 */
+	bool GoalIsHot();
+
+private:
+	// Devices
+	frc::DoubleSolenoid m_piston1{3, 4};
+	frc::DoubleSolenoid m_piston2{5, 6};
+	frc::Solenoid m_latchPiston{1, 2};
+	frc::DigitalInput m_piston1ReedSwitchFront{9};
+	frc::DigitalInput m_piston1ReedSwitchBack{11};
+	frc::DigitalInput m_hotGoalSensor{
+			7};  // NOTE: Currently ignored in simulation
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Triggers/DoubleButton.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Triggers/DoubleButton.cpp
new file mode 100644
index 0000000..c8b485d
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Triggers/DoubleButton.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DoubleButton.h"
+
+#include <Joystick.h>
+
+DoubleButton::DoubleButton(frc::Joystick* joy, int button1, int button2)
+    : m_joy(*joy) {
+	m_button1 = button1;
+	m_button2 = button2;
+}
+
+bool DoubleButton::Get() {
+	return m_joy.GetRawButton(m_button1) && m_joy.GetRawButton(m_button2);
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Triggers/DoubleButton.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Triggers/DoubleButton.h
new file mode 100644
index 0000000..a0b8f67
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PacGoat/src/Triggers/DoubleButton.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Buttons/Trigger.h>
+
+namespace frc {
+class Joystick;
+}  // namespace frc
+
+class DoubleButton : public frc::Trigger {
+public:
+	DoubleButton(frc::Joystick* joy, int button1, int button2);
+
+	bool Get();
+
+private:
+	frc::Joystick& m_joy;
+	int m_button1;
+	int m_button2;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/src/Robot.cpp
new file mode 100644
index 0000000..d2ef3f2
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/src/Robot.cpp
@@ -0,0 +1,82 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <array>
+
+#include <AnalogInput.h>
+#include <IterativeRobot.h>
+#include <Joystick.h>
+#include <PIDController.h>
+#include <Spark.h>
+
+/**
+ * This is a sample program to demonstrate how to use a soft potentiometer and a
+ * PID Controller to reach and maintain position setpoints on an elevator
+ * mechanism.
+ */
+class Robot : public frc::IterativeRobot {
+public:
+	void RobotInit() override { m_pidController.SetInputRange(0, 5); }
+
+	void TeleopInit() override { m_pidController.Enable(); }
+
+	void TeleopPeriodic() override {
+		// when the button is pressed once, the selected elevator
+		// setpoint
+		// is incremented
+		bool currentButtonValue = m_joystick.GetTrigger();
+		if (currentButtonValue && !m_previousButtonValue) {
+			// index of the elevator setpoint wraps around.
+			m_index = (m_index + 1) % (sizeof(kSetPoints) / 8);
+		}
+		m_previousButtonValue = currentButtonValue;
+
+		m_pidController.SetSetpoint(kSetPoints[m_index]);
+	}
+
+private:
+	static constexpr int kPotChannel = 1;
+	static constexpr int kMotorChannel = 7;
+	static constexpr int kJoystickChannel = 0;
+
+	// Bottom, middle, and top elevator setpoints
+	static constexpr std::array<double, 3> kSetPoints = {1.0, 2.6, 4.3};
+
+	/* proportional, integral, and derivative speed constants; motor
+	 * inverted
+	 * DANGER: when tuning PID constants, high/inappropriate values for
+	 * pGain,
+	 * iGain, and dGain may cause dangerous, uncontrollable, or
+	 * undesired behavior!
+	 *
+	 * These may need to be positive for a non-inverted motor
+	 */
+	static constexpr double kP = -5.0;
+	static constexpr double kI = -0.02;
+	static constexpr double kD = -2.0;
+
+	int m_index = 0;
+	bool m_previousButtonValue = false;
+
+	frc::AnalogInput m_potentiometer{kPotChannel};
+	frc::Joystick m_joystick{kJoystickChannel};
+	frc::Spark m_elevatorMotor{kMotorChannel};
+
+	/* potentiometer (AnalogInput) and elevatorMotor (Victor) can be used as
+	 * a
+	 * PIDSource and PIDOutput respectively. The PIDController takes
+	 * pointers
+	 * to the PIDSource and PIDOutput, so you must use &potentiometer and
+	 * &elevatorMotor to get their pointers.
+	 */
+	frc::PIDController m_pidController{
+			kP, kI, kD, &m_potentiometer, &m_elevatorMotor};
+};
+
+constexpr std::array<double, 3> Robot::kSetPoints;
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/QuickVision/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/QuickVision/src/Robot.cpp
new file mode 100644
index 0000000..2511d3a
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/QuickVision/src/Robot.cpp
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <CameraServer.h>
+#include <IterativeRobot.h>
+
+/**
+ * Uses the CameraServer class to automatically capture video from a USB webcam
+ * and send it to the FRC dashboard without doing any vision processing. This
+ * is the easiest way to get camera images to the dashboard. Just add this to
+ * the
+ * RobotInit() method in your program.
+ */
+class Robot : public frc::IterativeRobot {
+public:
+	void RobotInit() {
+		CameraServer::GetInstance()->StartAutomaticCapture();
+	}
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Relay/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Relay/src/Robot.cpp
new file mode 100644
index 0000000..99c60ea
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Relay/src/Robot.cpp
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <IterativeRobot.h>
+#include <Joystick.h>
+#include <Relay.h>
+
+/**
+ * This is a sample program which uses joystick buttons to control a relay.
+ * A Relay (generally a spike) has two outputs, each of which can be at either
+ *   0V or 12V and so can be used for actions such as turning a motor off,
+ *   full forwards, or full reverse, and is generally used on the compressor.
+ * This program uses two buttons on a joystick and each button corresponds to
+ *   one output; pressing the button sets the output to 12V and releasing sets
+ *   it to 0V.
+ */
+class Robot : public frc::IterativeRobot {
+public:
+	void TeleopPeriodic() override {
+		/* Retrieve the button values. GetRawButton will return
+		 * true if the button is pressed and false if not.
+		 */
+		bool forward = m_stick.GetRawButton(kRelayForwardButton);
+		bool reverse = m_stick.GetRawButton(kRelayReverseButton);
+
+		/* Depending on the button values, we want to use one of
+		 *   kOn, kOff, kForward, or kReverse.
+		 * kOn sets both outputs to 12V, kOff sets both to 0V,
+		 * kForward sets forward to 12V and reverse to 0V, and
+		 * kReverse sets reverse to 12V and forward to 0V.
+		 */
+		if (forward && reverse) {
+			m_relay.Set(Relay::kOn);
+		} else if (forward) {
+			m_relay.Set(Relay::kForward);
+		} else if (reverse) {
+			m_relay.Set(Relay::kReverse);
+		} else {
+			m_relay.Set(Relay::kOff);
+		}
+	}
+
+private:
+	frc::Joystick m_stick{0};
+	frc::Relay m_relay{0};
+
+	static constexpr int kRelayForwardButton = 1;
+	static constexpr int kRelayReverseButton = 2;
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Solenoid/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Solenoid/src/Robot.cpp
new file mode 100644
index 0000000..f880075
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Solenoid/src/Robot.cpp
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <DoubleSolenoid.h>
+#include <IterativeRobot.h>
+#include <Joystick.h>
+#include <Solenoid.h>
+
+/**
+ * This is a sample program showing the use of the solenoid classes during
+ *   operator control.
+ * Three buttons from a joystick will be used to control two solenoids:
+ *   One button to control the position of a single solenoid and the other
+ *   two buttons to control a double solenoid.
+ * Single solenoids can either be on or off, such that the air diverted through
+ *   them goes through either one channel or the other.
+ * Double solenoids have three states: Off, Forward, and Reverse. Forward and
+ *   Reverse divert the air through the two channels and correspond to the
+ *   on and off of a single solenoid, but a double solenoid can also be "off",
+ *   where both channels are diverted to exhaust such that there is no pressure
+ *   in either channel.
+ * Additionally, double solenoids take up two channels on your PCM whereas
+ *   single solenoids only take a single channel.
+ */
+class Robot : public frc::IterativeRobot {
+public:
+	void TeleopPeriodic() override {
+		/* The output of GetRawButton is true/false depending on whether
+		 * the button is pressed; Set takes a boolean for for whether to
+		 * use the default (false) channel or the other (true).
+		 */
+		m_solenoid.Set(m_stick.GetRawButton(kSolenoidButton));
+
+		/* In order to set the double solenoid, we will say that if
+		 * neither
+		 * button is pressed, it is off, if just one button is pressed,
+		 * set the solenoid to correspond to that button, and if both
+		 * are pressed, set the solenoid to Forwards.
+		 */
+		if (m_stick.GetRawButton(kDoubleSolenoidForward)) {
+			m_doubleSolenoid.Set(frc::DoubleSolenoid::kForward);
+		} else if (m_stick.GetRawButton(kDoubleSolenoidReverse)) {
+			m_doubleSolenoid.Set(frc::DoubleSolenoid::kReverse);
+		} else {
+			m_doubleSolenoid.Set(frc::DoubleSolenoid::kOff);
+		}
+	}
+
+private:
+	frc::Joystick m_stick{0};
+
+	// Solenoid corresponds to a single solenoid.
+	frc::Solenoid m_solenoid{0};
+
+	// DoubleSolenoid corresponds to a double solenoid.
+	frc::DoubleSolenoid m_doubleSolenoid{1, 2};
+
+	static constexpr int kSolenoidButton = 1;
+	static constexpr int kDoubleSolenoidForward = 2;
+	static constexpr int kDoubleSolenoidReverse = 3;
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Ultrasonic/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Ultrasonic/src/Robot.cpp
new file mode 100644
index 0000000..080fd72
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/Ultrasonic/src/Robot.cpp
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <AnalogInput.h>
+#include <Drive/DifferentialDrive.h>
+#include <IterativeRobot.h>
+#include <Spark.h>
+
+/**
+ * This is a sample program demonstrating how to use an ultrasonic sensor and
+ * proportional control to maintain a set distance from an object.
+ */
+class Robot : public frc::IterativeRobot {
+public:
+	/**
+	 * Tells the robot to drive to a set distance (in inches) from an object
+	 * using proportional control.
+	 */
+	void TeleopPeriodic() override {
+		// sensor returns a value from 0-4095 that is scaled to inches
+		double currentDistance =
+				m_ultrasonic.GetValue() * kValueToInches;
+		// convert distance error to a motor speed
+		double currentSpeed = (kHoldDistance - currentDistance) * kP;
+		// drive robot
+		m_robotDrive.ArcadeDrive(currentSpeed, 0);
+	}
+
+private:
+	// Distance in inches the robot wants to stay from an object
+	static constexpr int kHoldDistance = 12;
+
+	// Factor to convert sensor values to a distance in inches
+	static constexpr double kValueToInches = 0.125;
+
+	// Proportional speed constant
+	static constexpr double kP = 0.05;
+
+	static constexpr int kLeftMotorPort = 0;
+	static constexpr int kRightMotorPort = 1;
+	static constexpr int kUltrasonicPort = 0;
+
+	frc::AnalogInput m_ultrasonic{kUltrasonicPort};
+
+	frc::Spark m_left{kLeftMotorPort};
+	frc::Spark m_right{kRightMotorPort};
+	frc::DifferentialDrive m_robotDrive{m_left, m_right};
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/src/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/src/Robot.cpp
new file mode 100644
index 0000000..e0576af
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/src/Robot.cpp
@@ -0,0 +1,86 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <AnalogInput.h>
+#include <Drive/DifferentialDrive.h>
+#include <IterativeRobot.h>
+#include <PIDController.h>
+#include <PIDOutput.h>
+#include <Spark.h>
+
+/**
+ * This is a sample program demonstrating how to use an ultrasonic sensor and
+ * proportional control to maintain a set distance from an object.
+ */
+class Robot : public frc::IterativeRobot {
+public:
+	/**
+	 * Drives the robot a set distance from an object using PID control and
+	 * the
+	 * ultrasonic sensor.
+	 */
+	void TeleopInit() override {
+		// Set expected range to 0-24 inches; e.g. at 24 inches from
+		// object go
+		// full forward, at 0 inches from object go full backward.
+		m_pidController.SetInputRange(0, 24 * kValueToInches);
+
+		// Set setpoint of the pidController
+		m_pidController.SetSetpoint(kHoldDistance * kValueToInches);
+
+		// Begin PID control
+		m_pidController.Enable();
+	}
+
+private:
+	// Internal class to write to robot drive using a PIDOutput
+	class MyPIDOutput : public frc::PIDOutput {
+	public:
+		explicit MyPIDOutput(frc::DifferentialDrive& r)
+		    : m_rd(r) {
+			m_rd.SetSafetyEnabled(false);
+		}
+
+		void PIDWrite(double output) override {
+			// Write to robot drive by reference
+			m_rd.ArcadeDrive(output, 0);
+		}
+
+	private:
+		frc::DifferentialDrive& m_rd;
+	};
+
+	// Distance in inches the robot wants to stay from an object
+	static constexpr int kHoldDistance = 12;
+
+	// Factor to convert sensor values to a distance in inches
+	static constexpr double kValueToInches = 0.125;
+
+	// proportional speed constant
+	static constexpr double kP = 7.0;
+
+	// integral speed constant
+	static constexpr double kI = 0.018;
+
+	// derivative speed constant
+	static constexpr double kD = 1.5;
+
+	static constexpr int kLeftMotorPort = 0;
+	static constexpr int kRightMotorPort = 1;
+	static constexpr int kUltrasonicPort = 0;
+
+	frc::AnalogInput m_ultrasonic{kUltrasonicPort};
+
+	frc::Spark m_left{kLeftMotorPort};
+	frc::Spark m_right{kRightMotorPort};
+	frc::DifferentialDrive m_robotDrive{m_left, m_right};
+
+	frc::PIDController m_pidController{kP, kI, kD, &m_ultrasonic,
+			new MyPIDOutput(m_robotDrive)};
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Commands/ExampleCommand.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Commands/ExampleCommand.cpp
new file mode 100644
index 0000000..86bd891
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Commands/ExampleCommand.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ExampleCommand.h"
+
+ExampleCommand::ExampleCommand() {
+	// Use Requires() here to declare subsystem dependencies
+	// eg. Requires(&Robot::chassis);
+}
+
+// Called just before this Command runs the first time
+void ExampleCommand::Initialize() {}
+
+// Called repeatedly when this Command is scheduled to run
+void ExampleCommand::Execute() {}
+
+// Make this return true when this Command no longer needs to run execute()
+bool ExampleCommand::IsFinished() {
+	return false;
+}
+
+// Called once after isFinished returns true
+void ExampleCommand::End() {}
+
+// Called when another command which requires one or more of the same
+// subsystems is scheduled to run
+void ExampleCommand::Interrupted() {}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Commands/ExampleCommand.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Commands/ExampleCommand.h
new file mode 100644
index 0000000..44a9e5c
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Commands/ExampleCommand.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+class ExampleCommand : public frc::Command {
+public:
+	ExampleCommand();
+	void Initialize() override;
+	void Execute() override;
+	bool IsFinished() override;
+	void End() override;
+	void Interrupted() override;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Commands/MyAutoCommand.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Commands/MyAutoCommand.cpp
new file mode 100644
index 0000000..f548b68
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Commands/MyAutoCommand.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "MyAutoCommand.h"
+
+MyAutoCommand::MyAutoCommand() {
+	// Use Requires() here to declare subsystem dependencies
+	// eg. Requires(&Robot::chassis);
+}
+
+// Called just before this Command runs the first time
+void MyAutoCommand::Initialize() {}
+
+// Called repeatedly when this Command is scheduled to run
+void MyAutoCommand::Execute() {}
+
+// Make this return true when this Command no longer needs to run execute()
+bool MyAutoCommand::IsFinished() {
+	return false;
+}
+
+// Called once after isFinished returns true
+void MyAutoCommand::End() {}
+
+// Called when another command which requires one or more of the same
+// subsystems is scheduled to run
+void MyAutoCommand::Interrupted() {}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Commands/MyAutoCommand.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Commands/MyAutoCommand.h
new file mode 100644
index 0000000..452753b
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Commands/MyAutoCommand.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Command.h>
+
+class MyAutoCommand : public frc::Command {
+public:
+	MyAutoCommand();
+	void Initialize() override;
+	void Execute() override;
+	bool IsFinished() override;
+	void End() override;
+	void Interrupted() override;
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/OI.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/OI.cpp
new file mode 100644
index 0000000..bc51ff6
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/OI.cpp
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "OI.h"
+
+#include <WPILib.h>
+
+OI::OI() {
+	// Process operator interface input here.
+}
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/OI.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/OI.h
new file mode 100644
index 0000000..345b25a
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/OI.h
@@ -0,0 +1,13 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+class OI {
+public:
+	OI();
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Robot.cpp
new file mode 100644
index 0000000..d54d8fc
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Robot.cpp
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <Commands/Command.h>
+#include <Commands/Scheduler.h>
+#include <LiveWindow/LiveWindow.h>
+#include <SmartDashboard/SendableChooser.h>
+#include <SmartDashboard/SmartDashboard.h>
+#include <TimedRobot.h>
+
+#include "Commands/ExampleCommand.h"
+#include "Commands/MyAutoCommand.h"
+
+class Robot : public frc::TimedRobot {
+public:
+	void RobotInit() override {
+		m_chooser.AddDefault("Default Auto", &m_defaultAuto);
+		m_chooser.AddObject("My Auto", &m_myAuto);
+		frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
+	}
+
+	/**
+	 * This function is called once each time the robot enters Disabled
+	 * mode.
+	 * You can use it to reset any subsystem information you want to clear
+	 * when
+	 * the robot is disabled.
+	 */
+	void DisabledInit() override {}
+
+	void DisabledPeriodic() override {
+		frc::Scheduler::GetInstance()->Run();
+	}
+
+	/**
+	 * This autonomous (along with the chooser code above) shows how to
+	 * select
+	 * between different autonomous modes using the dashboard. The sendable
+	 * chooser code works with the Java SmartDashboard. If you prefer the
+	 * LabVIEW Dashboard, remove all of the chooser code and uncomment the
+	 * GetString code to get the auto name from the text box below the Gyro.
+	 *
+	 * You can add additional auto modes by adding additional commands to
+	 * the
+	 * chooser code above (like the commented example) or additional
+	 * comparisons
+	 * to the if-else structure below with additional strings & commands.
+	 */
+	void AutonomousInit() override {
+		std::string autoSelected = frc::SmartDashboard::GetString(
+				"Auto Selector", "Default");
+		if (autoSelected == "My Auto") {
+			m_autonomousCommand = &m_myAuto;
+		} else {
+			m_autonomousCommand = &m_defaultAuto;
+		}
+
+		m_autonomousCommand = m_chooser.GetSelected();
+
+		if (m_autonomousCommand != nullptr) {
+			m_autonomousCommand->Start();
+		}
+	}
+
+	void AutonomousPeriodic() override {
+		frc::Scheduler::GetInstance()->Run();
+	}
+
+	void TeleopInit() override {
+		// This makes sure that the autonomous stops running when
+		// teleop starts running. If you want the autonomous to
+		// continue until interrupted by another command, remove
+		// this line or comment it out.
+		if (m_autonomousCommand != nullptr) {
+			m_autonomousCommand->Cancel();
+			m_autonomousCommand = nullptr;
+		}
+	}
+
+	void TeleopPeriodic() override { frc::Scheduler::GetInstance()->Run(); }
+
+	void TestPeriodic() override {}
+
+private:
+	// Have it null by default so that if testing teleop it
+	// doesn't have undefined behavior and potentially crash.
+	frc::Command* m_autonomousCommand = nullptr;
+	ExampleCommand m_defaultAuto;
+	MyAutoCommand m_myAuto;
+	frc::SendableChooser<frc::Command*> m_chooser;
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/RobotMap.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/RobotMap.h
new file mode 100644
index 0000000..dd78a21
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/RobotMap.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/**
+ * The RobotMap is a mapping from the ports sensors and actuators are wired into
+ * to a variable name. This provides flexibility changing wiring, makes checking
+ * the wiring easier and significantly reduces the number of magic numbers
+ * floating around.
+ */
+
+// For example to map the left and right motors, you could define the
+// following variables to use with your drivetrain subsystem.
+// constexpr int kLeftMotor = 1;
+// constexpr int kRightMotor = 2;
+
+// If you are using multiple modules, make sure to define both the port
+// number and the module. For example you with a rangefinder:
+// constexpr int kRangeFinderPort = 1;
+// constexpr int kRangeFinderModule = 1;
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Subsystems/ExampleSubsystem.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Subsystems/ExampleSubsystem.cpp
new file mode 100644
index 0000000..da13125
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Subsystems/ExampleSubsystem.cpp
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ExampleSubsystem.h"
+
+#include "../RobotMap.h"
+
+ExampleSubsystem::ExampleSubsystem()
+    : frc::Subsystem("ExampleSubsystem") {}
+
+void ExampleSubsystem::InitDefaultCommand() {
+	// Set the default command for a subsystem here.
+	// SetDefaultCommand(new MySpecialCommand());
+}
+
+// Put methods for controlling this subsystem
+// here. Call these from Commands.
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Subsystems/ExampleSubsystem.h b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Subsystems/ExampleSubsystem.h
new file mode 100644
index 0000000..d64acb0
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/commandbased/Subsystems/ExampleSubsystem.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Commands/Subsystem.h>
+
+class ExampleSubsystem : public frc::Subsystem {
+public:
+	ExampleSubsystem();
+	void InitDefaultCommand() override;
+
+private:
+	// It's desirable that everything possible under private except
+	// for methods that implement subsystem capabilities
+};
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/iterative/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/iterative/Robot.cpp
new file mode 100644
index 0000000..c9695e4
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/iterative/Robot.cpp
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <iostream>
+#include <string>
+
+#include <IterativeRobot.h>
+#include <LiveWindow/LiveWindow.h>
+#include <SmartDashboard/SendableChooser.h>
+#include <SmartDashboard/SmartDashboard.h>
+
+class Robot : public frc::IterativeRobot {
+public:
+	void RobotInit() {
+		m_chooser.AddDefault(kAutoNameDefault, kAutoNameDefault);
+		m_chooser.AddObject(kAutoNameCustom, kAutoNameCustom);
+		frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
+	}
+
+	/*
+	 * This autonomous (along with the chooser code above) shows how to
+	 * select
+	 * between different autonomous modes using the dashboard. The sendable
+	 * chooser code works with the Java SmartDashboard. If you prefer the
+	 * LabVIEW Dashboard, remove all of the chooser code and uncomment the
+	 * GetString line to get the auto name from the text box below the Gyro.
+	 *
+	 * You can add additional auto modes by adding additional comparisons to
+	 * the
+	 * if-else structure below with additional strings. If using the
+	 * SendableChooser make sure to add them to the chooser code above as
+	 * well.
+	 */
+	void AutonomousInit() override {
+		m_autoSelected = m_chooser.GetSelected();
+		// m_autoSelected = SmartDashboard::GetString(
+		// 		"Auto Selector", kAutoNameDefault);
+		std::cout << "Auto selected: " << m_autoSelected << std::endl;
+
+		if (m_autoSelected == kAutoNameCustom) {
+			// Custom Auto goes here
+		} else {
+			// Default Auto goes here
+		}
+	}
+
+	void AutonomousPeriodic() {
+		if (m_autoSelected == kAutoNameCustom) {
+			// Custom Auto goes here
+		} else {
+			// Default Auto goes here
+		}
+	}
+
+	void TeleopInit() {}
+
+	void TeleopPeriodic() {}
+
+	void TestPeriodic() {}
+
+private:
+	frc::LiveWindow& m_lw = *LiveWindow::GetInstance();
+	frc::SendableChooser<std::string> m_chooser;
+	const std::string kAutoNameDefault = "Default";
+	const std::string kAutoNameCustom = "My Auto";
+	std::string m_autoSelected;
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/sample/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/sample/Robot.cpp
new file mode 100644
index 0000000..e62e49c
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/sample/Robot.cpp
@@ -0,0 +1,125 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <iostream>
+#include <string>
+
+#include <Drive/DifferentialDrive.h>
+#include <Joystick.h>
+#include <SampleRobot.h>
+#include <SmartDashboard/SendableChooser.h>
+#include <SmartDashboard/SmartDashboard.h>
+#include <Spark.h>
+#include <Timer.h>
+
+/**
+ * This is a demo program showing the use of the DifferentialDrive class.
+ * The SampleRobot class is the base of a robot application that will
+ * automatically call your Autonomous and OperatorControl methods at the right
+ * time as controlled by the switches on the driver station or the field
+ * controls.
+ *
+ * WARNING: While it may look like a good choice to use for your code if you're
+ * inexperienced, don't. Unless you know what you are doing, complex code will
+ * be much more difficult under this system. Use IterativeRobot or Command-Based
+ * instead if you're new.
+ */
+class Robot : public frc::SampleRobot {
+public:
+	Robot() {
+		// Note SmartDashboard is not initialized here, wait until
+		// RobotInit to make SmartDashboard calls
+		m_robotDrive.SetExpiration(0.1);
+	}
+
+	void RobotInit() {
+		m_chooser.AddDefault(kAutoNameDefault, kAutoNameDefault);
+		m_chooser.AddObject(kAutoNameCustom, kAutoNameCustom);
+		frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
+	}
+
+	/*
+	 * This autonomous (along with the chooser code above) shows how to
+	 * select between different autonomous modes using the dashboard. The
+	 * sendable chooser code works with the Java SmartDashboard. If you
+	 * prefer the LabVIEW Dashboard, remove all of the chooser code and
+	 * uncomment the GetString line to get the auto name from the text box
+	 * below the Gyro.
+	 *
+	 * You can add additional auto modes by adding additional comparisons to
+	 * the if-else structure below with additional strings. If using the
+	 * SendableChooser make sure to add them to the chooser code above as
+	 * well.
+	 */
+	void Autonomous() {
+		std::string autoSelected = m_chooser.GetSelected();
+		// std::string autoSelected = frc::SmartDashboard::GetString(
+		// "Auto Selector", kAutoNameDefault);
+		std::cout << "Auto selected: " << autoSelected << std::endl;
+
+		// MotorSafety improves safety when motors are updated in loops
+		// but is disabled here because motor updates are not looped in
+		// this autonomous mode.
+		m_robotDrive.SetSafetyEnabled(false);
+
+		if (autoSelected == kAutoNameCustom) {
+			// Custom Auto goes here
+			std::cout << "Running custom Autonomous" << std::endl;
+
+			// Spin at half speed for two seconds
+			m_robotDrive.ArcadeDrive(0.0, 0.5);
+			frc::Wait(2.0);
+
+			// Stop robot
+			m_robotDrive.ArcadeDrive(0.0, 0.0);
+		} else {
+			// Default Auto goes here
+			std::cout << "Running default Autonomous" << std::endl;
+
+			// Drive forwards at half speed for two seconds
+			m_robotDrive.ArcadeDrive(-0.5, 0.0);
+			frc::Wait(2.0);
+
+			// Stop robot
+			m_robotDrive.ArcadeDrive(0.0, 0.0);
+		}
+	}
+
+	/*
+	 * Runs the motors with arcade steering.
+	 */
+	void OperatorControl() override {
+		m_robotDrive.SetSafetyEnabled(true);
+		while (IsOperatorControl() && IsEnabled()) {
+			// Drive with arcade style (use right stick)
+			m_robotDrive.ArcadeDrive(
+					-m_stick.GetY(), m_stick.GetX());
+
+			// The motors will be updated every 5ms
+			frc::Wait(0.005);
+		}
+	}
+
+	/*
+	 * Runs during test mode
+	 */
+	void Test() override {}
+
+private:
+	// Robot drive system
+	frc::Spark m_leftMotor{0};
+	frc::Spark m_rightMotor{1};
+	frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
+
+	frc::Joystick m_stick{0};
+
+	frc::SendableChooser<std::string> m_chooser;
+	const std::string kAutoNameDefault = "Default";
+	const std::string kAutoNameCustom = "My Auto";
+};
+
+START_ROBOT_CLASS(Robot)
diff --git a/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/timed/Robot.cpp b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/timed/Robot.cpp
new file mode 100644
index 0000000..677a37e
--- /dev/null
+++ b/third_party/allwpilib_2018/wpilibcExamples/src/main/cpp/templates/timed/Robot.cpp
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <iostream>
+#include <string>
+
+#include <LiveWindow/LiveWindow.h>
+#include <SmartDashboard/SendableChooser.h>
+#include <SmartDashboard/SmartDashboard.h>
+#include <TimedRobot.h>
+
+class Robot : public frc::TimedRobot {
+public:
+	void RobotInit() {
+		m_chooser.AddDefault(kAutoNameDefault, kAutoNameDefault);
+		m_chooser.AddObject(kAutoNameCustom, kAutoNameCustom);
+		frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
+	}
+
+	/*
+	 * This autonomous (along with the chooser code above) shows how to
+	 * select between different autonomous modes using the dashboard. The
+	 * sendable chooser code works with the Java SmartDashboard. If you
+	 * prefer the LabVIEW Dashboard, remove all of the chooser code and
+	 * uncomment the GetString line to get the auto name from the text box
+	 * below the Gyro.
+	 *
+	 * You can add additional auto modes by adding additional comparisons to
+	 * the if-else structure below with additional strings. If using the
+	 * SendableChooser make sure to add them to the chooser code above as
+	 * well.
+	 */
+	void AutonomousInit() override {
+		m_autoSelected = m_chooser.GetSelected();
+		// m_autoSelected = SmartDashboard::GetString("Auto Selector",
+		//		 kAutoNameDefault);
+		std::cout << "Auto selected: " << m_autoSelected << std::endl;
+
+		if (m_autoSelected == kAutoNameCustom) {
+			// Custom Auto goes here
+		} else {
+			// Default Auto goes here
+		}
+	}
+
+	void AutonomousPeriodic() {
+		if (m_autoSelected == kAutoNameCustom) {
+			// Custom Auto goes here
+		} else {
+			// Default Auto goes here
+		}
+	}
+
+	void TeleopInit() {}
+
+	void TeleopPeriodic() {}
+
+	void TestPeriodic() {}
+
+private:
+	frc::LiveWindow& m_lw = *LiveWindow::GetInstance();
+	frc::SendableChooser<std::string> m_chooser;
+	const std::string kAutoNameDefault = "Default";
+	const std::string kAutoNameCustom = "My Auto";
+	std::string m_autoSelected;
+};
+
+START_ROBOT_CLASS(Robot)