Squashed 'third_party/allwpilib_2016/' changes from 7f61816..3ce6feb

3ce6feb Updated release number for the new release
e054bbc This adds StopMotor() to the SpeedController interface for C++ and Java. For Java, this is as simple as just adding it, as all motors already have an implementation from MotorSafety that is correctly resolved. For C++, I had to override StopMotor in the classes that descend from SafePWM and explicitly call the SafePWM version. RobotDrive now calls StopMotor on each of its SpeedControllers, instead of calling Disable or setting the motor to 0.0 as it was doing previously.
a15b9dc Merge "More updates to the Gyro test fixing potential null pointer exception"
21b7213 Added Config routine to allow enabling/disabling of limit switch and soft limits.  This improves upon the ConfigLimitMode routine, which does not allow certain combinations of enable/disabled limit features. Also keeps parity with LV and Java.
1b45237 Merge "Add an additional member variable for "stopped" which indicates the CAN motor controller has been explicitly stopped, but not disabled by the user (main use case is MotorSafety tripping). When Set() is called the next time the controller will be re-enabled automatically."
1096b15 Add an additional member variable for "stopped" which indicates the CAN motor controller has been explicitly stopped, but not disabled by the user (main use case is MotorSafety tripping). When Set() is called the next time the controller will be re-enabled automatically.
7da21fa More updates to the Gyro test fixing potential null pointer exception
ede5862 Rate-limit duplicate error messages to avoid flooding console.
c22284d Merge "artf4818: Fix CAN Talon JNI references with underscores."
cac3741 Merge "Updated PDP port of Talon and disabled PDP tests for Victor and Jaguar since the Victor and Jaguar don't draw enough current for the PDP to read above 0. PDP tests for both java and cpp only test the Talon now."
097aa8c Fixed the gyro deviation over time test
1d647b3 artf4818: Fix CAN Talon JNI references with underscores.
368cfc7 Merge "Fixed the motor tests by reducing speed to within the limits of the encoders we use. Also fixed java pid tolerances since getAvgError() was broken. It is now fixed and works properly. Added tests for both java and cpp that test if pid tolerances are working using fake input output pairs."
833e459 Updated PDP port of Talon and disabled PDP tests for Victor and Jaguar since the Victor and Jaguar don't draw enough current for the PDP to read above 0. PDP tests for both java and cpp only test the Talon now.
6c096a3 Fixed the motor tests by reducing speed to within the limits of the encoders we use. Also fixed java pid tolerances since getAvgError() was broken. It is now fixed and works properly. Added tests for both java and cpp that test if pid tolerances are working using fake input output pairs.
dd7eb0f Fixed robot drive for C++ Simulation
258a622 Merge "Update version number for Release 3 Print distinctive message on robot program startup Change-Id: Ic91b81bd298ee6730503933cf0e733702e4b4405"
b1386c6 Update version number for Release 3 Print distinctive message on robot program startup Change-Id: Ic91b81bd298ee6730503933cf0e733702e4b4405
a58de40 Merge "Removed publishing of java sim jar"
792d0d3 PDP Classes should support any PDP address
35df955 Merge "Remove maven local as a possible search location"
a0ce9ee Another improvement to HAL-joy getting to ensure it works in future RIO image updates.
0f02c31 Removed publishing of java sim jar
8435ac7 DriverStation::GetJoystickName(): Make work for stick>0.
b4cf4f4 Remove maven local as a possible search location
c3000c3 Merge "Fix HALGetJoystickDescriptor()."
4dec0b4 Merge "Fixed Simulation C++ API"
abc9c27 Fixed Simulation C++ API
b8ae9ec Fix HALGetJoystickDescriptor().
a60f874 Artf4800: Fixes HALGetJoystick*** Segfault
010b584 Merge "fix sim_ds launch script"
4429e16 Merge "Added build dir specification for sim javadoc to not overwrite athena javadoc"
ec9349b Initialized the m_sensors variable to fix artf4798.
9745af8 Added build dir specification for sim javadoc to not overwrite athena javadoc
4da8702 fix sim_ds launch script
05acf79 Fix C++ PIDController SetToleranceBuffer and OnTarget locking.
94a6b05 Merge "Fix onTarget() so that it returns false until there are any values retrieved"
d06053d Fix onTarget() so that it returns false until there are any values retrieved
74927cc Correctly set smart dashboard type for AnalogGyro and ADXRS450_Gyro.
070752f Merge "Fixed sim_ds script library path"
21a8bab Merge "PIDController feed forward term can now be calculated by the end user"
56bd6da Fixed sim_ds script library path
07710f1 Merge "Fixing install script... again"
e1cb61f Use absolute path for NT persistent storage.
09c7482 Fixing install script... again
a3b8bec PIDController feed forward term can now be calculated by the end user
790adb0 artf2612: Update license in source files.
042671c Merge "Removed gz_msgs from wpilibcSim"
c111690 Ultrasonic: replace linked list with std::set.
d71a8ed Removed gz_msgs from wpilibcSim
37259f7 Merge "Replaced linked list in Notifier with std::list"
cd17e7a Merge "Renamed Gyro to AnalogGyro to match athena API"
c5c8a87 Replaced linked list in Notifier with std::list
89405d8 Renamed Gyro to AnalogGyro to match athena API
4a19490 Merge "Adds CANTalon to LiveWindow"
c4a3567 Merge "Fixing the frcsim installer script"
295648f Adds CANTalon to LiveWindow
1b964a2 Merge "Fixes CAN devices in C++ library not showing in the livewindow"
7ba5cee Merge "HAL: Use extern "C" in implementation files."
d17d242 Fixes CAN devices in C++ library not showing in the livewindow
25a771a Added linear digital filters
7349c2c Fixing the frcsim installer script
c82122c Merge "Default bufLength for PIDController in Java should be 1"
58f3f97 Merge "Adds WaitResult to Java waitForInterrupt"
bc8ed12 HAL: Use extern "C" in implementation files.
4cac89e Default bufLength for PIDController in Java should be 1
64fcdcc Keep track of FPGA time rollovers with 64-bit time.
d30b283 Merge "Change C++ Notifier to allow std::function callback."
6ee3052 Merge "Rewrite C++ Notifier to use HAL multi-notifier support."
f5d09e2 Merge "Rewrite Java Notifier and update Interrupt JNI."
d0274aa Merge "Readded styleguide accidentally removed in the reorg"
68311ad Merge "Artf4179: Allow alternate I2C addresses for ADXL345_I2C"
dee12d4 Readded styleguide accidentally removed in the reorg
fa100df Fixed some typos in the comments of MotorEncoderFixture.java, a method name in CANMotorEncoderFixture.java, and the README files
3397b5c Adds WaitResult to Java waitForInterrupt
5f0dffd Artf4177: Use read byte count for ReadString
8564f33 Artf4179: Allow alternate I2C addresses for ADXL345_I2C
e52b52d Change C++ Notifier to allow std::function callback.
40b29e7 Rewrite C++ Notifier to use HAL multi-notifier support.
d126f45 Rewrite Java Notifier and update Interrupt JNI.
557805a Merge "finishing up FRCSim installer"
911b64b finishing up FRCSim installer
e24fe6f Merge "Artf4776 Fixes First DIO PWM usage errors"
f8f9284 Merge "Artf4774 Fixes HAL getHALErrorMessage missing error"
84428d5 Merge "Prevent double free in DigitalGlitchFilter"
a00a5ff Merge "Set correct error message"
9aeee98 Prevent double free in DigitalGlitchFilter
5d2186c working on install process for FRCSim 2016
7fdb616 Merge "This commit adds documentation generation, including grabbing ntcore sources, for both Java and C++. This will need changes made in the wpilib promotion tasks to copy the generatd documentation to the correct places."
f67ebca Improved READMEs
8a7c019 Artf4776 Fixes First DIO PWM usage errors
1cd2f9a Added libnipalu to make vision programs link properly
375b92a This commit adds documentation generation, including grabbing ntcore sources, for both Java and C++. This will need changes made in the wpilib promotion tasks to copy the generatd documentation to the correct places.
8d0a990 Set correct error message
b65401f Artf4774 Fixes HAL getHALErrorMessage missing error
5f918be Condition java sim build on -PmakeSim flag
53bd180 Merge "Add SPARK and SD540 motor controllers"
66cbe69 Fixed double free of DriverStation.
431f345 Repaired simulation build on linux
611593c Add Cmake wrappers and unzip desktop ntcore builds
51a18cd Add SPARK and SD540 motor controllers
c05e883 Merge changes I55ce71c6,I803680c1
2b80029 Rewrite CANTalon JNI layer.
ef4c45b Last feature addition for CANTalon java/C++ user-facing API.

Change-Id: Ia3a124978a426991890b6f8abbe07d34d75ba38d
git-subtree-dir: third_party/allwpilib_2016
git-subtree-split: 3ce6feb8acdeca46e93a55280fb6ace3a4d5bcd6
diff --git a/.gitignore b/.gitignore
index 7d0fcc8..bd7869d 100644
--- a/.gitignore
+++ b/.gitignore
@@ -175,3 +175,9 @@
 
 #catkin stuff
 package.xml
+
+# Doxygen stuff
+NO
+
+# Simulation folder stuff
+!simulation/install_resources/*
diff --git a/BSD_License_for_WPILib_code.txt b/BSD_License_for_WPILib_code.txt
new file mode 100644
index 0000000..5d3484b
--- /dev/null
+++ b/BSD_License_for_WPILib_code.txt
@@ -0,0 +1,24 @@
+* Copyright (c) 2009-2016 FIRST
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions are met:
+*     * Redistributions of source code must retain the above copyright
+*       notice, this list of conditions and the following disclaimer.
+*     * Redistributions in binary form must reproduce the above copyright
+*       notice, this list of conditions and the following disclaimer in the
+*       documentation and/or other materials provided with the distribution.
+*     * Neither the name of the FIRST nor the
+*       names of its contributors may be used to endorse or promote products
+*       derived from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY FIRST AND CONTRIBUTORS``AS IS'' AND ANY
+* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+* WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR 
+* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR 
+* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 107a338..ff6b504 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -5,27 +5,9 @@
 include (FindPkgConfig)
 include(GNUInstallDirs)
 
-#copied from GazeboUtils.cmake
-macro (APPEND_TO_CACHED_STRING _string _cacheDesc)
-  FOREACH (newItem ${ARGN})
-    SET (${_string} "${${_string}} ${newItem}" CACHE INTERNAL ${_cacheDesc} FORCE)
-  ENDFOREACH (newItem ${ARGN})
-endmacro (APPEND_TO_CACHED_STRING)
-
 #check for depenedencies
 find_package(gazebo REQUIRED)
 find_package(Boost COMPONENTS system filesystem REQUIRED)
-find_package(Protobuf REQUIRED)
-
-if (NOT PROTOBUF_FOUND)
-	MESSAGE ("Missing: Google Protobuf (libprotobuf-dev)")
-endif()
-if (NOT PROTOBUF_PROTOC_EXECUTABLE)
-	MESSAGE ( "Missing: Google Protobuf Compiler (protobuf-compiler)")
-endif()
-if (NOT PROTOBUF_PROTOC_LIBRARY)
-	MESSAGE ("Missing: Google Protobuf Compiler Library (libprotoc-dev)")
-endif()
 
 #on windows we produce .dlls with no prefix
 if(WIN32)
@@ -48,12 +30,10 @@
 if (MSVC)
   set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DFRC_SIMULATOR /MDd /Zi")
 else ()
-  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++1y -DFRC_SIMULATOR -Wno-unused-parameter -pthread -fPIC -fpermissive")
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g -std=c++1y -DFRC_SIMULATOR -Wno-unused-parameter -pthread -fPIC -fpermissive")
 endif()
 
-
 include_directories("build")
 add_subdirectory(simulation/gz_msgs)
 add_subdirectory(wpilibc/simulation)
 add_subdirectory(simulation/frc_gazebo_plugins)
-add_subdirectory(ntcore)
diff --git a/README.md b/README.md
index e21eccf..0826983 100644
--- a/README.md
+++ b/README.md
@@ -22,6 +22,24 @@
 ./gradlew :wpilibc:build
 ```
 
+If you also want simulation to be build, add -PmakeSim. This requires gazebo_transport. We have tested on 14.04 and 15.05, but any correct install of gazebo should work, even on windows if you build from source. Correct means cmake needs to be able to find gazebo-config.cmake, which you get for free with ubuntu installs.
+
+```bash
+./gradlew build -PmakeSim
+```
+
+C++ simulation tasks (including plugins, gz_msgs, and wpilibcSim) all depend on gazebo_transport. In order for this to build you must have installed gazebo. See [The Gazebo website](https://gazebosim.org/) for installation instructions.
+If you prefer to use CMake directly, the you can still do so.
+The common cmake tasks are wpilibcSim, frc_gazebo_plugins, and gz_msgs
+
+```bash
+mkdir build #run this in the root of allwpilib
+cd build
+cmake ..
+make
+```
+
+
 The gradlew wrapper only exists in the root of the main project, so be sure to run all commands from there. All of the subprojects have build tasks that can be run. Gradle automatically determines and rebuilds dependencies, so if you make a change to the HAL and then run `:wpilibc:build`, the HAL will be rebuilt, then wpilibc.
 
 There are a few tasks other than `build` available. To see them, run the meta-task `tasks`. This will print a list of all available tasks, with a description of each task.
@@ -42,3 +60,14 @@
 - edu.wpi.first.wpilibj:wpilibJavaSim:0.1.0-SNAPSHOT - Simulation Java
 - edu.wpi.first.wpilibj.simulation:SimDS:0.1.0-SNAPSHOT - The driverstation for controlling simulation.
 - org.gazebosim:JavaGazebo:0.1.0-SNAPSHOT - Gazebo protocol for Java.
+
+## Structure and Organization
+The main wpilib code you're probably looking for is in wpilibj and wpilibc. Those directories are split into shared, sim, and athena. Athena contains the wpilib code meant to run on your RoboRIO. Sim is wpilib code meant to run on your computer with gazebo, and shared is code shared between the two. Shared code must be platform-independent, since it will be compiled with both the ARM cross-compiler and whatever desktop compiler you are using (g++, msvc, etc...).
+
+The Simulation directory contains extra simulation tools and libraries, such as gz_msgs and JavaGazebo. See sub-directories for more information.
+
+The integration test directories for C++ and Java contain test code that runs on our test-system. When you submit code for review, it is tested by those programs. If you add new functionality you should make sure to write tests for it so we don't break it in the future.
+
+The hal directory contains more C++ code meant to run on the RoboRIO. HAL is an acronym for "Hardware Abstraction Layer", and it interfaces with the NI Libraries. The NI Libraries contain the low-level code for controlling devices on your robot. The NI Libraries are found in the ni-libraries folder.
+
+The styleguide directory contains the styleguide for C++ and Java code. Anything submitted to the wpilib project needs to follow the code style guides outlined in there.
\ No newline at end of file
diff --git a/build.gradle b/build.gradle
index d399ffd..a6f9cbe 100644
--- a/build.gradle
+++ b/build.gradle
@@ -7,6 +7,8 @@
 def repoBaseUrl = "http://first.wpi.edu/FRC/roborio/maven/${repo}"
 def publishUrl = "${System.getProperty('user.home')}/releases/maven/${repo}"
 
+ext.simulationInstallDir = "$rootDir/build/install/simulation"
+
 allprojects {
     ext.enableSimulation = enableSimulation
     ext.repo = repo
@@ -16,7 +18,6 @@
         maven {
             url publishUrl
         }
-        mavenLocal()
         maven {
             url repoBaseUrl
         }
@@ -43,4 +44,4 @@
     }
 }
 
-apply from: 'cppSettings.gradle'
\ No newline at end of file
+apply from: 'cppSettings.gradle'
diff --git a/cppSettings.gradle b/cppSettings.gradle
index 71d54ef..77c4ece 100644
--- a/cppSettings.gradle
+++ b/cppSettings.gradle
@@ -19,11 +19,20 @@
     }
 }
 
-def ntDependency =
+def armNtDependency =
     project.dependencies.create("edu.wpi.first.wpilib.networktables.cpp:NetworkTables:3.0.0-SNAPSHOT:arm@zip")
-def config = project.configurations.detachedConfiguration(ntDependency)
-config.setTransitive(false)
-def netTables = config.files[0].canonicalFile
+def armConfig = project.configurations.detachedConfiguration(armNtDependency)
+armConfig.setTransitive(false)
+def armNetTables = armConfig.files[0].canonicalFile
+
+def desktopNetTables
+if (project.hasProperty('makeSim')){
+    def desktopNtDependency =
+        project.dependencies.create("edu.wpi.first.wpilib.networktables.cpp:NetworkTables:3.0.0-SNAPSHOT:desktop@zip")
+    def desktopConfig = project.configurations.detachedConfiguration(desktopNtDependency)
+    desktopConfig.setTransitive(false)
+    desktopNetTables = desktopConfig.files[0].canonicalFile
+}
 
 def netTablesUnzipLocation = "$buildDir/networktables"
 
@@ -31,7 +40,10 @@
 task unzipNetworkTables(type: Copy) {
     description = 'Unzips the networktables maven dependency so that the include files and libraries can be used'
     group = 'WPILib'
-    from zipTree(netTables)
+    if (project.hasProperty('makeSim')){
+        from zipTree(desktopNetTables)
+    }
+    from zipTree(armNetTables)
     into netTablesUnzipLocation
 }
 
@@ -47,9 +59,12 @@
         ext.defineNetworkTablesProperties = {
             ext.netTables = netTablesUnzipLocation
             ext.netTablesInclude = "$netTablesUnzipLocation/include"
-            ext.netLibLocation = "$netTablesUnzipLocation/Linux/arm"
-            ext.netSharedLib = "$netLibLocation/libntcore.so"
-            ext.netStaticLib = "$netLibLocation/libntcore.a"
+            ext.netLibArmLocation = "$netTablesUnzipLocation/Linux/arm"
+            if (project.hasProperty('makeSim')){
+              ext.netLibDesktopLocation = "$netTablesUnzipLocation/Linux/amd64"
+            }
+            ext.netSharedLib = "$netLibArmLocation/libntcore.so"
+            ext.netStaticLib = "$netLibArmLocation/libntcore.a"
 
             task addNetworkTablesLibraryLinks() {
                 description = 'Adds the linker flags for the networktables libraries retreived from maven'
diff --git a/hal/include/HAL/CanTalonSRX.h b/hal/include/HAL/CanTalonSRX.h
index 4cbff71..87e2bf0 100644
--- a/hal/include/HAL/CanTalonSRX.h
+++ b/hal/include/HAL/CanTalonSRX.h
@@ -1,421 +1,829 @@
-/**

- * @brief CAN TALON SRX driver.

- *

- * The TALON SRX is designed to instrument all runtime signals periodically.  The default periods are chosen to support 16 TALONs

- * with 10ms update rate for control (throttle or setpoint).  However these can be overridden with SetStatusFrameRate. @see SetStatusFrameRate

- * The getters for these unsolicited signals are auto generated at the bottom of this module.

- *

- * Likewise most control signals are sent periodically using the fire-and-forget CAN API.

- * The setters for these unsolicited signals are auto generated at the bottom of this module.

- *

- * Signals that are not available in an unsolicited fashion are the Close Loop gains.

- * For teams that have a single profile for their TALON close loop they can use either the webpage to configure their TALONs once

- * 	or set the PIDF,Izone,CloseLoopRampRate,etc... once in the robot application.  These parameters are saved to flash so once they are

- * 	loaded in the TALON, they will persist through power cycles and mode changes.

- *

- * For teams that have one or two profiles to switch between, they can use the same strategy since there are two slots to choose from

- * and the ProfileSlotSelect is periodically sent in the 10 ms control frame.

- *

- * For teams that require changing gains frequently, they can use the soliciting API to get and set those parameters.  Most likely

- * they will only need to set them in a periodic fashion as a function of what motion the application is attempting.

- * If this API is used, be mindful of the CAN utilization reported in the driver station.

- *

- * Encoder position is measured in encoder edges.  Every edge is counted (similar to roboRIO 4X mode).

- * Analog position is 10 bits, meaning 1024 ticks per rotation (0V => 3.3V).

- * Use SetFeedbackDeviceSelect to select which sensor type you need.  Once you do that you can use GetSensorPosition()

- * and GetSensorVelocity().  These signals are updated on CANBus every 20ms (by default).

- * If a relative sensor is selected, you can zero (or change the current value) using SetSensorPosition.

- *

- * Analog Input and quadrature position (and velocity) are also explicitly reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel.

- * These signals are available all the time, regardless of what sensor is selected at a rate of 100ms.  This allows easy instrumentation

- * for "in the pits" checking of all sensors regardless of modeselect.  The 100ms rate is overridable for teams who want to acquire sensor

- * data for processing, not just instrumentation.  Or just select the sensor using SetFeedbackDeviceSelect to get it at 20ms.

- *

- * Velocity is in position ticks / 100ms.

- *

- * All output units are in respect to duty cycle (throttle) which is -1023(full reverse) to +1023 (full forward).

- *  This includes demand (which specifies duty cycle when in duty cycle mode) and rampRamp, which is in throttle units per 10ms (if nonzero).

- *

- * Pos and velocity close loops are calc'd as

- * 		err = target - posOrVel.

- * 		iErr += err;

- * 		if(   (IZone!=0)  and  abs(err) > IZone)

- * 			ClearIaccum()

- * 		output = P X err + I X iErr + D X dErr + F X target

- * 		dErr = err - lastErr

- *	P, I,and D gains are always positive. F can be negative.

- *	Motor direction can be reversed using SetRevMotDuringCloseLoopEn if sensor and motor are out of phase.

- *	Similarly feedback sensor can also be reversed (multiplied by -1) if you prefer the sensor to be inverted.

- *

- * P gain is specified in throttle per error tick.  For example, a value of 102 is ~9.9% (which is 102/1023) throttle per 1

- * 		ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.

- *

- * I gain is specified in throttle per integrated error. For example, a value of 10 equates to ~0.99% (which is 10/1023)

- *  	for each accumulated ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.

- *  	Close loop and integral accumulator runs every 1ms.

- *

- * D gain is specified in throttle per derivative error. For example a value of 102 equates to ~9.9% (which is 102/1023)

- * 	per change of 1 unit (ADC or encoder) per ms.

- *

- * I Zone is specified in the same units as sensor position (ADC units or quadrature edges).  If pos/vel error is outside of

- * 		this value, the integrated error will auto-clear...

- * 		if(   (IZone!=0)  and  abs(err) > IZone)

- * 			ClearIaccum()

- * 		...this is very useful in preventing integral windup and is highly recommended if using full PID to keep stability low.

- *

- * CloseLoopRampRate is in throttle units per 1ms.  Set to zero to disable ramping.

- * 		Works the same as RampThrottle but only is in effect when a close loop mode and profile slot is selected.

- *

- * auto generated using spreadsheet and WpiClassGen.csproj

- * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967

- */

-#ifndef CanTalonSRX_H_

-#define CanTalonSRX_H_

-#include "ctre/ctre.h"				//BIT Defines + Typedefs

-#include "ctre/CtreCanNode.h"

-#include <FRC_NetworkCommunication/CANSessionMux.h>	//CAN Comm

-#include <map>

-#include <atomic>

-class CanTalonSRX : public CtreCanNode

-{

-private:

-  // Use this for determining whether the default move constructor has been

-  // called; this prevents us from calling the destructor twice.

-  struct HasBeenMoved {

-    HasBeenMoved(HasBeenMoved&& other) {

-      other.moved = true;

-      moved = false;

-    }

-    HasBeenMoved() = default;

-    std::atomic<bool> moved{false};

-    operator bool() const { return moved; }

-  } m_hasBeenMoved;

-

-	//---------------------- Vars for opening a CAN stream if caller needs signals that require soliciting */

-	uint32_t _can_h; 	//!< Session handle for catching response params.

-	int32_t _can_stat; //!< Session handle status.

-	struct tCANStreamMessage _msgBuff[20];

-	static int const kMsgCapacity	= 20;

-	typedef std::map<uint32_t, uint32_t> sigs_t;

-	sigs_t _sigs; //!< Catches signal updates that are solicited.  Expect this to be very few.

-	void OpenSessionIfNeedBe();

-	void ProcessStreamMessages();

-	/**

-	 * Send a one shot frame to set an arbitrary signal.

-	 * Most signals are in the control frame so avoid using this API unless you have to.

-	 * Use this api for...

-	 * -A motor controller profile signal eProfileParam_XXXs.  These are backed up in flash.  If you are gain-scheduling then call this periodically.

-	 * -Default brake and limit switch signals... eOnBoot_XXXs.  Avoid doing this, use the override signals in the control frame.

-	 * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms.

-	 */

-	CTR_Code SetParamRaw(uint32_t paramEnum, int32_t rawBits);

-	/**

-	 * Checks cached CAN frames and updating solicited signals.

-	 */

-	CTR_Code GetParamResponseRaw(uint32_t paramEnum, int32_t & rawBits);

-public:

-	static const int kDefaultControlPeriodMs = 10; //!< default control update rate is 10ms.

-	CanTalonSRX(int deviceNumber = 0,int controlPeriodMs = kDefaultControlPeriodMs);

-	~CanTalonSRX();

-	void Set(double value);

-	/* mode select enumerations */

-	static const int kMode_DutyCycle = 0; //!< Demand is 11bit signed duty cycle [-1023,1023].

-	static const int kMode_PositionCloseLoop = 1; //!< Position PIDF.

-	static const int kMode_VelocityCloseLoop = 2; //!< Velocity PIDF.

-	static const int kMode_CurrentCloseLoop = 3; //!< Current close loop - not done.

-	static const int kMode_VoltCompen = 4; //!< Voltage Compensation Mode - not done.  Demand is fixed pt target 8.8 volts.

-	static const int kMode_SlaveFollower = 5; //!< Demand is the 6 bit Device ID of the 'master' TALON SRX.

-	static const int kMode_NoDrive = 15; //!< Zero the output (honors brake/coast) regardless of demand.  Might be useful if we need to change modes but can't atomically change all the signals we want in between.

-	/* limit switch enumerations */

-	static const int kLimitSwitchOverride_UseDefaultsFromFlash = 1;

-	static const int kLimitSwitchOverride_DisableFwd_DisableRev = 4;

-	static const int kLimitSwitchOverride_DisableFwd_EnableRev = 5;

-	static const int kLimitSwitchOverride_EnableFwd_DisableRev = 6;

-	static const int kLimitSwitchOverride_EnableFwd_EnableRev = 7;

-	/* brake override enumerations */

-	static const int kBrakeOverride_UseDefaultsFromFlash = 0;

-	static const int kBrakeOverride_OverrideCoast = 1;

-	static const int kBrakeOverride_OverrideBrake = 2;

-	/* feedback device enumerations */

-	static const int kFeedbackDev_DigitalQuadEnc=0;

-	static const int kFeedbackDev_AnalogPot=2;

-	static const int kFeedbackDev_AnalogEncoder=3;

-	static const int kFeedbackDev_CountEveryRisingEdge=4;

-	static const int kFeedbackDev_CountEveryFallingEdge=5;

-	static const int kFeedbackDev_PosIsPulseWidth=8;

-	/* ProfileSlotSelect enumerations*/

-	static const int kProfileSlotSelect_Slot0 = 0;

-	static const int kProfileSlotSelect_Slot1 = 1;

-    /* status frame rate types */

-    static const int kStatusFrame_General = 0;

-    static const int kStatusFrame_Feedback = 1;

-    static const int kStatusFrame_Encoder = 2;

-    static const int kStatusFrame_AnalogTempVbat = 3;

-    static const int kStatusFrame_PulseWidthMeas = 4;

-	/**

-	 * Signal enumeration for generic signal access.

-	 * Although every signal is enumerated, only use this for traffic that must be solicited.

-	 * Use the auto generated getters/setters at bottom of this header as much as possible.

-	 */

-	typedef enum _param_t{

-		eProfileParamSlot0_P=1,

-		eProfileParamSlot0_I=2,

-		eProfileParamSlot0_D=3,

-		eProfileParamSlot0_F=4,

-		eProfileParamSlot0_IZone=5,

-		eProfileParamSlot0_CloseLoopRampRate=6,

-		eProfileParamSlot1_P=11,

-		eProfileParamSlot1_I=12,

-		eProfileParamSlot1_D=13,

-		eProfileParamSlot1_F=14,

-		eProfileParamSlot1_IZone=15,

-		eProfileParamSlot1_CloseLoopRampRate=16,

-		eProfileParamSoftLimitForThreshold=21,

-		eProfileParamSoftLimitRevThreshold=22,

-		eProfileParamSoftLimitForEnable=23,

-		eProfileParamSoftLimitRevEnable=24,

-		eOnBoot_BrakeMode=31,

-		eOnBoot_LimitSwitch_Forward_NormallyClosed=32,

-		eOnBoot_LimitSwitch_Reverse_NormallyClosed=33,

-		eOnBoot_LimitSwitch_Forward_Disable=34,

-		eOnBoot_LimitSwitch_Reverse_Disable=35,

-		eFault_OverTemp=41,

-		eFault_UnderVoltage=42,

-		eFault_ForLim=43,

-		eFault_RevLim=44,

-		eFault_HardwareFailure=45,

-		eFault_ForSoftLim=46,

-		eFault_RevSoftLim=47,

-		eStckyFault_OverTemp=48,

-		eStckyFault_UnderVoltage=49,

-		eStckyFault_ForLim=50,

-		eStckyFault_RevLim=51,

-		eStckyFault_ForSoftLim=52,

-		eStckyFault_RevSoftLim=53,

-		eAppliedThrottle=61,

-		eCloseLoopErr=62,

-		eFeedbackDeviceSelect=63,

-		eRevMotDuringCloseLoopEn=64,

-		eModeSelect=65,

-		eProfileSlotSelect=66,

-		eRampThrottle=67,

-		eRevFeedbackSensor=68,

-		eLimitSwitchEn=69,

-		eLimitSwitchClosedFor=70,

-		eLimitSwitchClosedRev=71,

-		eSensorPosition=73,

-		eSensorVelocity=74,

-		eCurrent=75,

-		eBrakeIsEnabled=76,

-		eEncPosition=77,

-		eEncVel=78,

-		eEncIndexRiseEvents=79,

-		eQuadApin=80,

-		eQuadBpin=81,

-		eQuadIdxpin=82,

-		eAnalogInWithOv=83,

-		eAnalogInVel=84,

-		eTemp=85,

-		eBatteryV=86,

-		eResetCount=87,

-		eResetFlags=88,

-		eFirmVers=89,

-		eSettingsChanged=90,

-		eQuadFilterEn=91,

-		ePidIaccum=93,

-		eStatus1FrameRate=94, // TALON_Status_1_General_10ms_t

-		eStatus2FrameRate=95, // TALON_Status_2_Feedback_20ms_t

-		eStatus3FrameRate=96, // TALON_Status_3_Enc_100ms_t

-		eStatus4FrameRate=97, // TALON_Status_4_AinTempVbat_100ms_t

-		eStatus6FrameRate=98, // TALON_Status_6_Eol_t

-		eStatus7FrameRate=99, // TALON_Status_7_Debug_200ms_t

-		eClearPositionOnIdx=100,

-		//reserved,

-		//reserved,

-		//reserved,

-		ePeakPosOutput=104,

-		eNominalPosOutput=105,

-		ePeakNegOutput=106,

-		eNominalNegOutput=107,

-		eQuadIdxPolarity=108,

-		eStatus8FrameRate=109, // TALON_Status_8_PulseWid_100ms_t

-		eAllowPosOverflow=110,

-		eProfileParamSlot0_AllowableClosedLoopErr=111,

-		eNumberPotTurns=112,

-		eNumberEncoderCPR=113,

-		ePwdPosition=114,

-		eAinPosition=115,

-		eProfileParamVcompRate=116,

-		eProfileParamSlot1_AllowableClosedLoopErr=117,

-	}param_t;

-    /*---------------------setters and getters that use the solicated param request/response-------------*//**

-     * Send a one shot frame to set an arbitrary signal.

-     * Most signals are in the control frame so avoid using this API unless you have to.

-     * Use this api for...

-     * -A motor controller profile signal eProfileParam_XXXs.  These are backed up in flash.  If you are gain-scheduling then call this periodically.

-     * -Default brake and limit switch signals... eOnBoot_XXXs.  Avoid doing this, use the override signals in the control frame.

-     * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms.

-     */

-	CTR_Code SetParam(param_t paramEnum, double value);

-	/**

-	 * Asks TALON to immedietely respond with signal value.  This API is only used for signals that are not sent periodically.

-	 * This can be useful for reading params that rarely change like Limit Switch settings and PIDF values.

-	  * @param param to request.

-	 */

-	CTR_Code RequestParam(param_t paramEnum);

-	CTR_Code GetParamResponse(param_t paramEnum, double & value);

-	CTR_Code GetParamResponseInt32(param_t paramEnum, int & value);

-    /*----- getters and setters that use param request/response. These signals are backed up in flash and will survive a power cycle. ---------*/

-	/*----- If your application requires changing these values consider using both slots and switch between slot0 <=> slot1. ------------------*/

-	/*----- If your application requires changing these signals frequently then it makes sense to leverage this API. --------------------------*/

-	/*----- Getters don't block, so it may require several calls to get the latest value. --------------------------*/

-	CTR_Code SetPgain(unsigned slotIdx,double gain);

-	CTR_Code SetIgain(unsigned slotIdx,double gain);

-	CTR_Code SetDgain(unsigned slotIdx,double gain);

-	CTR_Code SetFgain(unsigned slotIdx,double gain);

-	CTR_Code SetIzone(unsigned slotIdx,int zone);

-	CTR_Code SetCloseLoopRampRate(unsigned slotIdx,int closeLoopRampRate);

-	CTR_Code SetVoltageCompensationRate(double voltagePerMs);

-	CTR_Code SetSensorPosition(int pos);

-	CTR_Code SetForwardSoftLimit(int forwardLimit);

-	CTR_Code SetReverseSoftLimit(int reverseLimit);

-	CTR_Code SetForwardSoftEnable(int enable);

-	CTR_Code SetReverseSoftEnable(int enable);

-	CTR_Code GetPgain(unsigned slotIdx,double & gain);

-	CTR_Code GetIgain(unsigned slotIdx,double & gain);

-	CTR_Code GetDgain(unsigned slotIdx,double & gain);

-	CTR_Code GetFgain(unsigned slotIdx,double & gain);

-	CTR_Code GetIzone(unsigned slotIdx,int & zone);

-	CTR_Code GetCloseLoopRampRate(unsigned slotIdx,int & closeLoopRampRate);

-	CTR_Code GetVoltageCompensationRate(double & voltagePerMs);

-	CTR_Code GetForwardSoftLimit(int & forwardLimit);

-	CTR_Code GetReverseSoftLimit(int & reverseLimit);

-	CTR_Code GetForwardSoftEnable(int & enable);

-	CTR_Code GetReverseSoftEnable(int & enable);

-	/**

-	 * Change the periodMs of a TALON's status frame.  See kStatusFrame_* enums for what's available.

-	 */

-	CTR_Code SetStatusFrameRate(unsigned frameEnum, unsigned periodMs);

-	/**

-	 * Clear all sticky faults in TALON.

-	 */

-	CTR_Code ClearStickyFaults();

-    /*------------------------ auto generated.  This API is optimal since it uses the fire-and-forget CAN interface ----------------------*/

-    /*------------------------ These signals should cover the majority of all use cases. ----------------------------------*/

-	CTR_Code GetFault_OverTemp(int &param);

-	CTR_Code GetFault_UnderVoltage(int &param);

-	CTR_Code GetFault_ForLim(int &param);

-	CTR_Code GetFault_RevLim(int &param);

-	CTR_Code GetFault_HardwareFailure(int &param);

-	CTR_Code GetFault_ForSoftLim(int &param);

-	CTR_Code GetFault_RevSoftLim(int &param);

-	CTR_Code GetStckyFault_OverTemp(int &param);

-	CTR_Code GetStckyFault_UnderVoltage(int &param);

-	CTR_Code GetStckyFault_ForLim(int &param);

-	CTR_Code GetStckyFault_RevLim(int &param);

-	CTR_Code GetStckyFault_ForSoftLim(int &param);

-	CTR_Code GetStckyFault_RevSoftLim(int &param);

-	CTR_Code GetAppliedThrottle(int &param);

-	CTR_Code GetCloseLoopErr(int &param);

-	CTR_Code GetFeedbackDeviceSelect(int &param);

-	CTR_Code GetModeSelect(int &param);

-	CTR_Code GetLimitSwitchEn(int &param);

-	CTR_Code GetLimitSwitchClosedFor(int &param);

-	CTR_Code GetLimitSwitchClosedRev(int &param);

-	CTR_Code GetSensorPosition(int &param);

-	CTR_Code GetSensorVelocity(int &param);

-	CTR_Code GetCurrent(double &param);

-	CTR_Code GetBrakeIsEnabled(int &param);

-	CTR_Code GetEncPosition(int &param);

-	CTR_Code GetEncVel(int &param);

-	CTR_Code GetEncIndexRiseEvents(int &param);

-	CTR_Code GetQuadApin(int &param);

-	CTR_Code GetQuadBpin(int &param);

-	CTR_Code GetQuadIdxpin(int &param);

-	CTR_Code GetAnalogInWithOv(int &param);

-	CTR_Code GetAnalogInVel(int &param);

-	CTR_Code GetTemp(double &param);

-	CTR_Code GetBatteryV(double &param);

-	CTR_Code GetResetCount(int &param);

-	CTR_Code GetResetFlags(int &param);

-	CTR_Code GetFirmVers(int &param);

-	CTR_Code SetDemand(int param);

-	CTR_Code SetOverrideLimitSwitchEn(int param);

-	CTR_Code SetFeedbackDeviceSelect(int param);

-	CTR_Code SetRevMotDuringCloseLoopEn(int param);

-	CTR_Code SetOverrideBrakeType(int param);

-	CTR_Code SetModeSelect(int param);

-	CTR_Code SetModeSelect(int modeSelect,int demand);

-	CTR_Code SetProfileSlotSelect(int param);

-	CTR_Code SetRampThrottle(int param);

-	CTR_Code SetRevFeedbackSensor(int param);

-	CTR_Code GetPulseWidthPosition(int &param);

-	CTR_Code GetPulseWidthVelocity(int &param);

-	CTR_Code GetPulseWidthRiseToFallUs(int &param);

-	CTR_Code GetPulseWidthRiseToRiseUs(int &param);

-	CTR_Code IsPulseWidthSensorPresent(int &param);

-};

-extern "C" {

-	void *c_TalonSRX_Create(int deviceNumber, int controlPeriodMs);

-	void c_TalonSRX_Destroy(void *handle);

-	CTR_Code c_TalonSRX_SetParam(void *handle, int paramEnum, double value);

-	CTR_Code c_TalonSRX_RequestParam(void *handle, int paramEnum);

-	CTR_Code c_TalonSRX_GetParamResponse(void *handle, int paramEnum, double *value);

-	CTR_Code c_TalonSRX_GetParamResponseInt32(void *handle, int paramEnum, int *value);

-	CTR_Code c_TalonSRX_SetStatusFrameRate(void *handle, unsigned frameEnum, unsigned periodMs);

-	CTR_Code c_TalonSRX_ClearStickyFaults(void *handle);

-	CTR_Code c_TalonSRX_GetFault_OverTemp(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetFault_UnderVoltage(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetFault_ForLim(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetFault_RevLim(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetFault_HardwareFailure(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetFault_ForSoftLim(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetFault_RevSoftLim(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetStckyFault_OverTemp(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetStckyFault_UnderVoltage(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetStckyFault_ForLim(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetStckyFault_RevLim(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetStckyFault_ForSoftLim(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetStckyFault_RevSoftLim(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetAppliedThrottle(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetCloseLoopErr(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetFeedbackDeviceSelect(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetModeSelect(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetLimitSwitchEn(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetLimitSwitchClosedFor(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetLimitSwitchClosedRev(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetSensorPosition(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetSensorVelocity(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetCurrent(void *handle, double *param);

-	CTR_Code c_TalonSRX_GetBrakeIsEnabled(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetEncPosition(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetEncVel(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetEncIndexRiseEvents(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetQuadApin(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetQuadBpin(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetQuadIdxpin(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetAnalogInWithOv(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetAnalogInVel(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetTemp(void *handle, double *param);

-	CTR_Code c_TalonSRX_GetBatteryV(void *handle, double *param);

-	CTR_Code c_TalonSRX_GetResetCount(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetResetFlags(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetFirmVers(void *handle, int *param);

-	CTR_Code c_TalonSRX_SetDemand(void *handle, int param);

-	CTR_Code c_TalonSRX_SetOverrideLimitSwitchEn(void *handle, int param);

-	CTR_Code c_TalonSRX_SetFeedbackDeviceSelect(void *handle, int param);

-	CTR_Code c_TalonSRX_SetRevMotDuringCloseLoopEn(void *handle, int param);

-	CTR_Code c_TalonSRX_SetOverrideBrakeType(void *handle, int param);

-	CTR_Code c_TalonSRX_SetModeSelect(void *handle, int param);

-	CTR_Code c_TalonSRX_SetModeSelect2(void *handle, int modeSelect, int demand);

-	CTR_Code c_TalonSRX_SetProfileSlotSelect(void *handle, int param);

-	CTR_Code c_TalonSRX_SetRampThrottle(void *handle, int param);

-	CTR_Code c_TalonSRX_SetRevFeedbackSensor(void *handle, int param);

-	CTR_Code c_TalonSRX_GetPulseWidthPosition(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetPulseWidthVelocity(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetPulseWidthRiseToFallUs(void *handle, int *param);

-	CTR_Code c_TalonSRX_GetPulseWidthRiseToRiseUs(void *handle, int *param);

-	CTR_Code c_TalonSRX_IsPulseWidthSensorPresent(void *handle, int *param);

-}

-#endif

-

+/**
+ * @brief CAN TALON SRX driver.
+ *
+ * The TALON SRX is designed to instrument all runtime signals periodically.
+ * The default periods are chosen to support 16 TALONs with 10ms update rate
+ * for control (throttle or setpoint).  However these can be overridden with
+ * SetStatusFrameRate. @see SetStatusFrameRate
+ * The getters for these unsolicited signals are auto generated at the bottom
+ * of this module.
+ *
+ * Likewise most control signals are sent periodically using the fire-and-forget
+ * CAN API.  The setters for these unsolicited signals are auto generated at the
+ * bottom of this module.
+ *
+ * Signals that are not available in an unsolicited fashion are the Close Loop
+ * gains.  For teams that have a single profile for their TALON close loop they
+ * can use either the webpage to configure their TALONs once or set the PIDF,
+ * Izone, CloseLoopRampRate, etc... once in the robot application.  These
+ * parameters are saved to flash so once they are loaded in the TALON, they
+ * will persist through power cycles and mode changes.
+ *
+ * For teams that have one or two profiles to switch between, they can use the
+ * same strategy since there are two slots to choose from and the
+ * ProfileSlotSelect is periodically sent in the 10 ms control frame.
+ *
+ * For teams that require changing gains frequently, they can use the soliciting
+ * API to get and set those parameters.  Most likely they will only need to set
+ * them in a periodic fashion as a function of what motion the application is
+ * attempting.  If this API is used, be mindful of the CAN utilization reported
+ * in the driver station.
+ *
+ * If calling application has used the config routines to configure the
+ * selected feedback sensor, then all positions are measured in floating point
+ * precision rotations.  All sensor velocities are specified in floating point
+ * precision RPM.
+ * @see ConfigPotentiometerTurns
+ * @see ConfigEncoderCodesPerRev
+ * HOWEVER, if calling application has not called the config routine for
+ * selected feedback sensor, then all getters/setters for position/velocity use
+ * the native engineering units of the Talon SRX firm (just like in 2015).
+ * Signals explained below.
+ *
+ * Encoder position is measured in encoder edges.  Every edge is counted
+ * (similar to roboRIO 4X mode).  Analog position is 10 bits, meaning 1024
+ * ticks per rotation (0V => 3.3V).  Use SetFeedbackDeviceSelect to select
+ * which sensor type you need.  Once you do that you can use GetSensorPosition()
+ * and GetSensorVelocity().  These signals are updated on CANBus every 20ms (by
+ * default).  If a relative sensor is selected, you can zero (or change the
+ * current value) using SetSensorPosition.
+ *
+ * Analog Input and quadrature position (and velocity) are also explicitly
+ * reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel.
+ * These signals are available all the time, regardless of what sensor is
+ * selected at a rate of 100ms.  This allows easy instrumentation for "in the
+ * pits" checking of all sensors regardless of modeselect.  The 100ms rate is
+ * overridable for teams who want to acquire sensor data for processing, not
+ * just instrumentation.  Or just select the sensor using
+ * SetFeedbackDeviceSelect to get it at 20ms.
+ *
+ * Velocity is in position ticks / 100ms.
+ *
+ * All output units are in respect to duty cycle (throttle) which is -1023(full
+ * reverse) to +1023 (full forward).  This includes demand (which specifies
+ * duty cycle when in duty cycle mode) and rampRamp, which is in throttle units
+ * per 10ms (if nonzero).
+ *
+ * Pos and velocity close loops are calc'd as
+ *   err = target - posOrVel.
+ *   iErr += err;
+ *   if(   (IZone!=0)  and  abs(err) > IZone)
+ *       ClearIaccum()
+ *   output = P X err + I X iErr + D X dErr + F X target
+ *   dErr = err - lastErr
+ * P, I, and D gains are always positive. F can be negative.
+ * Motor direction can be reversed using SetRevMotDuringCloseLoopEn if
+ * sensor and motor are out of phase. Similarly feedback sensor can also be
+ * reversed (multiplied by -1) if you prefer the sensor to be inverted.
+ *
+ * P gain is specified in throttle per error tick.  For example, a value of 102
+ * is ~9.9% (which is 102/1023) throttle per 1 ADC unit(10bit) or 1 quadrature
+ * encoder edge depending on selected sensor.
+ *
+ * I gain is specified in throttle per integrated error. For example, a value
+ * of 10 equates to ~0.99% (which is 10/1023) for each accumulated ADC unit
+ * (10 bit) or 1 quadrature encoder edge depending on selected sensor.
+ * Close loop and integral accumulator runs every 1ms.
+ *
+ * D gain is specified in throttle per derivative error. For example a value of
+ * 102 equates to ~9.9% (which is 102/1023) per change of 1 unit (ADC or
+ * encoder) per ms.
+ *
+ * I Zone is specified in the same units as sensor position (ADC units or
+ * quadrature edges).  If pos/vel error is outside of this value, the
+ * integrated error will auto-clear...
+ *   if(   (IZone!=0)  and  abs(err) > IZone)
+ *       ClearIaccum()
+ * ...this is very useful in preventing integral windup and is highly
+ * recommended if using full PID to keep stability low.
+ *
+ * CloseLoopRampRate is in throttle units per 1ms.  Set to zero to disable
+ * ramping.  Works the same as RampThrottle but only is in effect when a close
+ * loop mode and profile slot is selected.
+ *
+ * auto generated using spreadsheet and wpiclassgen.py
+ * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967
+ */
+#ifndef CanTalonSRX_H_
+#define CanTalonSRX_H_
+#include "ctre/ctre.h"  //BIT Defines + Typedefs, TALON_Control_6_MotProfAddTrajPoint_t
+#include "ctre/CtreCanNode.h"
+#include <FRC_NetworkCommunication/CANSessionMux.h>  //CAN Comm
+#include <map>
+#include <atomic>
+#include <deque>
+#include <mutex>
+class CanTalonSRX : public CtreCanNode {
+ private:
+  // Use this for determining whether the default move constructor has been
+  // called; this prevents us from calling the destructor twice.
+  struct HasBeenMoved {
+    HasBeenMoved(HasBeenMoved &&other) {
+      other.moved = true;
+      moved = false;
+    }
+    HasBeenMoved() = default;
+    std::atomic<bool> moved{false};
+    operator bool() const { return moved; }
+  } m_hasBeenMoved;
+
+  // Vars for opening a CAN stream if caller needs signals that require
+  // soliciting
+  uint32_t _can_h;    //!< Session handle for catching response params.
+  int32_t _can_stat;  //!< Session handle status.
+  struct tCANStreamMessage _msgBuff[20];
+  static int const kMsgCapacity = 20;
+  typedef std::map<uint32_t, uint32_t> sigs_t;
+  // Catches signal updates that are solicited.  Expect this to be very few.
+  sigs_t _sigs;
+  void OpenSessionIfNeedBe();
+  void ProcessStreamMessages();
+  /**
+   * Called in various places to double check we are using the best control
+   * frame.  If the Talon firmware is too old, use control 1 framing, which
+   * does not allow setting control signals until robot is enabled.  If Talon
+   * firmware can suport control5, use that since that frame can be
+   * transmitted during robot-disable.  If calling application uses setParam
+   * to set the signal eLegacyControlMode, caller can force using control1
+   * if needed for some reason.
+   */
+  void UpdateControlId();
+  /**
+   * @return true if Talon is reporting that it supports control5, and therefore
+   *              RIO can send control5 to update control params (even when
+   *              disabled).
+   */
+  bool IsControl5Supported();
+  /**
+   * Get a copy of the control frame to send.
+   * @param [out] pointer to eight byte array to fill.
+   */
+  void GetControlFrameCopy(uint8_t *toFill);
+  /**
+   * @return the tx task that transmits Control6 (motion profile control).
+   *         If it's not scheduled, then schedule it.  This is part
+   *         of making the lazy-framing that only peforms MotionProf framing
+   *         when needed to save bandwidth.
+   */
+  CtreCanNode::txTask<TALON_Control_6_MotProfAddTrajPoint_t> GetControl6();
+  /**
+   * Caller is either pushing a new motion profile point, or is
+   * calling the Process buffer routine.  In either case check our
+   * flow control to see if we need to start sending control6.
+   */
+  void ReactToMotionProfileCall();
+  /**
+   * Update the NextPt signals inside the control frame given the next pt to
+   * send.
+   * @param control pointer to the CAN frame payload containing control6.  Only
+   *                the signals that serialize the next trajectory point are
+   *                updated from the contents of newPt.
+   * @param newPt point to the next trajectory that needs to be inserted into
+   *              Talon RAM.
+   */
+  void CopyTrajPtIntoControl(
+      TALON_Control_6_MotProfAddTrajPoint_t *control,
+      const TALON_Control_6_MotProfAddTrajPoint_t *newPt);
+  //---------------------- General Control framing ---------------------------//
+  /**
+   * Frame period for control1 or control5, depending on which one we are using.
+   */
+  int _controlPeriodMs = kDefaultControlPeriodMs;
+  /**
+   * Frame Period of the motion profile control6 frame.
+   */
+  int _control6PeriodMs = kDefaultControl6PeriodMs;
+  /**
+   * When using control5, we still need to send a frame to enable robot.  This
+   * controls the period.  This only is used when we are in the control5 state.
+   * @see ControlFrameSelControl5
+   */
+  int _enablePeriodMs = kDefaultEnablePeriodMs;
+  /**
+   * ArbID to use for control frame.  Should be either CONTROL_1 or CONTROL_5.
+   */
+  uint32_t _controlFrameArbId;
+  /**
+   * Boolean flag to signal calling applications intent to allow using control5
+   * assuming Talon firmware supports it.  This can be cleared to force control1
+   * framing.
+   */
+  bool _useControl5ifSupported = true;
+  //--------------------- Buffering Motion Profile ---------------------------//
+  /**
+   * Top level Buffer for motion profile trajectory buffering.
+   * Basically this buffers up the eight byte CAN frame payloads that are
+   * handshaked into the Talon RAM.
+   * TODO: Should this be moved into a separate header, and if so where
+   * logically should it reside?
+   * TODO: Add compression so that multiple CAN frames can be compressed into
+   * one exchange.
+   */
+  class TrajectoryBuffer {
+   public:
+    void Clear() { _motProfTopBuffer.clear(); }
+    /**
+     * push caller's uncompressed simple trajectory point.
+     */
+    void Push(TALON_Control_6_MotProfAddTrajPoint_huff0_t &pt) {
+      _motProfTopBuffer.push_back(pt);
+    }
+    /**
+     * Get the next trajectory point CAN frame to send.
+     * Underlying layer may compress the next few points together
+     * into one control_6 frame.
+     */
+    TALON_Control_6_MotProfAddTrajPoint_t *Front() {
+      /* TODO : peek ahead and use compression strategies */
+      _lastFront = _motProfTopBuffer.front();
+      return (TALON_Control_6_MotProfAddTrajPoint_t *)&_lastFront;
+    }
+    void Pop() {
+      /* TODO : pop multiple points if last front'd point was compressed. */
+      _motProfTopBuffer.pop_front();
+    }
+    unsigned int GetNumTrajectories() { return _motProfTopBuffer.size(); }
+    bool IsEmpty() { return _motProfTopBuffer.empty(); }
+
+   private:
+    std::deque<TALON_Control_6_MotProfAddTrajPoint_huff0_t> _motProfTopBuffer;
+    TALON_Control_6_MotProfAddTrajPoint_huff0_t _lastFront;
+  };
+  TrajectoryBuffer _motProfTopBuffer;
+  /**
+   * To keep buffers from getting out of control, place a cap on the top level
+   * buffer.  Calling application
+   * can stream addition points as they are fed to Talon.
+   * Approx memory footprint is this capacity X 8 bytes.
+   */
+  static const int kMotionProfileTopBufferCapacity = 2048;
+  /**
+   * Flow control for streaming trajectories.
+   */
+  int32_t _motProfFlowControl = -1;
+  /**
+   * Since we may need the MP pts to be emptied into Talon in the background
+   * make sure the buffering is thread-safe.
+   */
+  std::mutex _mutMotProf;
+  /**
+   * Send a one shot frame to set an arbitrary signal.
+   * Most signals are in the control frame so avoid using this API unless you
+   * have to.
+   * Use this api for...
+   * -A motor controller profile signal eProfileParam_XXXs.  These are backed up
+   * in flash.  If you are gain-scheduling then call this periodically.
+   * -Default brake and limit switch signals... eOnBoot_XXXs.  Avoid doing this,
+   * use the override signals in the control frame.
+   * Talon will automatically send a PARAM_RESPONSE after the set, so
+   * GetParamResponse will catch the latest value after a couple ms.
+   */
+  CTR_Code SetParamRaw(uint32_t paramEnum, int32_t rawBits);
+  /**
+   * Checks cached CAN frames and updating solicited signals.
+   */
+  CTR_Code GetParamResponseRaw(uint32_t paramEnum, int32_t &rawBits);
+
+ public:
+  // default control update rate is 10ms.
+  static const int kDefaultControlPeriodMs = 10;
+  // default enable update rate is 50ms (when using the new control5 frame).
+  static const int kDefaultEnablePeriodMs = 50;
+  // Default update rate for motion profile control 6.  This only takes effect
+  // when calling uses MP functions.
+  static const int kDefaultControl6PeriodMs = 10;
+  explicit CanTalonSRX(int deviceNumber = 0,
+                       int controlPeriodMs = kDefaultControlPeriodMs,
+                       int enablePeriodMs = kDefaultEnablePeriodMs);
+  ~CanTalonSRX();
+  void Set(double value);
+  /* mode select enumerations */
+  // Demand is 11bit signed duty cycle [-1023,1023].
+  static const int kMode_DutyCycle = 0;
+  // Position PIDF.
+  static const int kMode_PositionCloseLoop = 1;
+  // Velocity PIDF.
+  static const int kMode_VelocityCloseLoop = 2;
+  // Current close loop - not done.
+  static const int kMode_CurrentCloseLoop = 3;
+  // Voltage Compensation Mode - not done.  Demand is fixed pt target 8.8 volts.
+  static const int kMode_VoltCompen = 4;
+  // Demand is the 6 bit Device ID of the 'master' TALON SRX.
+  static const int kMode_SlaveFollower = 5;
+  // Demand is '0' (Disabled), '1' (Enabled), or '2' (Hold).
+  static const int kMode_MotionProfile = 6;
+  // Zero the output (honors brake/coast) regardless of demand.
+  // Might be useful if we need to change modes but can't atomically
+  // change all the signals we want in between.
+  static const int kMode_NoDrive = 15;
+  /* limit switch enumerations */
+  static const int kLimitSwitchOverride_UseDefaultsFromFlash = 1;
+  static const int kLimitSwitchOverride_DisableFwd_DisableRev = 4;
+  static const int kLimitSwitchOverride_DisableFwd_EnableRev = 5;
+  static const int kLimitSwitchOverride_EnableFwd_DisableRev = 6;
+  static const int kLimitSwitchOverride_EnableFwd_EnableRev = 7;
+  /* brake override enumerations */
+  static const int kBrakeOverride_UseDefaultsFromFlash = 0;
+  static const int kBrakeOverride_OverrideCoast = 1;
+  static const int kBrakeOverride_OverrideBrake = 2;
+  /* feedback device enumerations */
+  static const int kFeedbackDev_DigitalQuadEnc = 0;
+  static const int kFeedbackDev_AnalogPot = 2;
+  static const int kFeedbackDev_AnalogEncoder = 3;
+  static const int kFeedbackDev_CountEveryRisingEdge = 4;
+  static const int kFeedbackDev_CountEveryFallingEdge = 5;
+  static const int kFeedbackDev_PosIsPulseWidth = 8;
+  /* ProfileSlotSelect enumerations*/
+  static const int kProfileSlotSelect_Slot0 = 0;
+  static const int kProfileSlotSelect_Slot1 = 1;
+  /* status frame rate types */
+  static const int kStatusFrame_General = 0;
+  static const int kStatusFrame_Feedback = 1;
+  static const int kStatusFrame_Encoder = 2;
+  static const int kStatusFrame_AnalogTempVbat = 3;
+  static const int kStatusFrame_PulseWidthMeas = 4;
+  static const int kStatusFrame_MotionProfile = 5;
+  /* Motion Profile status bits */
+  static const int kMotionProfileFlag_ActTraj_IsValid = 0x1;
+  static const int kMotionProfileFlag_HasUnderrun = 0x2;
+  static const int kMotionProfileFlag_IsUnderrun = 0x4;
+  static const int kMotionProfileFlag_ActTraj_IsLast = 0x8;
+  static const int kMotionProfileFlag_ActTraj_VelOnly = 0x10;
+  /* Motion Profile Set Output */
+  // Motor output is neutral, Motion Profile Executer is not running.
+  static const int kMotionProf_Disabled = 0;
+  // Motor output is updated from Motion Profile Executer, MPE will
+  // process the buffered points.
+  static const int kMotionProf_Enable = 1;
+  // Motor output is updated from Motion Profile Executer, MPE will
+  // stay processing current trajectory point.
+  static const int kMotionProf_Hold = 2;
+  /**
+   * Signal enumeration for generic signal access.
+   * Although every signal is enumerated, only use this for traffic that must
+   * be solicited.
+   * Use the auto generated getters/setters at bottom of this header as much as
+   * possible.
+   */
+  enum param_t {
+    eProfileParamSlot0_P = 1,
+    eProfileParamSlot0_I = 2,
+    eProfileParamSlot0_D = 3,
+    eProfileParamSlot0_F = 4,
+    eProfileParamSlot0_IZone = 5,
+    eProfileParamSlot0_CloseLoopRampRate = 6,
+    eProfileParamSlot1_P = 11,
+    eProfileParamSlot1_I = 12,
+    eProfileParamSlot1_D = 13,
+    eProfileParamSlot1_F = 14,
+    eProfileParamSlot1_IZone = 15,
+    eProfileParamSlot1_CloseLoopRampRate = 16,
+    eProfileParamSoftLimitForThreshold = 21,
+    eProfileParamSoftLimitRevThreshold = 22,
+    eProfileParamSoftLimitForEnable = 23,
+    eProfileParamSoftLimitRevEnable = 24,
+    eOnBoot_BrakeMode = 31,
+    eOnBoot_LimitSwitch_Forward_NormallyClosed = 32,
+    eOnBoot_LimitSwitch_Reverse_NormallyClosed = 33,
+    eOnBoot_LimitSwitch_Forward_Disable = 34,
+    eOnBoot_LimitSwitch_Reverse_Disable = 35,
+    eFault_OverTemp = 41,
+    eFault_UnderVoltage = 42,
+    eFault_ForLim = 43,
+    eFault_RevLim = 44,
+    eFault_HardwareFailure = 45,
+    eFault_ForSoftLim = 46,
+    eFault_RevSoftLim = 47,
+    eStckyFault_OverTemp = 48,
+    eStckyFault_UnderVoltage = 49,
+    eStckyFault_ForLim = 50,
+    eStckyFault_RevLim = 51,
+    eStckyFault_ForSoftLim = 52,
+    eStckyFault_RevSoftLim = 53,
+    eAppliedThrottle = 61,
+    eCloseLoopErr = 62,
+    eFeedbackDeviceSelect = 63,
+    eRevMotDuringCloseLoopEn = 64,
+    eModeSelect = 65,
+    eProfileSlotSelect = 66,
+    eRampThrottle = 67,
+    eRevFeedbackSensor = 68,
+    eLimitSwitchEn = 69,
+    eLimitSwitchClosedFor = 70,
+    eLimitSwitchClosedRev = 71,
+    eSensorPosition = 73,
+    eSensorVelocity = 74,
+    eCurrent = 75,
+    eBrakeIsEnabled = 76,
+    eEncPosition = 77,
+    eEncVel = 78,
+    eEncIndexRiseEvents = 79,
+    eQuadApin = 80,
+    eQuadBpin = 81,
+    eQuadIdxpin = 82,
+    eAnalogInWithOv = 83,
+    eAnalogInVel = 84,
+    eTemp = 85,
+    eBatteryV = 86,
+    eResetCount = 87,
+    eResetFlags = 88,
+    eFirmVers = 89,
+    eSettingsChanged = 90,
+    eQuadFilterEn = 91,
+    ePidIaccum = 93,
+    eStatus1FrameRate = 94,  // TALON_Status_1_General_10ms_t
+    eStatus2FrameRate = 95,  // TALON_Status_2_Feedback_20ms_t
+    eStatus3FrameRate = 96,  // TALON_Status_3_Enc_100ms_t
+    eStatus4FrameRate = 97,  // TALON_Status_4_AinTempVbat_100ms_t
+    eStatus6FrameRate = 98,  // TALON_Status_6_Eol_t
+    eStatus7FrameRate = 99,  // TALON_Status_7_Debug_200ms_t
+    eClearPositionOnIdx = 100,
+    // reserved,
+    // reserved,
+    // reserved,
+    ePeakPosOutput = 104,
+    eNominalPosOutput = 105,
+    ePeakNegOutput = 106,
+    eNominalNegOutput = 107,
+    eQuadIdxPolarity = 108,
+    eStatus8FrameRate = 109,  // TALON_Status_8_PulseWid_100ms_t
+    eAllowPosOverflow = 110,
+    eProfileParamSlot0_AllowableClosedLoopErr = 111,
+    eNumberPotTurns = 112,
+    eNumberEncoderCPR = 113,
+    ePwdPosition = 114,
+    eAinPosition = 115,
+    eProfileParamVcompRate = 116,
+    eProfileParamSlot1_AllowableClosedLoopErr = 117,
+    eStatus9FrameRate = 118,  // TALON_Status_9_MotProfBuffer_100ms_t
+    eMotionProfileHasUnderrunErr = 119,
+    eReserved120 = 120,
+    eLegacyControlMode = 121,
+  };
+  //---- setters and getters that use the solicated param request/response ---//
+  /**
+   * Send a one shot frame to set an arbitrary signal.
+   * Most signals are in the control frame so avoid using this API unless you
+   * have to.
+   * Use this api for...
+   * -A motor controller profile signal eProfileParam_XXXs.  These are backed
+   * up in flash.  If you are gain-scheduling then call this periodically.
+   * -Default brake and limit switch signals... eOnBoot_XXXs.  Avoid doing
+   * this, use the override signals in the control frame.
+   * Talon will automatically send a PARAM_RESPONSE after the set, so
+   * GetParamResponse will catch the latest value after a couple ms.
+   */
+  CTR_Code SetParam(param_t paramEnum, double value);
+  /**
+   * Asks TALON to immedietely respond with signal value.  This API is only used
+   * for signals that are not sent periodically.
+   * This can be useful for reading params that rarely change like Limit Switch
+   * settings and PIDF values.
+   * @param param to request.
+   */
+  CTR_Code RequestParam(param_t paramEnum);
+  CTR_Code GetParamResponse(param_t paramEnum, double &value);
+  CTR_Code GetParamResponseInt32(param_t paramEnum, int &value);
+  //----------- getters and setters that use param request/response ----------//
+  /**
+   * These signals are backed up in flash and will survive a power cycle.
+   * If your application requires changing these values consider using both
+   * slots and switch between slot0 <=> slot1.
+   * If your application requires changing these signals frequently then it
+   * makes sense to leverage this API.
+   * Getters don't block, so it may require several calls to get the latest
+   * value.
+   */
+  CTR_Code SetPgain(unsigned slotIdx, double gain);
+  CTR_Code SetIgain(unsigned slotIdx, double gain);
+  CTR_Code SetDgain(unsigned slotIdx, double gain);
+  CTR_Code SetFgain(unsigned slotIdx, double gain);
+  CTR_Code SetIzone(unsigned slotIdx, int zone);
+  CTR_Code SetCloseLoopRampRate(unsigned slotIdx, int closeLoopRampRate);
+  CTR_Code SetVoltageCompensationRate(double voltagePerMs);
+  CTR_Code SetSensorPosition(int pos);
+  CTR_Code SetForwardSoftLimit(int forwardLimit);
+  CTR_Code SetReverseSoftLimit(int reverseLimit);
+  CTR_Code SetForwardSoftEnable(int enable);
+  CTR_Code SetReverseSoftEnable(int enable);
+  CTR_Code GetPgain(unsigned slotIdx, double &gain);
+  CTR_Code GetIgain(unsigned slotIdx, double &gain);
+  CTR_Code GetDgain(unsigned slotIdx, double &gain);
+  CTR_Code GetFgain(unsigned slotIdx, double &gain);
+  CTR_Code GetIzone(unsigned slotIdx, int &zone);
+  CTR_Code GetCloseLoopRampRate(unsigned slotIdx, int &closeLoopRampRate);
+  CTR_Code GetVoltageCompensationRate(double &voltagePerMs);
+  CTR_Code GetForwardSoftLimit(int &forwardLimit);
+  CTR_Code GetReverseSoftLimit(int &reverseLimit);
+  CTR_Code GetForwardSoftEnable(int &enable);
+  CTR_Code GetReverseSoftEnable(int &enable);
+  CTR_Code GetPulseWidthRiseToFallUs(int &param);
+  CTR_Code IsPulseWidthSensorPresent(int &param);
+  CTR_Code SetModeSelect(int modeSelect, int demand);
+  /**
+   * Change the periodMs of a TALON's status frame.  See kStatusFrame_* enums
+   * for what's available.
+   */
+  CTR_Code SetStatusFrameRate(unsigned frameEnum, unsigned periodMs);
+  /**
+   * Clear all sticky faults in TALON.
+   */
+  CTR_Code ClearStickyFaults();
+  /**
+   * Calling application can opt to speed up the handshaking between the robot
+   * API and the Talon to increase the
+   * download rate of the Talon's Motion Profile.  Ideally the period should be
+   * no more than half the period
+   * of a trajectory point.
+   */
+  void ChangeMotionControlFramePeriod(uint32_t periodMs);
+  /**
+   * Clear the buffered motion profile in both Talon RAM (bottom), and in the
+   * API (top).
+   */
+  void ClearMotionProfileTrajectories();
+  /**
+   * Retrieve just the buffer count for the api-level (top) buffer.
+   * This routine performs no CAN or data structure lookups, so its fast and
+   * ideal if caller needs to quickly poll the progress of trajectory points
+   * being emptied into Talon's RAM. Otherwise just use GetMotionProfileStatus.
+   * @return number of trajectory points in the top buffer.
+   */
+  uint32_t GetMotionProfileTopLevelBufferCount();
+  /**
+   * Retrieve just the buffer full for the api-level (top) buffer.
+   * This routine performs no CAN or data structure lookups, so its fast and
+   * ideal if caller needs to quickly poll. Otherwise just use
+   * GetMotionProfileStatus.
+   * @return number of trajectory points in the top buffer.
+   */
+  bool IsMotionProfileTopLevelBufferFull();
+  /**
+   * Push another trajectory point into the top level buffer (which is emptied
+   * into the Talon's bottom buffer as room allows).
+   * @param targPos  servo position in native Talon units (sensor units).
+   * @param targVel  velocity to feed-forward in native Talon units (sensor
+   *                 units per 100ms).
+   * @param profileSlotSelect  which slot to pull PIDF gains from.  Currently
+   *                           supports 0 or 1.
+   * @param timeDurMs  time in milliseconds of how long to apply this point.
+   * @param velOnly  set to nonzero to signal Talon that only the feed-foward
+   *                 velocity should be used, i.e. do not perform PID on
+   *                 position.  This is equivalent to setting PID gains to zero,
+   *                 but much more efficient and synchronized to MP.
+   * @param isLastPoint  set to nonzero to signal Talon to keep processing this
+   *                     trajectory point, instead of jumping to the next one
+   *                     when timeDurMs expires.  Otherwise MP executer will
+   *                     eventually see an empty buffer after the last point
+   *                     expires, causing it to assert the IsUnderRun flag.
+   *                     However this may be desired if calling application
+   *                     nevers wants to terminate the MP.
+   * @param zeroPos  set to nonzero to signal Talon to "zero" the selected
+   *                 position sensor before executing this trajectory point.
+   *                 Typically the first point should have this set only thus
+   *                 allowing the remainder of the MP positions to be relative
+   *                 to zero.
+   * @return CTR_OKAY if trajectory point push ok. CTR_BufferFull if buffer is
+   *         full due to kMotionProfileTopBufferCapacity.
+   */
+  CTR_Code PushMotionProfileTrajectory(int targPos, int targVel,
+                                       int profileSlotSelect, int timeDurMs,
+                                       int velOnly, int isLastPoint,
+                                       int zeroPos);
+  /**
+   * This must be called periodically to funnel the trajectory points from the
+   * API's top level buffer to the Talon's bottom level buffer.  Recommendation
+   * is to call this twice as fast as the executation rate of the motion
+   * profile.  So if MP is running with 20ms trajectory points, try calling
+   * this routine every 10ms.  All motion profile functions are thread-safe
+   * through the use of a mutex, so there is no harm in having the caller
+   * utilize threading.
+   */
+  void ProcessMotionProfileBuffer();
+  /**
+   * Retrieve all status information.
+   * Since this all comes from one CAN frame, its ideal to have one routine to
+   * retrieve the frame once and decode everything.
+   * @param [out] flags  bitfield for status bools. Starting with least
+   *        significant bit: IsValid, HasUnderrun, IsUnderrun, IsLast, VelOnly.
+   *
+   *        IsValid  set when MP executer is processing a trajectory point,
+   *                 and that point's status is instrumented with IsLast,
+   *                 VelOnly, targPos, targVel.  However if MP executor is
+   *                 not processing a trajectory point, then this flag is
+   *                 false, and the instrumented signals will be zero.
+   *        HasUnderrun  is set anytime the MP executer is ready to pop
+   *                     another trajectory point from the Talon's RAM,
+   *                     but the buffer is empty.  It can only be cleared
+   *                     by using SetParam(eMotionProfileHasUnderrunErr,0);
+   *        IsUnderrun  is set when the MP executer is ready for another
+   *                    point, but the buffer is empty, and cleared when
+   *                    the MP executer does not need another point.
+   *                    HasUnderrun shadows this registor when this
+   *                    register gets set, however HasUnderrun stays
+   *                    asserted until application has process it, and
+   *                    IsUnderrun auto-clears when the condition is
+   *                    resolved.
+   *        IsLast  is set/cleared based on the MP executer's current
+   *                trajectory point's IsLast value.  This assumes
+   *                IsLast was set when PushMotionProfileTrajectory
+   *                was used to insert the currently processed trajectory
+   *                point.
+   *        VelOnly  is set/cleared based on the MP executer's current
+   *                 trajectory point's VelOnly value.
+   *
+   * @param [out] profileSlotSelect  The currently processed trajectory point's
+   *        selected slot.  This can differ in the currently selected slot used
+   *        for Position and Velocity servo modes.
+   * @param [out] targPos The currently processed trajectory point's position
+   *        in native units.  This param is zero if IsValid is zero.
+   * @param [out] targVel The currently processed trajectory point's velocity
+   *        in native units.  This param is zero if IsValid is zero.
+   * @param [out] topBufferRem The remaining number of points in the top level
+   *        buffer.
+   * @param [out] topBufferCnt The number of points in the top level buffer to
+   *        be sent to Talon.
+   * @param [out] btmBufferCnt The number of points in the bottom level buffer
+   *        inside Talon.
+   * @return CTR error code
+   */
+  CTR_Code GetMotionProfileStatus(uint32_t &flags, uint32_t &profileSlotSelect,
+                                  int32_t &targPos, int32_t &targVel,
+                                  uint32_t &topBufferRemaining,
+                                  uint32_t &topBufferCnt,
+                                  uint32_t &btmBufferCnt,
+                                  uint32_t &outputEnable);
+//------------------------ auto generated ------------------------------------//
+/* This API is optimal since it uses the fire-and-forget CAN interface.
+ * These signals should cover the majority of all use cases.
+ */
+  CTR_Code GetFault_OverTemp(int &param);
+  CTR_Code GetFault_UnderVoltage(int &param);
+  CTR_Code GetFault_ForLim(int &param);
+  CTR_Code GetFault_RevLim(int &param);
+  CTR_Code GetFault_HardwareFailure(int &param);
+  CTR_Code GetFault_ForSoftLim(int &param);
+  CTR_Code GetFault_RevSoftLim(int &param);
+  CTR_Code GetStckyFault_OverTemp(int &param);
+  CTR_Code GetStckyFault_UnderVoltage(int &param);
+  CTR_Code GetStckyFault_ForLim(int &param);
+  CTR_Code GetStckyFault_RevLim(int &param);
+  CTR_Code GetStckyFault_ForSoftLim(int &param);
+  CTR_Code GetStckyFault_RevSoftLim(int &param);
+  CTR_Code GetAppliedThrottle(int &param);
+  CTR_Code GetCloseLoopErr(int &param);
+  CTR_Code GetFeedbackDeviceSelect(int &param);
+  CTR_Code GetModeSelect(int &param);
+  CTR_Code GetLimitSwitchEn(int &param);
+  CTR_Code GetLimitSwitchClosedFor(int &param);
+  CTR_Code GetLimitSwitchClosedRev(int &param);
+  CTR_Code GetSensorPosition(int &param);
+  CTR_Code GetSensorVelocity(int &param);
+  CTR_Code GetCurrent(double &param);
+  CTR_Code GetBrakeIsEnabled(int &param);
+  CTR_Code GetEncPosition(int &param);
+  CTR_Code GetEncVel(int &param);
+  CTR_Code GetEncIndexRiseEvents(int &param);
+  CTR_Code GetQuadApin(int &param);
+  CTR_Code GetQuadBpin(int &param);
+  CTR_Code GetQuadIdxpin(int &param);
+  CTR_Code GetAnalogInWithOv(int &param);
+  CTR_Code GetAnalogInVel(int &param);
+  CTR_Code GetTemp(double &param);
+  CTR_Code GetBatteryV(double &param);
+  CTR_Code GetResetCount(int &param);
+  CTR_Code GetResetFlags(int &param);
+  CTR_Code GetFirmVers(int &param);
+  CTR_Code GetPulseWidthPosition(int &param);
+  CTR_Code GetPulseWidthVelocity(int &param);
+  CTR_Code GetPulseWidthRiseToRiseUs(int &param);
+  CTR_Code GetActTraj_IsValid(int &param);
+  CTR_Code GetActTraj_ProfileSlotSelect(int &param);
+  CTR_Code GetActTraj_VelOnly(int &param);
+  CTR_Code GetActTraj_IsLast(int &param);
+  CTR_Code GetOutputType(int &param);
+  CTR_Code GetHasUnderrun(int &param);
+  CTR_Code GetIsUnderrun(int &param);
+  CTR_Code GetNextID(int &param);
+  CTR_Code GetBufferIsFull(int &param);
+  CTR_Code GetCount(int &param);
+  CTR_Code GetActTraj_Velocity(int &param);
+  CTR_Code GetActTraj_Position(int &param);
+  CTR_Code SetDemand(int param);
+  CTR_Code SetOverrideLimitSwitchEn(int param);
+  CTR_Code SetFeedbackDeviceSelect(int param);
+  CTR_Code SetRevMotDuringCloseLoopEn(int param);
+  CTR_Code SetOverrideBrakeType(int param);
+  CTR_Code SetModeSelect(int param);
+  CTR_Code SetProfileSlotSelect(int param);
+  CTR_Code SetRampThrottle(int param);
+  CTR_Code SetRevFeedbackSensor(int param);
+};
+extern "C" {
+  void *c_TalonSRX_Create3(int deviceNumber, int controlPeriodMs, int enablePeriodMs);
+  void *c_TalonSRX_Create2(int deviceNumber, int controlPeriodMs);
+  void *c_TalonSRX_Create1(int deviceNumber);
+  void c_TalonSRX_Destroy(void *handle);
+  void c_TalonSRX_Set(void *handle, double value);
+  CTR_Code c_TalonSRX_SetParam(void *handle, int paramEnum, double value);
+  CTR_Code c_TalonSRX_RequestParam(void *handle, int paramEnum);
+  CTR_Code c_TalonSRX_GetParamResponse(void *handle, int paramEnum, double *value);
+  CTR_Code c_TalonSRX_GetParamResponseInt32(void *handle, int paramEnum, int *value);
+  CTR_Code c_TalonSRX_SetPgain(void *handle, int slotIdx, double gain);
+  CTR_Code c_TalonSRX_SetIgain(void *handle, int slotIdx, double gain);
+  CTR_Code c_TalonSRX_SetDgain(void *handle, int slotIdx, double gain);
+  CTR_Code c_TalonSRX_SetFgain(void *handle, int slotIdx, double gain);
+  CTR_Code c_TalonSRX_SetIzone(void *handle, int slotIdx, int zone);
+  CTR_Code c_TalonSRX_SetCloseLoopRampRate(void *handle, int slotIdx, int closeLoopRampRate);
+  CTR_Code c_TalonSRX_SetVoltageCompensationRate(void *handle, double voltagePerMs);
+  CTR_Code c_TalonSRX_SetSensorPosition(void *handle, int pos);
+  CTR_Code c_TalonSRX_SetForwardSoftLimit(void *handle, int forwardLimit);
+  CTR_Code c_TalonSRX_SetReverseSoftLimit(void *handle, int reverseLimit);
+  CTR_Code c_TalonSRX_SetForwardSoftEnable(void *handle, int enable);
+  CTR_Code c_TalonSRX_SetReverseSoftEnable(void *handle, int enable);
+  CTR_Code c_TalonSRX_GetPgain(void *handle, int slotIdx, double *gain);
+  CTR_Code c_TalonSRX_GetIgain(void *handle, int slotIdx, double *gain);
+  CTR_Code c_TalonSRX_GetDgain(void *handle, int slotIdx, double *gain);
+  CTR_Code c_TalonSRX_GetFgain(void *handle, int slotIdx, double *gain);
+  CTR_Code c_TalonSRX_GetIzone(void *handle, int slotIdx, int *zone);
+  CTR_Code c_TalonSRX_GetCloseLoopRampRate(void *handle, int slotIdx, int *closeLoopRampRate);
+  CTR_Code c_TalonSRX_GetVoltageCompensationRate(void *handle, double *voltagePerMs);
+  CTR_Code c_TalonSRX_GetForwardSoftLimit(void *handle, int *forwardLimit);
+  CTR_Code c_TalonSRX_GetReverseSoftLimit(void *handle, int *reverseLimit);
+  CTR_Code c_TalonSRX_GetForwardSoftEnable(void *handle, int *enable);
+  CTR_Code c_TalonSRX_GetReverseSoftEnable(void *handle, int *enable);
+  CTR_Code c_TalonSRX_GetPulseWidthRiseToFallUs(void *handle, int *param);
+  CTR_Code c_TalonSRX_IsPulseWidthSensorPresent(void *handle, int *param);
+  CTR_Code c_TalonSRX_SetModeSelect2(void *handle, int modeSelect, int demand);
+  CTR_Code c_TalonSRX_SetStatusFrameRate(void *handle, int frameEnum, int periodMs);
+  CTR_Code c_TalonSRX_ClearStickyFaults(void *handle);
+  void c_TalonSRX_ChangeMotionControlFramePeriod(void *handle, int periodMs);
+  void c_TalonSRX_ClearMotionProfileTrajectories(void *handle);
+  int c_TalonSRX_GetMotionProfileTopLevelBufferCount(void *handle);
+  int c_TalonSRX_IsMotionProfileTopLevelBufferFull(void *handle);
+  CTR_Code c_TalonSRX_PushMotionProfileTrajectory(void *handle, int targPos, int targVel, int profileSlotSelect, int timeDurMs, int velOnly, int isLastPoint, int zeroPos);
+  void c_TalonSRX_ProcessMotionProfileBuffer(void *handle);
+  CTR_Code c_TalonSRX_GetMotionProfileStatus(void *handle, int *flags, int *profileSlotSelect, int *targPos, int *targVel, int *topBufferRemaining, int *topBufferCnt, int *btmBufferCnt, int *outputEnable);
+  CTR_Code c_TalonSRX_GetFault_OverTemp(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetFault_UnderVoltage(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetFault_ForLim(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetFault_RevLim(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetFault_HardwareFailure(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetFault_ForSoftLim(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetFault_RevSoftLim(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetStckyFault_OverTemp(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetStckyFault_UnderVoltage(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetStckyFault_ForLim(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetStckyFault_RevLim(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetStckyFault_ForSoftLim(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetStckyFault_RevSoftLim(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetAppliedThrottle(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetCloseLoopErr(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetFeedbackDeviceSelect(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetModeSelect(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetLimitSwitchEn(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetLimitSwitchClosedFor(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetLimitSwitchClosedRev(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetSensorPosition(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetSensorVelocity(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetCurrent(void *handle, double *param);
+  CTR_Code c_TalonSRX_GetBrakeIsEnabled(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetEncPosition(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetEncVel(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetEncIndexRiseEvents(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetQuadApin(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetQuadBpin(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetQuadIdxpin(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetAnalogInWithOv(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetAnalogInVel(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetTemp(void *handle, double *param);
+  CTR_Code c_TalonSRX_GetBatteryV(void *handle, double *param);
+  CTR_Code c_TalonSRX_GetResetCount(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetResetFlags(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetFirmVers(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetPulseWidthPosition(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetPulseWidthVelocity(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetPulseWidthRiseToRiseUs(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetActTraj_IsValid(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetActTraj_ProfileSlotSelect(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetActTraj_VelOnly(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetActTraj_IsLast(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetOutputType(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetHasUnderrun(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetIsUnderrun(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetNextID(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetBufferIsFull(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetCount(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetActTraj_Velocity(void *handle, int *param);
+  CTR_Code c_TalonSRX_GetActTraj_Position(void *handle, int *param);
+  CTR_Code c_TalonSRX_SetDemand(void *handle, int param);
+  CTR_Code c_TalonSRX_SetOverrideLimitSwitchEn(void *handle, int param);
+  CTR_Code c_TalonSRX_SetFeedbackDeviceSelect(void *handle, int param);
+  CTR_Code c_TalonSRX_SetRevMotDuringCloseLoopEn(void *handle, int param);
+  CTR_Code c_TalonSRX_SetOverrideBrakeType(void *handle, int param);
+  CTR_Code c_TalonSRX_SetModeSelect(void *handle, int param);
+  CTR_Code c_TalonSRX_SetProfileSlotSelect(void *handle, int param);
+  CTR_Code c_TalonSRX_SetRampThrottle(void *handle, int param);
+  CTR_Code c_TalonSRX_SetRevFeedbackSensor(void *handle, int param);
+}
+#endif
diff --git a/hal/include/HAL/HAL.hpp b/hal/include/HAL/HAL.hpp
index f09a5d2..fb3c6aa 100644
--- a/hal/include/HAL/HAL.hpp
+++ b/hal/include/HAL/HAL.hpp
@@ -222,11 +222,14 @@
 
 	uint16_t getFPGAVersion(int32_t *status);
 	uint32_t getFPGARevision(int32_t *status);
-	uint32_t getFPGATime(int32_t *status);
+	uint64_t getFPGATime(int32_t *status);
 
 	bool getFPGAButton(int32_t *status);
 
 	int HALSetErrorData(const char *errors, int errorsLength, int wait_ms);
+	int HALSendError(int isError, int32_t errorCode, int isLVCode,
+		const char *details, const char *location, const char *callStack,
+		int printMsg);
 
 	int HALGetControlWord(HALControlWord *data);
 	int HALGetAllianceStation(enum HALAllianceStationID *allianceStation);
diff --git a/hal/include/HAL/Notifier.hpp b/hal/include/HAL/Notifier.hpp
index f16572f..e8cb381 100644
--- a/hal/include/HAL/Notifier.hpp
+++ b/hal/include/HAL/Notifier.hpp
@@ -4,8 +4,9 @@
 
 extern "C"
 {
-	void* initializeNotifier(void (*ProcessQueue)(uint32_t, void*), void* param, int32_t *status);
+	void* initializeNotifier(void (*process)(uint64_t, void*), void* param, int32_t *status);
 	void cleanNotifier(void* notifier_pointer, int32_t *status);
-
-	void updateNotifierAlarm(void* notifier_pointer, uint32_t triggerTime, int32_t *status);
+	void* getNotifierParam(void* notifier_pointer, int32_t *status);
+	void updateNotifierAlarm(void* notifier_pointer, uint64_t triggerTime, int32_t *status);
+	void stopNotifierAlarm(void* notifier_pointer, int32_t *status);
 }
diff --git a/hal/include/HAL/Port.h b/hal/include/HAL/Port.h
index 8679c26..b2e97c2 100644
--- a/hal/include/HAL/Port.h
+++ b/hal/include/HAL/Port.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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
 
 typedef struct port_t
diff --git a/hal/include/HAL/cpp/priority_condition_variable.h b/hal/include/HAL/cpp/priority_condition_variable.h
index e8ab9e5..cd02ce4 100644
--- a/hal/include/HAL/cpp/priority_condition_variable.h
+++ b/hal/include/HAL/cpp/priority_condition_variable.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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
 
 /* std::condition_variable provides the native_handle() method to return its
diff --git a/hal/include/HAL/cpp/priority_mutex.h b/hal/include/HAL/cpp/priority_mutex.h
index 16e88f6..b03f012 100644
--- a/hal/include/HAL/cpp/priority_mutex.h
+++ b/hal/include/HAL/cpp/priority_mutex.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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
 
 // Allows usage with std::lock_guard without including <mutex> separately
diff --git a/hal/include/ctre/CtreCanNode.h b/hal/include/ctre/CtreCanNode.h
index 4af7307..2707598 100644
--- a/hal/include/ctre/CtreCanNode.h
+++ b/hal/include/ctre/CtreCanNode.h
@@ -52,10 +52,26 @@
 	};

 	UINT8 _deviceNumber;

 	void RegisterRx(uint32_t arbId);

+	/**

+	 * Schedule a CAN Frame for periodic transmit.  Assume eight byte DLC and zero value for initial transmission.

+	 * @param arbId 	CAN Frame Arbitration ID.  Set BIT31 for 11bit ids, otherwise we use 29bit ids.

+	 * @param periodMs	Period to transmit CAN frame.  Pass 0 for one-shot, which also disables that ArbID's preceding periodic transmit.

+	 */

 	void RegisterTx(uint32_t arbId, uint32_t periodMs);

+	/**

+	 * Schedule a CAN Frame for periodic transmit.

+	 * @param arbId 	CAN Frame Arbitration ID.  Set BIT31 for 11bit ids, otherwise we use 29bit ids.

+	 * @param periodMs	Period to transmit CAN frame.  Pass 0 for one-shot, which also disables that ArbID's preceding periodic transmit.

+	 * @param dlc 		Number of bytes to transmit (0 to 8).

+	 * @param initialFrame	Ptr to the frame data to schedule for transmitting.  Passing null will result

+	 *						in defaulting to zero data value.

+	 */

+	void RegisterTx(uint32_t arbId, uint32_t periodMs, uint32_t dlc, const uint8_t * initialFrame);

+	void UnregisterTx(uint32_t arbId);

 

 	CTR_Code GetRx(uint32_t arbId,uint8_t * dataBytes,uint32_t timeoutMs);

 	void FlushTx(uint32_t arbId);

+	bool ChangeTxPeriod(uint32_t arbId, uint32_t periodMs);

 

 	template<typename T> txTask<T> GetTx(uint32_t arbId)

 	{

@@ -86,6 +102,7 @@
 			uint32_t arbId;

 			uint8_t toSend[8];

 			uint32_t periodMs;

+			uint8_t dlc;

 	};

 

 	class rxEvent_t{

diff --git a/hal/include/ctre/ctre.h b/hal/include/ctre/ctre.h
index c2d3f69..a0f99b3 100644
--- a/hal/include/ctre/ctre.h
+++ b/hal/include/ctre/ctre.h
@@ -1,5 +1,9 @@
-#ifndef GLOBAL_H

-#define GLOBAL_H

+/**

+ * @file ctre.h

+ * Common header for all CTRE HAL modules.

+ */

+#ifndef CTRE_H

+#define CTRE_H

 

 //Bit Defines

 #define BIT0 0x01

@@ -45,6 +49,9 @@
 		CTR_UnexpectedArbId,	//!< Specified CAN Id is invalid.

 		CTR_TxFailed,			//!< Could not transmit the CAN frame.

 		CTR_SigNotUpdated,		//!< Have not received an value response for signal.

+		CTR_BufferFull,			//!< Caller attempted to insert data into a buffer that is full.

 }CTR_Code;

 

-#endif

+#include "ctre_frames.h"

+

+#endif /* CTRE_H */

diff --git a/hal/include/ctre/ctre_frames.h b/hal/include/ctre/ctre_frames.h
new file mode 100644
index 0000000..f131538
--- /dev/null
+++ b/hal/include/ctre/ctre_frames.h
@@ -0,0 +1,243 @@
+/**
+ * @file ctre_frames.h
+ * CAN Encoder/Decoder Structures for CTRE devices.
+ */
+#ifndef CTRE_FRAMES_H
+#define CTRE_FRAMES_H
+
+/** control */
+typedef struct _TALON_Control_1_General_10ms_t {
+	unsigned TokenH:8;
+	unsigned TokenL:8;
+	unsigned DemandH:8;
+	unsigned DemandM:8;
+	unsigned DemandL:8;
+	unsigned ProfileSlotSelect:1;
+	unsigned FeedbackDeviceSelect:4;
+	unsigned OverrideLimitSwitchEn:3;
+	unsigned RevFeedbackSensor:1;
+	unsigned RevMotDuringCloseLoopEn:1;
+	unsigned OverrideBrakeType:2;
+	unsigned ModeSelect:4;
+	unsigned RampThrottle:8;
+} TALON_Control_1_General_10ms_t ;
+
+/* TALON_Control_2_Rates_OneShot_t removed since it has been deprecated */
+
+typedef struct _TALON_Control_3_ClearFlags_OneShot_t {
+	unsigned ZeroFeedbackSensor:1;
+	unsigned ClearStickyFaults:1;
+} TALON_Control_3_ClearFlags_OneShot_t ;
+
+typedef struct _TALON_Control_5_General_10ms_t {
+	unsigned ThrottleBump_h3:3;
+	unsigned ReservedZero:5;
+	unsigned ThrottleBump_l8:8;
+	unsigned DemandH:8;
+	unsigned DemandM:8;
+	unsigned DemandL:8;
+	unsigned ProfileSlotSelect:1;
+	unsigned FeedbackDeviceSelect:4;
+	unsigned OverrideLimitSwitchEn:3;
+	unsigned RevFeedbackSensor:1;
+	unsigned RevMotDuringCloseLoopEn:1;
+	unsigned OverrideBrakeType:2;
+	unsigned ModeSelect:4;
+	unsigned RampThrottle:8;
+} TALON_Control_5_General_10ms_t ;
+
+typedef struct _TALON_Control_6_MotProfAddTrajPoint_t {
+	unsigned huffCode:2; //!< Compression coding
+	unsigned NextPt_VelOnly:1;
+	unsigned NextPt_IsLast:1;
+	unsigned reserved0:2;
+	unsigned NextPt_ZeroPosition:1;
+	unsigned NextPt_ProfileSlotSelect:1;
+	unsigned Idx:4;
+	unsigned reserved1:4;
+	unsigned restOfFrame0:8;
+	unsigned restOfFrame1:8;
+	unsigned restOfFrame2:8;
+	unsigned restOfFrame3:8;
+	unsigned restOfFrame4:8;
+	unsigned restOfFrame5:8;
+} TALON_Control_6_MotProfAddTrajPoint_t;
+
+typedef struct _TALON_Control_6_MotProfAddTrajPoint_huff0_t {
+	unsigned huffCode_expect_0:2; //!< Compression coding
+	unsigned NextPt_VelOnly:1;
+	unsigned NextPt_IsLast:1;
+	unsigned reserved0:2;
+	unsigned NextPt_ZeroPosition:1;
+	unsigned NextPt_ProfileSlotSelect:1;
+	unsigned Idx:4;
+	unsigned reserved1:4;
+	unsigned NextPt_DurationMs:8;
+	unsigned NextPt_VelocityH:8;
+	unsigned NextPt_VelocityL:8;
+	unsigned NextPt_PositionH:8;
+	unsigned NextPt_PositionM:8;
+	unsigned NextPt_PositionL:8;
+} TALON_Control_6_MotProfAddTrajPoint_huff0_t;
+
+typedef struct _TALON_Control_6_MotProfAddTrajPoint_huff1_t {
+	unsigned huffCode_expect_1:2; //!< Compression coding
+	unsigned NextPt_VelOnly:1;
+	unsigned NextPt_IsLast:1;
+	unsigned reserved0:2;
+	unsigned NextPt_ZeroPosition:1;
+	unsigned NextPt_ProfileSlotSelect:1;
+	unsigned Idx:4;
+	unsigned reserved1:4;
+	unsigned NextPt_DurationMs:8;
+	unsigned NextPt_SameVelocityH:8;
+	unsigned NextPt_SameVelocityL:8;
+	unsigned NextPt_DeltaPositionH:8;
+	unsigned NextPt_DeltaPositionL:8;
+	unsigned NextPt_Count:8;
+} TALON_Control_6_MotProfAddTrajPoint_huff1_t;
+
+/** status */
+typedef struct _TALON_Status_1_General_10ms_t {
+	unsigned CloseLoopErrH:8;
+	unsigned CloseLoopErrM:8;
+	unsigned CloseLoopErrL:8;
+	unsigned AppliedThrottle_h3:3;
+	unsigned Fault_RevSoftLim:1;
+	unsigned Fault_ForSoftLim:1;
+	unsigned TokLocked:1;
+	unsigned LimitSwitchClosedRev:1;
+	unsigned LimitSwitchClosedFor:1;
+	unsigned AppliedThrottle_l8:8;
+	unsigned ModeSelect_h1:1;
+	unsigned FeedbackDeviceSelect:4;
+	unsigned LimitSwitchEn:3;
+	unsigned Fault_HardwareFailure:1;
+	unsigned Fault_RevLim:1;
+	unsigned Fault_ForLim:1;
+	unsigned Fault_UnderVoltage:1;
+	unsigned Fault_OverTemp:1;
+	unsigned ModeSelect_b3:3;
+	unsigned TokenSeed:8;
+} TALON_Status_1_General_10ms_t ;
+typedef struct _TALON_Status_2_Feedback_20ms_t {
+	unsigned SensorPositionH:8;
+	unsigned SensorPositionM:8;
+	unsigned SensorPositionL:8;
+	unsigned SensorVelocityH:8;
+	unsigned SensorVelocityL:8;
+	unsigned Current_h8:8;
+	unsigned StckyFault_RevSoftLim:1;
+	unsigned StckyFault_ForSoftLim:1;
+	unsigned StckyFault_RevLim:1;
+	unsigned StckyFault_ForLim:1;
+	unsigned StckyFault_UnderVoltage:1;
+	unsigned StckyFault_OverTemp:1;
+	unsigned Current_l2:2;
+	unsigned reserved:3;
+	unsigned Cmd5Allowed:1;
+	unsigned VelDiv4:1;
+	unsigned PosDiv8:1;
+	unsigned ProfileSlotSelect:1;
+	unsigned BrakeIsEnabled:1;
+} TALON_Status_2_Feedback_20ms_t ;
+typedef struct _TALON_Status_3_Enc_100ms_t {
+	unsigned EncPositionH:8;
+	unsigned EncPositionM:8;
+	unsigned EncPositionL:8;
+	unsigned EncVelH:8;
+	unsigned EncVelL:8;
+	unsigned EncIndexRiseEventsH:8;
+	unsigned EncIndexRiseEventsL:8;
+	unsigned reserved:3;
+	unsigned VelDiv4:1;
+	unsigned PosDiv8:1;
+	unsigned QuadIdxpin:1;
+	unsigned QuadBpin:1;
+	unsigned QuadApin:1;
+} TALON_Status_3_Enc_100ms_t ;
+typedef struct _TALON_Status_4_AinTempVbat_100ms_t {
+	unsigned AnalogInWithOvH:8;
+	unsigned AnalogInWithOvM:8;
+	unsigned AnalogInWithOvL:8;
+	unsigned AnalogInVelH:8;
+	unsigned AnalogInVelL:8;
+	unsigned Temp:8;
+	unsigned BatteryV:8;
+	unsigned reserved:6;
+	unsigned VelDiv4:1;
+	unsigned PosDiv8:1;
+} TALON_Status_4_AinTempVbat_100ms_t ;
+typedef struct _TALON_Status_5_Startup_OneShot_t {
+	unsigned ResetCountH:8;
+	unsigned ResetCountL:8;
+	unsigned ResetFlagsH:8;
+	unsigned ResetFlagsL:8;
+	unsigned FirmVersH:8;
+	unsigned FirmVersL:8;
+} TALON_Status_5_Startup_OneShot_t ;
+typedef struct _TALON_Status_6_Eol_t {
+	unsigned currentAdcUncal_h2:2;
+	unsigned reserved1:5;
+	unsigned SpiCsPin_GadgeteerPin6:1;
+	unsigned currentAdcUncal_l8:8;
+	unsigned tempAdcUncal_h2:2;
+	unsigned reserved2:6;
+	unsigned tempAdcUncal_l8:8;
+	unsigned vbatAdcUncal_h2:2;
+	unsigned reserved3:6;
+	unsigned vbatAdcUncal_l8:8;
+	unsigned analogAdcUncal_h2:2;
+	unsigned reserved4:6;
+	unsigned analogAdcUncal_l8:8;
+} TALON_Status_6_Eol_t ;
+typedef struct _TALON_Status_7_Debug_200ms_t {
+	unsigned TokenizationFails_h8:8;
+	unsigned TokenizationFails_l8:8;
+	unsigned LastFailedToken_h8:8;
+	unsigned LastFailedToken_l8:8;
+	unsigned TokenizationSucceses_h8:8;
+	unsigned TokenizationSucceses_l8:8;
+} TALON_Status_7_Debug_200ms_t ;
+typedef struct _TALON_Status_8_PulseWid_100ms_t {
+	unsigned PulseWidPositionH:8;
+	unsigned PulseWidPositionM:8;
+	unsigned PulseWidPositionL:8;
+	unsigned reserved:6;
+	unsigned VelDiv4:1;
+	unsigned PosDiv8:1;
+	unsigned PeriodUsM8:8;
+	unsigned PeriodUsL8:8;
+	unsigned PulseWidVelH:8;
+	unsigned PulseWidVelL:8;
+} TALON_Status_8_PulseWid_100ms_t ;
+typedef struct _TALON_Status_9_MotProfBuffer_100ms_t {
+	unsigned ActTraj_IsValid:1; //!< '1' if other ActTraj_* signals are valid.  '0' if there is no active trajectory pt.
+	unsigned ActTraj_ProfileSlotSelect:1;
+	unsigned ActTraj_VelOnly:1;
+	unsigned ActTraj_IsLast:1;
+	unsigned OutputType:2;
+	unsigned HasUnderrun:1;
+	unsigned IsUnderrun:1;
+	unsigned NextID:4;
+	unsigned reserved1:3;
+	unsigned BufferIsFull:1;
+	unsigned Count:8;
+	unsigned ActTraj_VelocityH:8;
+	unsigned ActTraj_VelocityL:8;
+	unsigned ActTraj_PositionH:8;
+	unsigned ActTraj_PositionM:8;
+	unsigned ActTraj_PositionL:8;
+} TALON_Status_9_MotProfBuffer_100ms_t ;
+typedef struct _TALON_Param_Request_t {
+	unsigned ParamEnum:8;
+} TALON_Param_Request_t ;
+typedef struct _TALON_Param_Response_t {
+	unsigned ParamEnum:8;
+	unsigned ParamValueL:8;
+	unsigned ParamValueML:8;
+	unsigned ParamValueMH:8;
+	unsigned ParamValueH:8;
+} TALON_Param_Response_t ;
+
+#endif /* CTRE_FRAMES_H */
diff --git a/hal/lib/Athena/Accelerometer.cpp b/hal/lib/Athena/Accelerometer.cpp
index 0895c9c..315df10 100644
--- a/hal/lib/Athena/Accelerometer.cpp
+++ b/hal/lib/Athena/Accelerometer.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/Accelerometer.hpp"
 
 #include "ChipObject.h"
@@ -171,6 +178,8 @@
 	}
 }
 
+extern "C" {
+
 /**
  * Set the accelerometer to active or standby mode.  It must be in standby
  * mode to change any configuration.
@@ -232,3 +241,5 @@
 	int raw = (readRegister(kReg_OutZMSB) << 4) | (readRegister(kReg_OutZLSB) >> 4);
 	return unpackAxis(raw);
 }
+
+}  // extern "C"
diff --git a/hal/lib/Athena/Analog.cpp b/hal/lib/Athena/Analog.cpp
index e56d658..a34eb93 100644
--- a/hal/lib/Athena/Analog.cpp
+++ b/hal/lib/Athena/Analog.cpp
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/Analog.hpp"
 
@@ -24,18 +30,20 @@
   tAccumulator *accumulator;
 };
 
-bool analogSampleRateSet = false;
-priority_recursive_mutex analogRegisterWindowMutex;
-tAI* analogInputSystem = NULL;
-tAO* analogOutputSystem = NULL;
-uint32_t analogNumChannelsToActivate = 0;
+static bool analogSampleRateSet = false;
+static priority_recursive_mutex analogRegisterWindowMutex;
+static tAI* analogInputSystem = NULL;
+static tAO* analogOutputSystem = NULL;
+static uint32_t analogNumChannelsToActivate = 0;
+
+extern "C" {
 
 // Utility methods defined below.
-uint32_t getAnalogNumActiveChannels(int32_t *status);
-uint32_t getAnalogNumChannelsToActivate(int32_t *status);
-void setAnalogNumChannelsToActivate(uint32_t channels);
+static uint32_t getAnalogNumActiveChannels(int32_t *status);
+static uint32_t getAnalogNumChannelsToActivate(int32_t *status);
+static void setAnalogNumChannelsToActivate(uint32_t channels);
 
-bool analogSystemInitialized = false;
+static bool analogSystemInitialized = false;
 
 /**
  * Initialize the analog System.
@@ -424,7 +432,7 @@
  *
  * @return Active channels.
  */
-uint32_t getAnalogNumActiveChannels(int32_t *status) {
+static uint32_t getAnalogNumActiveChannels(int32_t *status) {
   uint32_t scanSize = analogInputSystem->readConfig_ScanSize(status);
   if (scanSize == 0)
     return 8;
@@ -442,7 +450,7 @@
  *
  * @return Value to write to the active channels field.
  */
-uint32_t getAnalogNumChannelsToActivate(int32_t *status) {
+static uint32_t getAnalogNumChannelsToActivate(int32_t *status) {
   if(analogNumChannelsToActivate == 0) return getAnalogNumActiveChannels(status);
   return analogNumChannelsToActivate;
 }
@@ -455,7 +463,7 @@
  *
  * @param channels Number of active channels.
  */
-void setAnalogNumChannelsToActivate(uint32_t channels) {
+static void setAnalogNumChannelsToActivate(uint32_t channels) {
   analogNumChannelsToActivate = channels;
 }
 
@@ -744,3 +752,5 @@
 void setAnalogTriggerLimitsVoltageIntHack(void* analog_trigger_pointer, int lower, int upper, int32_t *status) {
   setAnalogTriggerLimitsVoltage(analog_trigger_pointer, intToFloat(lower), intToFloat(upper), status);
 }
+
+}  // extern "C"
diff --git a/hal/lib/Athena/ChipObject.h b/hal/lib/Athena/ChipObject.h
index 630c34d..ac0fe71 100644
--- a/hal/lib/Athena/ChipObject.h
+++ b/hal/lib/Athena/ChipObject.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 #pragma GCC diagnostic push
 #pragma GCC diagnostic ignored "-Wpedantic"
diff --git a/hal/lib/Athena/Compressor.cpp b/hal/lib/Athena/Compressor.cpp
index 9305097..25986a4 100644
--- a/hal/lib/Athena/Compressor.cpp
+++ b/hal/lib/Athena/Compressor.cpp
@@ -1,15 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/Compressor.hpp"
 #include "ctre/PCM.h"
 #include <iostream>
 
 static const int NUM_MODULE_NUMBERS = 63;
-extern PCM *modules[NUM_MODULE_NUMBERS];
+extern PCM *PCM_modules[NUM_MODULE_NUMBERS];
 extern void initializePCM(int module);
 
+extern "C" {
+
 void *initializeCompressor(uint8_t module) {
 	initializePCM(module);
 	
-	return modules[module];
+	return PCM_modules[module];
 }
 
 bool checkCompressorModule(uint8_t module) {
@@ -114,3 +123,5 @@
 	
 	*status = module->ClearStickyFaults();
 }
+
+}  // extern "C"
diff --git a/hal/lib/Athena/Digital.cpp b/hal/lib/Athena/Digital.cpp
index 0d4ff5f..e82beca 100644
--- a/hal/lib/Athena/Digital.cpp
+++ b/hal/lib/Athena/Digital.cpp
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/Digital.hpp"
 
@@ -53,42 +59,43 @@
   uint32_t PWMGeneratorID;
 };
 
-// XXX: Set these back to static once we figure out the memory clobbering issue
 // Create a mutex to protect changes to the digital output values
-priority_recursive_mutex digitalDIOMutex;
+static priority_recursive_mutex digitalDIOMutex;
 // Create a mutex to protect changes to the relay values
-priority_recursive_mutex digitalRelayMutex;
+static priority_recursive_mutex digitalRelayMutex;
 // Create a mutex to protect changes to the DO PWM config
-priority_recursive_mutex digitalPwmMutex;
-priority_recursive_mutex digitalI2COnBoardMutex;
-priority_recursive_mutex digitalI2CMXPMutex;
+static priority_recursive_mutex digitalPwmMutex;
+static priority_recursive_mutex digitalI2COnBoardMutex;
+static priority_recursive_mutex digitalI2CMXPMutex;
 
-tDIO* digitalSystem = NULL;
-tRelay* relaySystem = NULL;
-tPWM* pwmSystem = NULL;
-hal::Resource *DIOChannels = NULL;
-hal::Resource *DO_PWMGenerators = NULL;
-hal::Resource *PWMChannels = NULL;
+static tDIO* digitalSystem = NULL;
+static tRelay* relaySystem = NULL;
+static tPWM* pwmSystem = NULL;
+static hal::Resource *DIOChannels = NULL;
+static hal::Resource *DO_PWMGenerators = NULL;
+static hal::Resource *PWMChannels = NULL;
 
-bool digitalSystemsInitialized = false;
+static bool digitalSystemsInitialized = false;
 
-uint8_t i2COnboardObjCount = 0;
-uint8_t i2CMXPObjCount = 0;
-uint8_t i2COnBoardHandle = 0;
-uint8_t i2CMXPHandle = 0;
+static uint8_t i2COnboardObjCount = 0;
+static uint8_t i2CMXPObjCount = 0;
+static uint8_t i2COnBoardHandle = 0;
+static uint8_t i2CMXPHandle = 0;
 
-int32_t m_spiCS0Handle = 0;
-int32_t m_spiCS1Handle = 0;
-int32_t m_spiCS2Handle = 0;
-int32_t m_spiCS3Handle = 0;
-int32_t m_spiMXPHandle = 0;
-priority_recursive_mutex spiOnboardSemaphore;
-priority_recursive_mutex spiMXPSemaphore;
-tSPI *spiSystem;
+static int32_t m_spiCS0Handle = 0;
+static int32_t m_spiCS1Handle = 0;
+static int32_t m_spiCS2Handle = 0;
+static int32_t m_spiCS3Handle = 0;
+static int32_t m_spiMXPHandle = 0;
+static priority_recursive_mutex spiOnboardSemaphore;
+static priority_recursive_mutex spiMXPSemaphore;
+static tSPI *spiSystem;
+
+extern "C" {
 
 struct SPIAccumulator {
 	void* notifier = nullptr;
-	uint32_t triggerTime;
+	uint64_t triggerTime;
 	uint32_t period;
 
 	int64_t value = 0;
@@ -805,7 +812,7 @@
  * If it's an analog trigger, determine the module from the high order routing channel
  * else do normal digital input remapping based on pin number (MXP)
  */
-void remapDigitalSource(bool analogTrigger, uint32_t &pin, uint8_t &module) {
+extern "C++" void remapDigitalSource(bool analogTrigger, uint32_t &pin, uint8_t &module) {
   if (analogTrigger) {
     module = pin >> 4;
   } else {
@@ -1492,14 +1499,14 @@
  * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
  * @return The semaphore for the SPI port.
  */
-priority_recursive_mutex& spiGetSemaphore(uint8_t port) {
+extern "C++" priority_recursive_mutex& spiGetSemaphore(uint8_t port) {
 	if(port < 4)
 		return spiOnboardSemaphore;
 	else
 		return spiMXPSemaphore;
 }
 
-static void spiAccumulatorProcess(uint32_t currentTime, void *param) {
+static void spiAccumulatorProcess(uint64_t currentTime, void *param) {
 	SPIAccumulator* accum = (SPIAccumulator*)param;
 
 	// perform SPI transaction
@@ -1872,3 +1879,5 @@
 	}
 	return;
 }
+
+}  // extern "C"
diff --git a/hal/lib/Athena/HALAthena.cpp b/hal/lib/Athena/HALAthena.cpp
index b1ffcb1..3a392f1 100644
--- a/hal/lib/Athena/HALAthena.cpp
+++ b/hal/lib/Athena/HALAthena.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/HAL.hpp"
 
 #include "HAL/Port.h"
@@ -12,6 +19,7 @@
 #include <cstdlib>
 #include <fstream>
 #include <iostream>
+#include <mutex>
 #include <unistd.h>
 #include <sys/prctl.h>
 #include <signal.h> // linux for kill
@@ -23,6 +31,14 @@
 static tGlobal *global = nullptr;
 static tSysWatchdog *watchdog = nullptr;
 
+static priority_mutex timeMutex;
+static priority_mutex msgMutex;
+static uint32_t timeEpoch = 0;
+static uint32_t prevFPGATime = 0;
+static void* rolloverNotifier = nullptr;
+
+extern "C" {
+
 void* getPort(uint8_t pin)
 {
 	Port* port = new Port();
@@ -99,6 +115,8 @@
 			return INCOMPATIBLE_STATE_MESSAGE;
 		case NO_AVAILABLE_RESOURCES:
 			return NO_AVAILABLE_RESOURCES_MESSAGE;
+		case RESOURCE_IS_ALLOCATED:
+			return RESOURCE_IS_ALLOCATED_MESSAGE;
 		case NULL_PARAMETER:
 			return NULL_PARAMETER_MESSAGE;
 		case ANALOG_TRIGGER_LIMIT_ORDER_ERROR:
@@ -182,13 +200,19 @@
  *
  * @return The current time in microseconds according to the FPGA (since FPGA reset).
  */
-uint32_t getFPGATime(int32_t *status)
+uint64_t getFPGATime(int32_t *status)
 {
 	if (!global) {
 		*status = NiFpga_Status_ResourceNotInitialized;
 		return 0;
 	}
-	return global->readLocalTime(status);
+	std::lock_guard<priority_mutex> lock(timeMutex);
+	uint32_t fpgaTime = global->readLocalTime(status);
+	if (*status != 0) return 0;
+	// check for rollover
+	if (fpgaTime < prevFPGATime) ++timeEpoch;
+	prevFPGATime = fpgaTime;
+	return (((uint64_t)timeEpoch) << 32) | ((uint64_t)fpgaTime);
 }
 
 /**
@@ -209,6 +233,54 @@
 	return setErrorData(errors, errorsLength, wait_ms);
 }
 
+int HALSendError(int isError, int32_t errorCode, int isLVCode,
+	const char *details, const char *location, const char *callStack,
+	int printMsg)
+{
+	// Avoid flooding console by keeping track of previous 5 error
+	// messages and only printing again if they're longer than 1 second old.
+	static constexpr int KEEP_MSGS = 5;
+	std::lock_guard<priority_mutex> lock(msgMutex);
+	static std::string prev_msg[KEEP_MSGS];
+	static uint64_t prev_msg_time[KEEP_MSGS] = { 0, 0, 0 };
+
+	int32_t status = 0;
+	uint64_t curTime = getFPGATime(&status);
+	int i;
+	for (i=0; i<KEEP_MSGS; ++i) {
+		if (prev_msg[i] == details) break;
+	}
+	int retval = 0;
+	if (i == KEEP_MSGS || (curTime - prev_msg_time[i]) >= 1000000) {
+		retval = FRC_NetworkCommunication_sendError(isError, errorCode, isLVCode, details, location, callStack);
+		if (printMsg) {
+			if (location && location[0] != '\0') {
+				fprintf(stderr, "%s at %s: ",
+					isError ? "Error" : "Warning",
+					location);
+			}
+			fprintf(stderr, "%s\n", details);
+			if (callStack && callStack[0] != '\0') {
+				fprintf(stderr, "%s\n", callStack);
+			}
+		}
+		if (i == KEEP_MSGS) {
+			// replace the oldest one
+			i = 0;
+			uint64_t first = prev_msg_time[0];
+			for (int j=1; j<KEEP_MSGS; ++j) {
+				if (prev_msg_time[j] < first) {
+					first = prev_msg_time[j];
+					i = j;
+				}
+			}
+			prev_msg[i] = details;
+		}
+		prev_msg_time[i] = curTime;
+	}
+	return retval;
+}
+
 
 bool HALGetSystemActive(int32_t *status)
 {
@@ -233,6 +305,12 @@
 	watchdog = nullptr;
 }
 
+static void timerRollover(uint64_t currentTime, void*) {
+	// reschedule timer for next rollover
+	int32_t status = 0;
+	updateNotifierAlarm(rolloverNotifier, currentTime + 0x80000000ULL, &status);
+}
+
 /**
  * Call this to start up HAL. This is required for robot programs.
  */
@@ -254,6 +332,14 @@
 
 	std::atexit(HALCleanupAtExit);
 
+	if (!rolloverNotifier)
+		rolloverNotifier = initializeNotifier(timerRollover, nullptr, &status);
+	if (status == 0) {
+		uint64_t curTime = getFPGATime(&status);
+		if (status == 0)
+			updateNotifierAlarm(rolloverNotifier, curTime + 0x80000000ULL, &status);
+	}
+
 	// Kill any previous robot programs
 	std::fstream fs;
 	// By making this both in/out, it won't give us an error if it doesnt exist
@@ -300,6 +386,7 @@
 	pid = getpid();
 	fs << pid << std::endl;
 	fs.close();
+
 	return 1;
 }
 
@@ -337,3 +424,5 @@
 void niTimestamp64()
 {
 }
+
+}  // extern "C"
diff --git a/hal/lib/Athena/Interrupts.cpp b/hal/lib/Athena/Interrupts.cpp
index e5ad2af..55c4660 100644
--- a/hal/lib/Athena/Interrupts.cpp
+++ b/hal/lib/Athena/Interrupts.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/Interrupts.hpp"
 #include "ChipObject.h"
 
@@ -9,6 +16,8 @@
 	tInterruptManager *manager;
 };
 
+extern "C" {
+
 void* initializeInterrupts(uint32_t interruptIndex, bool watcher, int32_t *status)
 {
 	Interrupt* anInterrupt = new Interrupt();
@@ -121,3 +130,5 @@
 	anInterrupt->anInterrupt->writeConfig_RisingEdge(risingEdge, status);
 	anInterrupt->anInterrupt->writeConfig_FallingEdge(fallingEdge, status);
 }
+
+}  // extern "C"
diff --git a/hal/lib/Athena/Notifier.cpp b/hal/lib/Athena/Notifier.cpp
index c2c6c4c..2184b5a 100644
--- a/hal/lib/Athena/Notifier.cpp
+++ b/hal/lib/Athena/Notifier.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/Notifier.hpp"
 #include "ChipObject.h"
 #include "HAL/HAL.hpp"
@@ -12,12 +19,12 @@
 static priority_recursive_mutex notifierMutex;
 static tAlarm *notifierAlarm = nullptr;
 static tInterruptManager *notifierManager = nullptr;
-static uint32_t closestTrigger = UINT32_MAX;
+static uint64_t closestTrigger = UINT64_MAX;
 struct Notifier {
 	Notifier *prev, *next;
 	void *param;
-	void (*process)(uint32_t, void*);
-	uint32_t triggerTime = UINT32_MAX;
+	void (*process)(uint64_t, void*);
+	uint64_t triggerTime = UINT64_MAX;
 };
 static Notifier *notifiers = nullptr;
 static std::atomic_flag notifierAtexitRegistered = ATOMIC_FLAG_INIT;
@@ -28,19 +35,19 @@
 	std::unique_lock<priority_recursive_mutex> sync(notifierMutex);
 
 	int32_t status = 0;
-	uint32_t currentTime = 0;
+	uint64_t currentTime = 0;
 
 	// the hardware disables itself after each alarm
-	closestTrigger = UINT32_MAX;
+	closestTrigger = UINT64_MAX;
 
 	// process all notifiers
 	Notifier *notifier = notifiers;
 	while (notifier) {
-		if (notifier->triggerTime != UINT32_MAX) {
+		if (notifier->triggerTime != UINT64_MAX) {
 			if (currentTime == 0)
 				currentTime = getFPGATime(&status);
 			if (notifier->triggerTime < currentTime) {
-				notifier->triggerTime = UINT32_MAX;
+				notifier->triggerTime = UINT64_MAX;
 				auto process = notifier->process;
 				auto param = notifier->param;
 				sync.unlock();
@@ -59,9 +66,11 @@
 	notifierManager = nullptr;
 }
 
-void* initializeNotifier(void (*ProcessQueue)(uint32_t, void*), void *param, int32_t *status)
+extern "C" {
+
+void* initializeNotifier(void (*process)(uint64_t, void*), void *param, int32_t *status)
 {
-	if (!ProcessQueue) {
+	if (!process) {
 		*status = NULL_PARAMETER;
 		return nullptr;
 	}
@@ -85,7 +94,7 @@
 	notifier->next = notifiers;
 	if (notifier->next) notifier->next->prev = notifier;
 	notifier->param = param;
-	notifier->process = ProcessQueue;
+	notifier->process = process;
 	notifiers = notifier;
 	return notifier;
 }
@@ -119,25 +128,40 @@
 	}
 }
 
-void updateNotifierAlarm(void* notifier_pointer, uint32_t triggerTime, int32_t *status)
+void* getNotifierParam(void* notifier_pointer, int32_t *status)
+{
+	return ((Notifier*)notifier_pointer)->param;
+}
+
+void updateNotifierAlarm(void* notifier_pointer, uint64_t triggerTime, int32_t *status)
 {
 	std::lock_guard<priority_recursive_mutex> sync(notifierMutex);
 
 	Notifier* notifier = (Notifier*)notifier_pointer;
 	notifier->triggerTime = triggerTime;
-	bool wasActive = (closestTrigger != UINT32_MAX);
+	bool wasActive = (closestTrigger != UINT64_MAX);
 
-        if (!notifierInterruptMutex.try_lock() || notifierRefCount == 0 ||
-            !notifierAlarm)
-          return;
+	if (!notifierInterruptMutex.try_lock() || notifierRefCount == 0 ||
+			!notifierAlarm)
+		return;
 
-        // Update alarm time if closer than current.
+	// Update alarm time if closer than current.
 	if (triggerTime < closestTrigger) {
 		closestTrigger = triggerTime;
-		notifierAlarm->writeTriggerTime(triggerTime, status);
+		// Simply truncate the hardware trigger time to 32-bit.
+		notifierAlarm->writeTriggerTime((uint32_t)triggerTime, status);
 	}
 	// Enable the alarm.  The hardware disables itself after each alarm.
 	if (!wasActive) notifierAlarm->writeEnable(true, status);
 
 	notifierInterruptMutex.unlock();
 }
+
+void stopNotifierAlarm(void* notifier_pointer, int32_t *status)
+{
+	std::lock_guard<priority_recursive_mutex> sync(notifierMutex);
+	Notifier* notifier = (Notifier*)notifier_pointer;
+	notifier->triggerTime = UINT64_MAX;
+}
+
+}  // extern "C"
diff --git a/hal/lib/Athena/PDP.cpp b/hal/lib/Athena/PDP.cpp
index 26fb4f6..334e8d4 100644
--- a/hal/lib/Athena/PDP.cpp
+++ b/hal/lib/Athena/PDP.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/PDP.hpp"
 #include "ctre/PDP.h"
 //static PDP pdp;
@@ -6,6 +13,8 @@
 
 static PDP *pdp[NUM_MODULE_NUMBERS] = { NULL };
 
+extern "C" {
+
 void initializePDP(uint8_t module) {
 	if(!pdp[module]) {
 		pdp[module] = new PDP(module);
@@ -68,4 +77,4 @@
 	*status = pdp[module]->ClearStickyFaults();
 }
 
-
+}  // extern "C"
diff --git a/hal/lib/Athena/Power.cpp b/hal/lib/Athena/Power.cpp
index cde96ea..47da918 100644
--- a/hal/lib/Athena/Power.cpp
+++ b/hal/lib/Athena/Power.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/Power.hpp"
 #include "ChipObject.h"
 
@@ -9,6 +16,8 @@
 	}
 }
 
+extern "C" {
+
 /**
  * Get the roboRIO input voltage
  */
@@ -125,3 +134,5 @@
 	initializePower(status);
 	return (int)power->readFaultCounts_OverCurrentFaultCount3V3(status);
 }
+
+}  // extern "C"
diff --git a/hal/lib/Athena/Semaphore.cpp b/hal/lib/Athena/Semaphore.cpp
index db9e9a3..8403438 100644
--- a/hal/lib/Athena/Semaphore.cpp
+++ b/hal/lib/Athena/Semaphore.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/Semaphore.hpp"
 
 #include "Log.hpp"
@@ -9,6 +16,8 @@
     if (level > semaphoreLogLevel) ; \
     else Log().Get(level)
 
+extern "C" {
+
 MUTEX_ID initializeMutexNormal() { return new priority_mutex; }
 
 void deleteMutex(MUTEX_ID sem) { delete sem; }
@@ -40,3 +49,5 @@
 }
 
 void giveMultiWait(MULTIWAIT_ID cond) { cond->notify_all(); }
+
+}  // extern "C"
diff --git a/hal/lib/Athena/SerialPort.cpp b/hal/lib/Athena/SerialPort.cpp
index 7393e2c..5e8d065 100644
--- a/hal/lib/Athena/SerialPort.cpp
+++ b/hal/lib/Athena/SerialPort.cpp
@@ -1,9 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/SerialPort.hpp"
 #include "visa/visa.h"
 
 
-uint32_t m_resourceManagerHandle;
-uint32_t m_portHandle[2];
+static uint32_t m_resourceManagerHandle;
+static uint32_t m_portHandle[2];
+
+extern "C" {
 
 void serialInitializePort(uint8_t port, int32_t *status) {
 	char const * portName;
@@ -144,5 +153,5 @@
 	if(*status > 0)
 		*status = 0;
 }
-	
-	
\ No newline at end of file
+
+}  // extern "C"
diff --git a/hal/lib/Athena/Solenoid.cpp b/hal/lib/Athena/Solenoid.cpp
index a95d836..6df930a 100644
--- a/hal/lib/Athena/Solenoid.cpp
+++ b/hal/lib/Athena/Solenoid.cpp
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/Solenoid.hpp"
 
@@ -9,7 +15,7 @@
 
 static const int NUM_MODULE_NUMBERS = 63;
 
-PCM *modules[NUM_MODULE_NUMBERS] = { NULL };
+PCM *PCM_modules[NUM_MODULE_NUMBERS] = { NULL };
 
 struct solenoid_port_t {
 	PCM *module;
@@ -17,17 +23,19 @@
 };
 
 void initializePCM(int module) {
-	if(!modules[module]) {
-		modules[module] = new PCM(module);
+	if(!PCM_modules[module]) {
+		PCM_modules[module] = new PCM(module);
 	}
 }
 
+extern "C" {
+
 void* initializeSolenoidPort(void *port_pointer, int32_t *status) {
 	Port* port = (Port*) port_pointer;
 	initializePCM(port->module);
 	
 	solenoid_port_t *solenoid_port = new solenoid_port_t;
-	solenoid_port->module = modules[port->module];
+	solenoid_port->module = PCM_modules[port->module];
 	solenoid_port->pin = port->pin;
 
 	return solenoid_port;
@@ -95,3 +103,5 @@
 	
 	*status = port->module->ClearStickyFaults();
 }
+
+}  // extern "C"
diff --git a/hal/lib/Athena/Task.cpp b/hal/lib/Athena/Task.cpp
index 9e4b2e9..3536544 100644
--- a/hal/lib/Athena/Task.cpp
+++ b/hal/lib/Athena/Task.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/Task.hpp"
 
 #ifndef OK
@@ -9,6 +16,8 @@
 
 #include <signal.h>
 
+extern "C" {
+
 STATUS verifyTaskID(TASK task) {
   if (task != nullptr && pthread_kill(*task, 0) == 0) {
 	return OK;
@@ -49,3 +58,5 @@
     return ERROR;
   }
 }
+
+}  // extern "C"
diff --git a/hal/lib/Athena/Utilities.cpp b/hal/lib/Athena/Utilities.cpp
index b34677f..5c22ea8 100644
--- a/hal/lib/Athena/Utilities.cpp
+++ b/hal/lib/Athena/Utilities.cpp
@@ -1,9 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/Utilities.hpp"
 #include <time.h>
 
 const int32_t HAL_NO_WAIT = 0;
 const int32_t HAL_WAIT_FOREVER = -1;
 
+extern "C" {
+
 void delayTicks(int32_t ticks)
 {
 	struct timespec test, remaining;
@@ -42,3 +51,5 @@
 		test = remaining;
 	}
 }
+
+}  // extern "C"
diff --git a/hal/lib/Athena/cpp/Resource.cpp b/hal/lib/Athena/cpp/Resource.cpp
index 3e7e86d..3e13d63 100644
--- a/hal/lib/Athena/cpp/Resource.cpp
+++ b/hal/lib/Athena/cpp/Resource.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "HAL/cpp/Resource.hpp"
diff --git a/hal/lib/Athena/cpp/Semaphore.cpp b/hal/lib/Athena/cpp/Semaphore.cpp
index 458ca6e..56349e3 100644
--- a/hal/lib/Athena/cpp/Semaphore.cpp
+++ b/hal/lib/Athena/cpp/Semaphore.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2015. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2015-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "HAL/cpp/Semaphore.hpp"
diff --git a/hal/lib/Athena/cpp/priority_mutex.cpp b/hal/lib/Athena/cpp/priority_mutex.cpp
index 66d3dcc..5aed982 100644
--- a/hal/lib/Athena/cpp/priority_mutex.cpp
+++ b/hal/lib/Athena/cpp/priority_mutex.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/cpp/priority_mutex.h"
 
 void priority_recursive_mutex::lock() {
diff --git a/hal/lib/Athena/ctre/CanTalonSRX.cpp b/hal/lib/Athena/ctre/CanTalonSRX.cpp
index 56e68e1..2f6198d 100644
--- a/hal/lib/Athena/ctre/CanTalonSRX.cpp
+++ b/hal/lib/Athena/ctre/CanTalonSRX.cpp
@@ -1,1417 +1,2020 @@
-/**

- * @brief CAN TALON SRX driver.

- *

- * The TALON SRX is designed to instrument all runtime signals periodically.  The default periods are chosen to support 16 TALONs

- * with 10ms update rate for control (throttle or setpoint).  However these can be overridden with SetStatusFrameRate. @see SetStatusFrameRate

- * The getters for these unsolicited signals are auto generated at the bottom of this module.

- *

- * Likewise most control signals are sent periodically using the fire-and-forget CAN API.

- * The setters for these unsolicited signals are auto generated at the bottom of this module.

- *

- * Signals that are not available in an unsolicited fashion are the Close Loop gains.

- * For teams that have a single profile for their TALON close loop they can use either the webpage to configure their TALONs once

- * 	or set the PIDF,Izone,CloseLoopRampRate,etc... once in the robot application.  These parameters are saved to flash so once they are

- * 	loaded in the TALON, they will persist through power cycles and mode changes.

- *

- * For teams that have one or two profiles to switch between, they can use the same strategy since there are two slots to choose from

- * and the ProfileSlotSelect is periodically sent in the 10 ms control frame.

- *

- * For teams that require changing gains frequently, they can use the soliciting API to get and set those parameters.  Most likely

- * they will only need to set them in a periodic fashion as a function of what motion the application is attempting.

- * If this API is used, be mindful of the CAN utilization reported in the driver station.

- *

- * If calling application has used the config routines to configure the selected feedback sensor, then all positions are measured in

- * floating point precision rotations.  All sensor velocities are specified in floating point precision RPM.

- *	@see ConfigPotentiometerTurns

- *	@see ConfigEncoderCodesPerRev

- * HOWEVER, if calling application has not called the config routine for selected feedback sensor, then all getters/setters for

- * position/velocity use the native engineering units of the Talon SRX firm (just like in 2015).  Signals explained below.

- *

- * Encoder position is measured in encoder edges.  Every edge is counted (similar to roboRIO 4X mode).

- * Analog position is 10 bits, meaning 1024 ticks per rotation (0V => 3.3V).

- * Use SetFeedbackDeviceSelect to select which sensor type you need.  Once you do that you can use GetSensorPosition()

- * and GetSensorVelocity().  These signals are updated on CANBus every 20ms (by default).

- * If a relative sensor is selected, you can zero (or change the current value) using SetSensorPosition.

- *

- * Analog Input and quadrature position (and velocity) are also explicitly reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel.

- * These signals are available all the time, regardless of what sensor is selected at a rate of 100ms.  This allows easy instrumentation

- * for "in the pits" checking of all sensors regardless of modeselect.  The 100ms rate is overridable for teams who want to acquire sensor

- * data for processing, not just instrumentation.  Or just select the sensor using SetFeedbackDeviceSelect to get it at 20ms.

- *

- * Velocity is in position ticks / 100ms.

- *

- * All output units are in respect to duty cycle (throttle) which is -1023(full reverse) to +1023 (full forward).

- *  This includes demand (which specifies duty cycle when in duty cycle mode) and rampRamp, which is in throttle units per 10ms (if nonzero).

- *

- * Pos and velocity close loops are calc'd as

- * 		err = target - posOrVel.

- * 		iErr += err;

- * 		if(   (IZone!=0)  and  abs(err) > IZone)

- * 			ClearIaccum()

- * 		output = P X err + I X iErr + D X dErr + F X target

- * 		dErr = err - lastErr

- *	P, I,and D gains are always positive. F can be negative.

- *	Motor direction can be reversed using SetRevMotDuringCloseLoopEn if sensor and motor are out of phase.

- *	Similarly feedback sensor can also be reversed (multiplied by -1) if you prefer the sensor to be inverted.

- *

- * P gain is specified in throttle per error tick.  For example, a value of 102 is ~9.9% (which is 102/1023) throttle per 1

- * 		ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.

- *

- * I gain is specified in throttle per integrated error. For example, a value of 10 equates to ~0.99% (which is 10/1023)

- *  	for each accumulated ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.

- *  	Close loop and integral accumulator runs every 1ms.

- *

- * D gain is specified in throttle per derivative error. For example a value of 102 equates to ~9.9% (which is 102/1023)

- * 	per change of 1 unit (ADC or encoder) per ms.

- *

- * I Zone is specified in the same units as sensor position (ADC units or quadrature edges).  If pos/vel error is outside of

- * 		this value, the integrated error will auto-clear...

- * 		if(   (IZone!=0)  and  abs(err) > IZone)

- * 			ClearIaccum()

- * 		...this is very useful in preventing integral windup and is highly recommended if using full PID to keep stability low.

- *

- * CloseLoopRampRate is in throttle units per 1ms.  Set to zero to disable ramping.

- * 		Works the same as RampThrottle but only is in effect when a close loop mode and profile slot is selected.

- *

- * auto generated using spreadsheet and WpiClassGen.csproj

- * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967

- */

-#include "HAL/CanTalonSRX.h"

-#include "FRC_NetworkCommunication/CANSessionMux.h"	//CAN Comm

-#include <string.h> // memset

-#include <unistd.h> // usleep

-

-#define STATUS_1  		0x02041400

-#define STATUS_2  		0x02041440

-#define STATUS_3  		0x02041480

-#define STATUS_4  		0x020414C0

-#define STATUS_5  		0x02041500

-#define STATUS_6  		0x02041540

-#define STATUS_7  		0x02041580

-#define STATUS_8  		0x020415C0

-

-#define CONTROL_1 			0x02040000

-#define CONTROL_2 			0x02040040

-#define CONTROL_3 			0x02040080

-

-#define EXPECTED_RESPONSE_TIMEOUT_MS	(200)

-#define GET_STATUS1() CtreCanNode::recMsg<TALON_Status_1_General_10ms_t		> rx = GetRx<TALON_Status_1_General_10ms_t>(STATUS_1	  | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

-#define GET_STATUS2() CtreCanNode::recMsg<TALON_Status_2_Feedback_20ms_t	> rx = GetRx<TALON_Status_2_Feedback_20ms_t>(STATUS_2	  | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

-#define GET_STATUS3() CtreCanNode::recMsg<TALON_Status_3_Enc_100ms_t		> rx = GetRx<TALON_Status_3_Enc_100ms_t>(STATUS_3		  | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

-#define GET_STATUS4() CtreCanNode::recMsg<TALON_Status_4_AinTempVbat_100ms_t> rx = GetRx<TALON_Status_4_AinTempVbat_100ms_t>(STATUS_4 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

-#define GET_STATUS5() CtreCanNode::recMsg<TALON_Status_5_Startup_OneShot_t	> rx = GetRx<TALON_Status_5_Startup_OneShot_t>(STATUS_5	  | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

-#define GET_STATUS6() CtreCanNode::recMsg<TALON_Status_6_Eol_t				> rx = GetRx<TALON_Status_6_Eol_t>(STATUS_6				  | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

-#define GET_STATUS7() CtreCanNode::recMsg<TALON_Status_7_Debug_200ms_t		> rx = GetRx<TALON_Status_7_Debug_200ms_t>(STATUS_7		  | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

-#define GET_STATUS8() CtreCanNode::recMsg<TALON_Status_8_PulseWid_100ms_t	> rx = GetRx<TALON_Status_8_PulseWid_100ms_t>(STATUS_8	  | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

-

-#define PARAM_REQUEST 		0x02041800

-#define PARAM_RESPONSE 		0x02041840

-#define PARAM_SET			0x02041880

-

-const int kParamArbIdValue = 	PARAM_RESPONSE;

-const int kParamArbIdMask = 	0xFFFFFFFF;

-

-const double FLOAT_TO_FXP_10_22 = (double)0x400000;

-const double FXP_TO_FLOAT_10_22 = 0.0000002384185791015625;

-

-const double FLOAT_TO_FXP_0_8 = (double)0x100;

-const double FXP_TO_FLOAT_0_8 = 0.00390625;

-

-/* encoder/decoders */

-/** control */

-typedef struct _TALON_Control_1_General_10ms_t {

-	unsigned TokenH:8;

-	unsigned TokenL:8;

-	unsigned DemandH:8;

-	unsigned DemandM:8;

-	unsigned DemandL:8;

-	unsigned ProfileSlotSelect:1;

-	unsigned FeedbackDeviceSelect:4;

-	unsigned OverrideLimitSwitchEn:3;

-	unsigned RevFeedbackSensor:1;

-	unsigned RevMotDuringCloseLoopEn:1;

-	unsigned OverrideBrakeType:2;

-	unsigned ModeSelect:4;

-	unsigned RampThrottle:8;

-} TALON_Control_1_General_10ms_t ;

-typedef struct _TALON_Control_2_Rates_OneShot_t {

-	unsigned Status1Ms:8;

-	unsigned Status2Ms:8;

-	unsigned Status3Ms:8;

-	unsigned Status4Ms:8;

-	unsigned StatusPulWidMs:8;	// TALON_Status_8_PulseWid_100ms_t

-} TALON_Control_2_Rates_OneShot_t ;

-typedef struct _TALON_Control_3_ClearFlags_OneShot_t {

-	unsigned ZeroFeedbackSensor:1;

-	unsigned ClearStickyFaults:1;

-} TALON_Control_3_ClearFlags_OneShot_t ;

-

-/** status */

-typedef struct _TALON_Status_1_General_10ms_t {

-	unsigned CloseLoopErrH:8;

-	unsigned CloseLoopErrM:8;

-	unsigned CloseLoopErrL:8;

-	unsigned AppliedThrottle_h3:3;

-	unsigned Fault_RevSoftLim:1;

-	unsigned Fault_ForSoftLim:1;

-	unsigned TokLocked:1;

-	unsigned LimitSwitchClosedRev:1;

-	unsigned LimitSwitchClosedFor:1;

-	unsigned AppliedThrottle_l8:8;

-	unsigned ModeSelect_h1:1;

-	unsigned FeedbackDeviceSelect:4;

-	unsigned LimitSwitchEn:3;

-	unsigned Fault_HardwareFailure:1;

-	unsigned Fault_RevLim:1;

-	unsigned Fault_ForLim:1;

-	unsigned Fault_UnderVoltage:1;

-	unsigned Fault_OverTemp:1;

-	unsigned ModeSelect_b3:3;

-	unsigned TokenSeed:8;

-} TALON_Status_1_General_10ms_t ;

-typedef struct _TALON_Status_2_Feedback_20ms_t {

-	unsigned SensorPositionH:8;

-	unsigned SensorPositionM:8;

-	unsigned SensorPositionL:8;

-	unsigned SensorVelocityH:8;

-	unsigned SensorVelocityL:8;

-	unsigned Current_h8:8;

-	unsigned StckyFault_RevSoftLim:1;

-	unsigned StckyFault_ForSoftLim:1;

-	unsigned StckyFault_RevLim:1;

-	unsigned StckyFault_ForLim:1;

-	unsigned StckyFault_UnderVoltage:1;

-	unsigned StckyFault_OverTemp:1;

-	unsigned Current_l2:2;

-	unsigned reserved2:4;

-	unsigned VelDiv4:1;

-	unsigned PosDiv8:1;

-	unsigned ProfileSlotSelect:1;

-	unsigned BrakeIsEnabled:1;

-} TALON_Status_2_Feedback_20ms_t ;

-typedef struct _TALON_Status_3_Enc_100ms_t {

-	unsigned EncPositionH:8;

-	unsigned EncPositionM:8;

-	unsigned EncPositionL:8;

-	unsigned EncVelH:8;

-	unsigned EncVelL:8;

-	unsigned EncIndexRiseEventsH:8;

-	unsigned EncIndexRiseEventsL:8;

-	unsigned reserved:3;

-	unsigned VelDiv4:1;

-	unsigned PosDiv8:1;

-	unsigned QuadIdxpin:1;

-	unsigned QuadBpin:1;

-	unsigned QuadApin:1;

-} TALON_Status_3_Enc_100ms_t ;

-typedef struct _TALON_Status_4_AinTempVbat_100ms_t {

-	unsigned AnalogInWithOvH:8;

-	unsigned AnalogInWithOvM:8;

-	unsigned AnalogInWithOvL:8;

-	unsigned AnalogInVelH:8;

-	unsigned AnalogInVelL:8;

-	unsigned Temp:8;

-	unsigned BatteryV:8;

-	unsigned reserved:6;

-	unsigned VelDiv4:1;

-	unsigned PosDiv8:1;

-} TALON_Status_4_AinTempVbat_100ms_t ;

-typedef struct _TALON_Status_5_Startup_OneShot_t {

-	unsigned ResetCountH:8;

-	unsigned ResetCountL:8;

-	unsigned ResetFlagsH:8;

-	unsigned ResetFlagsL:8;

-	unsigned FirmVersH:8;

-	unsigned FirmVersL:8;

-} TALON_Status_5_Startup_OneShot_t ;

-typedef struct _TALON_Status_6_Eol_t {

-	unsigned currentAdcUncal_h2:2;

-	unsigned reserved1:5;

-	unsigned SpiCsPin_GadgeteerPin6:1;

-	unsigned currentAdcUncal_l8:8;

-	unsigned tempAdcUncal_h2:2;

-	unsigned reserved2:6;

-	unsigned tempAdcUncal_l8:8;

-	unsigned vbatAdcUncal_h2:2;

-	unsigned reserved3:6;

-	unsigned vbatAdcUncal_l8:8;

-	unsigned analogAdcUncal_h2:2;

-	unsigned reserved4:6;

-	unsigned analogAdcUncal_l8:8;

-} TALON_Status_6_Eol_t ;

-typedef struct _TALON_Status_7_Debug_200ms_t {

-	unsigned TokenizationFails_h8:8;

-	unsigned TokenizationFails_l8:8;

-	unsigned LastFailedToken_h8:8;

-	unsigned LastFailedToken_l8:8;

-	unsigned TokenizationSucceses_h8:8;

-	unsigned TokenizationSucceses_l8:8;

-} TALON_Status_7_Debug_200ms_t ;

-typedef struct _TALON_Status_8_PulseWid_100ms_t {

-	unsigned PulseWidPositionH:8;

-	unsigned PulseWidPositionM:8;

-	unsigned PulseWidPositionL:8;

-	unsigned reserved:6;

-	unsigned VelDiv4:1;

-	unsigned PosDiv8:1;

-	unsigned PeriodUsM8:8;

-	unsigned PeriodUsL8:8;

-	unsigned PulseWidVelH:8;

-	unsigned PulseWidVelL:8;

-} TALON_Status_8_PulseWid_100ms_t ;

-typedef struct _TALON_Param_Request_t {

-	unsigned ParamEnum:8;

-} TALON_Param_Request_t ;

-typedef struct _TALON_Param_Response_t {

-	unsigned ParamEnum:8;

-	unsigned ParamValueL:8;

-	unsigned ParamValueML:8;

-	unsigned ParamValueMH:8;

-	unsigned ParamValueH:8;

-} TALON_Param_Response_t ;

-

-CanTalonSRX::CanTalonSRX(int deviceNumber,int controlPeriodMs): CtreCanNode(deviceNumber), _can_h(0), _can_stat(0)

-{

-	/* bound period to be within [1 ms,95 ms] */

-	if(controlPeriodMs < 1)

-		controlPeriodMs = 1;

-	else if(controlPeriodMs > 95)

-		controlPeriodMs = 95;

-	RegisterRx(STATUS_1 | (UINT8)deviceNumber );

-	RegisterRx(STATUS_2 | (UINT8)deviceNumber );

-	RegisterRx(STATUS_3 | (UINT8)deviceNumber );

-	RegisterRx(STATUS_4 | (UINT8)deviceNumber );

-	RegisterRx(STATUS_5 | (UINT8)deviceNumber );

-	RegisterRx(STATUS_6 | (UINT8)deviceNumber );

-	RegisterRx(STATUS_7 | (UINT8)deviceNumber );

-	RegisterTx(CONTROL_1 | (UINT8)deviceNumber, (UINT8)controlPeriodMs);

-	/* the only default param that is nonzero is limit switch.

-	 * Default to using the flash settings. */

-	SetOverrideLimitSwitchEn(kLimitSwitchOverride_UseDefaultsFromFlash);

-}

-/* CanTalonSRX D'tor

- */

-CanTalonSRX::~CanTalonSRX()

-{

-	if (m_hasBeenMoved){

-		/* Another CANTalonSRX still exists, so

-		 don't un-register the periodic control frame */

-	}else{

-		/* un-register the control frame so Talon is disabled */

-		RegisterTx(CONTROL_1 | (UINT8)GetDeviceNumber(), 0);

-	}

-	/* free the stream we used for SetParam/GetParamResponse */

-	if(_can_h){

-		FRC_NetworkCommunication_CANSessionMux_closeStreamSession(_can_h);

-		_can_h = 0;

-	}

-}

-void CanTalonSRX::OpenSessionIfNeedBe()

-{

-	_can_stat = 0;

-	if (_can_h == 0) {

-		/* bit30 - bit8 must match $000002XX.  Top bit is not masked to get remote frames */

-		FRC_NetworkCommunication_CANSessionMux_openStreamSession(&_can_h,kParamArbIdValue | GetDeviceNumber(), kParamArbIdMask, kMsgCapacity, &_can_stat);

-		if (_can_stat == 0) {

-			/* success */

-		} else {

-			/* something went wrong, try again later */

-			_can_h = 0;

-		}

-	}

-}

-void CanTalonSRX::ProcessStreamMessages()

-{

-	if(0 == _can_h)

-		OpenSessionIfNeedBe();

-	/* process receive messages */

-	uint32_t i;

-	uint32_t messagesToRead = sizeof(_msgBuff) / sizeof(_msgBuff[0]);

-	uint32_t messagesRead = 0;

-	/* read out latest bunch of messages */

-	_can_stat = 0;

-	if (_can_h){

-		FRC_NetworkCommunication_CANSessionMux_readStreamSession(_can_h,_msgBuff, messagesToRead, &messagesRead, &_can_stat);

-	}

-	/* loop thru each message of interest */

-	for (i = 0; i < messagesRead; ++i) {

-		tCANStreamMessage * msg = _msgBuff + i;

-		if(msg->messageID == (PARAM_RESPONSE | GetDeviceNumber()) ){

-			TALON_Param_Response_t * paramResp = (TALON_Param_Response_t*)msg->data;

-			/* decode value */

-			int32_t val = paramResp->ParamValueH;

-			val <<= 8;

-			val |=  paramResp->ParamValueMH;

-			val <<= 8;

-			val |=  paramResp->ParamValueML;

-			val <<= 8;

-			val |=  paramResp->ParamValueL;

-			/* save latest signal */

-			_sigs[paramResp->ParamEnum] = val;

-		}else{

-			int brkpthere = 42;

-			++brkpthere;

-		}

-	}

-}

-void CanTalonSRX::Set(double value)

-{

-	if(value > 1)

-		value = 1;

-	else if(value < -1)

-		value = -1;

-	SetDemand(1023*value); /* must be within [-1023,1023] */

-}

-/*---------------------setters and getters that use the param request/response-------------*/

-/**

- * Send a one shot frame to set an arbitrary signal.

- * Most signals are in the control frame so avoid using this API unless you have to.

- * Use this api for...

- * -A motor controller profile signal eProfileParam_XXXs.  These are backed up in flash.  If you are gain-scheduling then call this periodically.

- * -Default brake and limit switch signals... eOnBoot_XXXs.  Avoid doing this, use the override signals in the control frame.

- * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms.

- */

-CTR_Code CanTalonSRX::SetParamRaw(unsigned paramEnum, int rawBits)

-{

-	/* caller is using param API.  Open session if it hasn'T been done. */

-	if(0 == _can_h)

-		OpenSessionIfNeedBe();

-	TALON_Param_Response_t frame;

-	memset(&frame,0,sizeof(frame));

-	frame.ParamEnum = paramEnum;

-	frame.ParamValueH = rawBits >> 0x18;

-	frame.ParamValueMH = rawBits >> 0x10;

-	frame.ParamValueML = rawBits >> 0x08;

-	frame.ParamValueL = rawBits;

-	int32_t status = 0;

-	FRC_NetworkCommunication_CANSessionMux_sendMessage(PARAM_SET | GetDeviceNumber(), (const uint8_t*)&frame, 5, 0, &status);

-	if(status)

-		return CTR_TxFailed;

-	return CTR_OKAY;

-}

-/**

- * Checks cached CAN frames and updating solicited signals.

- */

-CTR_Code CanTalonSRX::GetParamResponseRaw(unsigned paramEnum, int & rawBits)

-{

-	CTR_Code retval = CTR_OKAY;

-	/* process received param events. We don't expect many since this API is not used often. */

-	ProcessStreamMessages();

-	/* grab the solicited signal value */

-	sigs_t::iterator i = _sigs.find(paramEnum);

-	if(i == _sigs.end()){

-		retval = CTR_SigNotUpdated;

-	}else{

-		rawBits = i->second;

-	}

-	return retval;

-}

-/**

- * Asks TALON to immedietely respond with signal value.  This API is only used for signals that are not sent periodically.

- * This can be useful for reading params that rarely change like Limit Switch settings and PIDF values.

-  * @param param to request.

- */

-CTR_Code CanTalonSRX::RequestParam(param_t paramEnum)

-{

-	/* process received param events. We don't expect many since this API is not used often. */

-	ProcessStreamMessages();

-	TALON_Param_Request_t frame;

-	memset(&frame,0,sizeof(frame));

-	frame.ParamEnum = paramEnum;

-	int32_t status = 0;

-	FRC_NetworkCommunication_CANSessionMux_sendMessage(PARAM_REQUEST | GetDeviceNumber(), (const uint8_t*)&frame, 1, 0, &status);

-	if(status)

-		return CTR_TxFailed;

-	return CTR_OKAY;

-}

-

-CTR_Code CanTalonSRX::SetParam(param_t paramEnum, double value)

-{

-	int32_t rawbits = 0;

-	switch(paramEnum){

-		case eProfileParamSlot0_P:/* unsigned 10.22 fixed pt value */

-		case eProfileParamSlot0_I:

-		case eProfileParamSlot0_D:

-		case eProfileParamSlot1_P:

-		case eProfileParamSlot1_I:

-		case eProfileParamSlot1_D:

-		{

-			uint32_t urawbits;

-			value = std::min(value,1023.0); /* bounds check doubles that are outside u10.22 */

-			value = std::max(value,0.0);

-			urawbits = value * FLOAT_TO_FXP_10_22; /* perform unsign arithmetic */

-			rawbits = urawbits; /* copy bits over.  SetParamRaw just stuffs into CAN frame with no sense of signedness */

-		}	break;

-		case eProfileParamSlot1_F:	/* signed 10.22 fixed pt value */

-		case eProfileParamSlot0_F:

-			value = std::min(value, 512.0); /* bounds check doubles that are outside s10.22 */

-			value = std::max(value,-512.0);

-			rawbits = value * FLOAT_TO_FXP_10_22;

-			break;

-		case eProfileParamVcompRate: /* unsigned 0.8 fixed pt value volts per ms */

-			/* within [0,1) volts per ms.

-				Slowest ramp is 1/256 VperMilliSec or 3.072 seconds from 0-to-12V.

-				Fastest ramp is 255/256 VperMilliSec or 12.1ms from 0-to-12V.

-				*/

-			if(value <= 0){

-				/* negative or zero (disable), send raw value of zero */

-				rawbits = 0;

-			}else{

-				/* nonzero ramping */

-				rawbits = value * FLOAT_TO_FXP_0_8;

-				/* since whole part is cleared, cap to just under whole unit */

-				if(rawbits > (FLOAT_TO_FXP_0_8-1) )

-					rawbits = (FLOAT_TO_FXP_0_8-1);

-				/* since ramping is nonzero, cap to smallest ramp rate possible */

-				if(rawbits == 0){

-					/* caller is providing a nonzero ramp rate that's too small

-						to serialize, so cap to smallest possible */

-					rawbits = 1;

-				}

-			}

-			break;

-		default: /* everything else is integral */

-			rawbits = (int32_t)value;

-			break;

-	}

-	return SetParamRaw(paramEnum,rawbits);

-}

-CTR_Code CanTalonSRX::GetParamResponse(param_t paramEnum, double & value)

-{

-	int32_t rawbits = 0;

-	CTR_Code retval = GetParamResponseRaw(paramEnum,rawbits);

-	switch(paramEnum){

-		case eProfileParamSlot0_P:/* 10.22 fixed pt value */

-		case eProfileParamSlot0_I:

-		case eProfileParamSlot0_D:

-		case eProfileParamSlot0_F:

-		case eProfileParamSlot1_P:

-		case eProfileParamSlot1_I:

-		case eProfileParamSlot1_D:

-		case eProfileParamSlot1_F:

-		case eCurrent:

-		case eTemp:

-		case eBatteryV:

-			value = ((double)rawbits) * FXP_TO_FLOAT_10_22;

-			break;

-		case eProfileParamVcompRate:

-			value = ((double)rawbits) * FXP_TO_FLOAT_0_8;

-			break;

-		default: /* everything else is integral */

-			value = (double)rawbits;

-			break;

-	}

-	return retval;

-}

-CTR_Code CanTalonSRX::GetParamResponseInt32(param_t paramEnum, int & value)

-{

-	double dvalue = 0;

-	CTR_Code retval = GetParamResponse(paramEnum, dvalue);

-	value = (int32_t)dvalue;

-	return retval;

-}

-/*----- getters and setters that use param request/response. These signals are backed up in flash and will survive a power cycle. ---------*/

-/*----- If your application requires changing these values consider using both slots and switch between slot0 <=> slot1. ------------------*/

-/*----- If your application requires changing these signals frequently then it makes sense to leverage this API. --------------------------*/

-/*----- Getters don't block, so it may require several calls to get the latest value. --------------------------*/

-CTR_Code CanTalonSRX::SetPgain(unsigned slotIdx,double gain)

-{

-	if(slotIdx == 0)

-		return SetParam(eProfileParamSlot0_P, gain);

-	return SetParam(eProfileParamSlot1_P, gain);

-}

-CTR_Code CanTalonSRX::SetIgain(unsigned slotIdx,double gain)

-{

-	if(slotIdx == 0)

-		return SetParam(eProfileParamSlot0_I, gain);

-	return SetParam(eProfileParamSlot1_I, gain);

-}

-CTR_Code CanTalonSRX::SetDgain(unsigned slotIdx,double gain)

-{

-	if(slotIdx == 0)

-		return SetParam(eProfileParamSlot0_D, gain);

-	return SetParam(eProfileParamSlot1_D, gain);

-}

-CTR_Code CanTalonSRX::SetFgain(unsigned slotIdx,double gain)

-{

-	if(slotIdx == 0)

-		return SetParam(eProfileParamSlot0_F, gain);

-	return SetParam(eProfileParamSlot1_F, gain);

-}

-CTR_Code CanTalonSRX::SetIzone(unsigned slotIdx,int zone)

-{

-	if(slotIdx == 0)

-		return SetParam(eProfileParamSlot0_IZone, zone);

-	return SetParam(eProfileParamSlot1_IZone, zone);

-}

-CTR_Code CanTalonSRX::SetCloseLoopRampRate(unsigned slotIdx,int closeLoopRampRate)

-{

-	if(slotIdx == 0)

-		return SetParam(eProfileParamSlot0_CloseLoopRampRate, closeLoopRampRate);

-	return SetParam(eProfileParamSlot1_CloseLoopRampRate, closeLoopRampRate);

-}

-CTR_Code CanTalonSRX::SetVoltageCompensationRate(double voltagePerMs)

-{

-	return SetParam(eProfileParamVcompRate, voltagePerMs);

-}

-CTR_Code CanTalonSRX::GetPgain(unsigned slotIdx,double & gain)

-{

-	if(slotIdx == 0)

-		return GetParamResponse(eProfileParamSlot0_P, gain);

-	return GetParamResponse(eProfileParamSlot1_P, gain);

-}

-CTR_Code CanTalonSRX::GetIgain(unsigned slotIdx,double & gain)

-{

-	if(slotIdx == 0)

-		return GetParamResponse(eProfileParamSlot0_I, gain);

-	return GetParamResponse(eProfileParamSlot1_I, gain);

-}

-CTR_Code CanTalonSRX::GetDgain(unsigned slotIdx,double & gain)

-{

-	if(slotIdx == 0)

-		return GetParamResponse(eProfileParamSlot0_D, gain);

-	return GetParamResponse(eProfileParamSlot1_D, gain);

-}

-CTR_Code CanTalonSRX::GetFgain(unsigned slotIdx,double & gain)

-{

-	if(slotIdx == 0)

-		return GetParamResponse(eProfileParamSlot0_F, gain);

-	return GetParamResponse(eProfileParamSlot1_F, gain);

-}

-CTR_Code CanTalonSRX::GetIzone(unsigned slotIdx,int & zone)

-{

-	if(slotIdx == 0)

-		return GetParamResponseInt32(eProfileParamSlot0_IZone, zone);

-	return GetParamResponseInt32(eProfileParamSlot1_IZone, zone);

-}

-CTR_Code CanTalonSRX::GetCloseLoopRampRate(unsigned slotIdx,int & closeLoopRampRate)

-{

-	if(slotIdx == 0)

-		return GetParamResponseInt32(eProfileParamSlot0_CloseLoopRampRate, closeLoopRampRate);

-	return GetParamResponseInt32(eProfileParamSlot1_CloseLoopRampRate, closeLoopRampRate);

-}

-CTR_Code CanTalonSRX::GetVoltageCompensationRate(double & voltagePerMs)

-{

-	return GetParamResponse(eProfileParamVcompRate, voltagePerMs);

-}

-CTR_Code CanTalonSRX::SetSensorPosition(int pos)

-{

-	return SetParam(eSensorPosition, pos);

-}

-CTR_Code CanTalonSRX::SetForwardSoftLimit(int forwardLimit)

-{

-	return SetParam(eProfileParamSoftLimitForThreshold, forwardLimit);

-}

-CTR_Code CanTalonSRX::SetReverseSoftLimit(int reverseLimit)

-{

-	return SetParam(eProfileParamSoftLimitRevThreshold, reverseLimit);

-}

-CTR_Code CanTalonSRX::SetForwardSoftEnable(int enable)

-{

-	return SetParam(eProfileParamSoftLimitForEnable, enable);

-}

-CTR_Code CanTalonSRX::SetReverseSoftEnable(int enable)

-{

-	return SetParam(eProfileParamSoftLimitRevEnable, enable);

-}

-CTR_Code CanTalonSRX::GetForwardSoftLimit(int & forwardLimit)

-{

-	return GetParamResponseInt32(eProfileParamSoftLimitForThreshold, forwardLimit);

-}

-CTR_Code CanTalonSRX::GetReverseSoftLimit(int & reverseLimit)

-{

-	return GetParamResponseInt32(eProfileParamSoftLimitRevThreshold, reverseLimit);

-}

-CTR_Code CanTalonSRX::GetForwardSoftEnable(int & enable)

-{

-	return GetParamResponseInt32(eProfileParamSoftLimitForEnable, enable);

-}

-CTR_Code CanTalonSRX::GetReverseSoftEnable(int & enable)

-{

-	return GetParamResponseInt32(eProfileParamSoftLimitRevEnable, enable);

-}

-/**

- * Change the periodMs of a TALON's status frame.  See kStatusFrame_* enums for what's available.

- */

-CTR_Code CanTalonSRX::SetStatusFrameRate(unsigned frameEnum, unsigned periodMs)

-{

-	CTR_Code retval = CTR_OKAY;

-	int32_t paramEnum = 0;

-	/* bounds check the period */

-	if(periodMs < 1)

-		periodMs = 1;

-	else if (periodMs > 255)

-		periodMs = 255;

-	uint8_t period = (uint8_t)periodMs;

-	/* lookup the correct param enum based on what frame to rate-change */

-	switch(frameEnum){

-		case kStatusFrame_General:

-			paramEnum = eStatus1FrameRate;

-			break;

-		case kStatusFrame_Feedback:

-			paramEnum = eStatus2FrameRate;

-			break;

-		case kStatusFrame_Encoder:

-			paramEnum = eStatus3FrameRate;

-			break;

-		case kStatusFrame_AnalogTempVbat:

-			paramEnum = eStatus4FrameRate;

-			break;

-		case kStatusFrame_PulseWidthMeas:

-			paramEnum = eStatus8FrameRate;

-			break;

-		default:

-			/* caller's request is not support, return an error code */

-			retval = CTR_InvalidParamValue;

-			break;

-	}

-	/* if lookup was succesful, send set-request out */

-	if(retval == CTR_OKAY){

-		/* paramEnum is updated, sent it out */

-		retval = SetParamRaw(paramEnum, period);

-	}

-	return retval;

-}

-/**

- * Clear all sticky faults in TALON.

- */

-CTR_Code CanTalonSRX::ClearStickyFaults()

-{

-	int32_t status = 0;

-	/* build request frame */

-	TALON_Control_3_ClearFlags_OneShot_t frame;

-	memset(&frame,0,sizeof(frame));

-	frame.ClearStickyFaults = 1;

-	FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_3 | GetDeviceNumber(), (const uint8_t*)&frame, sizeof(frame), 0, &status);

-	if(status)

-		return CTR_TxFailed;

-	return CTR_OKAY;

-}

-/*------------------------ auto generated.  This API is optimal since it uses the fire-and-forget CAN interface ----------------------*/

-/*------------------------ These signals should cover the majority of all use cases. ----------------------------------*/

-CTR_Code CanTalonSRX::GetFault_OverTemp(int &param)

-{

-	GET_STATUS1();

-	param = rx->Fault_OverTemp;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetFault_UnderVoltage(int &param)

-{

-	GET_STATUS1();

-	param = rx->Fault_UnderVoltage;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetFault_ForLim(int &param)

-{

-	GET_STATUS1();

-	param = rx->Fault_ForLim;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetFault_RevLim(int &param)

-{

-	GET_STATUS1();

-	param = rx->Fault_RevLim;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetFault_HardwareFailure(int &param)

-{

-	GET_STATUS1();

-	param = rx->Fault_HardwareFailure;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetFault_ForSoftLim(int &param)

-{

-	GET_STATUS1();

-	param = rx->Fault_ForSoftLim;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetFault_RevSoftLim(int &param)

-{

-	GET_STATUS1();

-	param = rx->Fault_RevSoftLim;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetStckyFault_OverTemp(int &param)

-{

-	GET_STATUS2();

-	param = rx->StckyFault_OverTemp;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetStckyFault_UnderVoltage(int &param)

-{

-	GET_STATUS2();

-	param = rx->StckyFault_UnderVoltage;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetStckyFault_ForLim(int &param)

-{

-	GET_STATUS2();

-	param = rx->StckyFault_ForLim;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetStckyFault_RevLim(int &param)

-{

-	GET_STATUS2();

-	param = rx->StckyFault_RevLim;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetStckyFault_ForSoftLim(int &param)

-{

-	GET_STATUS2();

-	param = rx->StckyFault_ForSoftLim;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetStckyFault_RevSoftLim(int &param)

-{

-	GET_STATUS2();

-	param = rx->StckyFault_RevSoftLim;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetAppliedThrottle(int &param)

-{

-	GET_STATUS1();

-	int32_t raw = 0;

-	raw |= rx->AppliedThrottle_h3;

-	raw <<= 8;

-	raw |= rx->AppliedThrottle_l8;

-	raw <<= (32-11); /* sign extend */

-	raw >>= (32-11); /* sign extend */

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetCloseLoopErr(int &param)

-{

-	GET_STATUS1();

-	int32_t raw = 0;

-	raw |= rx->CloseLoopErrH;

-	raw <<= 8;

-	raw |= rx->CloseLoopErrM;

-	raw <<= 8;

-	raw |= rx->CloseLoopErrL;

-	raw <<= (32-24); /* sign extend */

-	raw >>= (32-24); /* sign extend */

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetFeedbackDeviceSelect(int &param)

-{

-	GET_STATUS1();

-	param = rx->FeedbackDeviceSelect;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetModeSelect(int &param)

-{

-	GET_STATUS1();

-	uint32_t raw = 0;

-	raw |= rx->ModeSelect_h1;

-	raw <<= 3;

-	raw |= rx->ModeSelect_b3;

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetLimitSwitchEn(int &param)

-{

-	GET_STATUS1();

-	param = rx->LimitSwitchEn;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetLimitSwitchClosedFor(int &param)

-{

-	GET_STATUS1();

-	param = rx->LimitSwitchClosedFor;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetLimitSwitchClosedRev(int &param)

-{

-	GET_STATUS1();

-	param = rx->LimitSwitchClosedRev;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetSensorPosition(int &param)

-{

-	GET_STATUS2();

-	int32_t raw = 0;

-	raw |= rx->SensorPositionH;

-	raw <<= 8;

-	raw |= rx->SensorPositionM;

-	raw <<= 8;

-	raw |= rx->SensorPositionL;

-	raw <<= (32-24); /* sign extend */

-	raw >>= (32-24); /* sign extend */

-	if(rx->PosDiv8)

-		raw *= 8;

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetSensorVelocity(int &param)

-{

-	GET_STATUS2();

-	int32_t raw = 0;

-	raw |= rx->SensorVelocityH;

-	raw <<= 8;

-	raw |= rx->SensorVelocityL;

-	raw <<= (32-16); /* sign extend */

-	raw >>= (32-16); /* sign extend */

-	if(rx->VelDiv4)

-		raw *= 4;

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetCurrent(double &param)

-{

-	GET_STATUS2();

-	uint32_t raw = 0;

-	raw |= rx->Current_h8;

-	raw <<= 2;

-	raw |= rx->Current_l2;

-	param = (double)raw * 0.125 + 0;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetBrakeIsEnabled(int &param)

-{

-	GET_STATUS2();

-	param = rx->BrakeIsEnabled;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetEncPosition(int &param)

-{

-	GET_STATUS3();

-	int32_t raw = 0;

-	raw |= rx->EncPositionH;

-	raw <<= 8;

-	raw |= rx->EncPositionM;

-	raw <<= 8;

-	raw |= rx->EncPositionL;

-	raw <<= (32-24); /* sign extend */

-	raw >>= (32-24); /* sign extend */

-	if(rx->PosDiv8)

-		raw *= 8;

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetEncVel(int &param)

-{

-	GET_STATUS3();

-	int32_t raw = 0;

-	raw |= rx->EncVelH;

-	raw <<= 8;

-	raw |= rx->EncVelL;

-	raw <<= (32-16); /* sign extend */

-	raw >>= (32-16); /* sign extend */

-	if(rx->VelDiv4)

-		raw *= 4;

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetEncIndexRiseEvents(int &param)

-{

-	GET_STATUS3();

-	uint32_t raw = 0;

-	raw |= rx->EncIndexRiseEventsH;

-	raw <<= 8;

-	raw |= rx->EncIndexRiseEventsL;

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetQuadApin(int &param)

-{

-	GET_STATUS3();

-	param = rx->QuadApin;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetQuadBpin(int &param)

-{

-	GET_STATUS3();

-	param = rx->QuadBpin;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetQuadIdxpin(int &param)

-{

-	GET_STATUS3();

-	param = rx->QuadIdxpin;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetAnalogInWithOv(int &param)

-{

-	GET_STATUS4();

-	int32_t raw = 0;

-	raw |= rx->AnalogInWithOvH;

-	raw <<= 8;

-	raw |= rx->AnalogInWithOvM;

-	raw <<= 8;

-	raw |= rx->AnalogInWithOvL;

-	raw <<= (32-24); /* sign extend */

-	raw >>= (32-24); /* sign extend */

-	if(rx->PosDiv8)

-		raw *= 8;

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetAnalogInVel(int &param)

-{

-	GET_STATUS4();

-	int32_t raw = 0;

-	raw |= rx->AnalogInVelH;

-	raw <<= 8;

-	raw |= rx->AnalogInVelL;

-	raw <<= (32-16); /* sign extend */

-	raw >>= (32-16); /* sign extend */

-	if(rx->VelDiv4)

-		raw *= 4;

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetTemp(double &param)

-{

-	GET_STATUS4();

-	uint32_t raw = rx->Temp;

-	param = (double)raw * 0.6451612903 + -50;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetBatteryV(double &param)

-{

-	GET_STATUS4();

-	uint32_t raw = rx->BatteryV;

-	param = (double)raw * 0.05 + 4;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetResetCount(int &param)

-{

-	GET_STATUS5();

-	uint32_t raw = 0;

-	raw |= rx->ResetCountH;

-	raw <<= 8;

-	raw |= rx->ResetCountL;

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetResetFlags(int &param)

-{

-	GET_STATUS5();

-	uint32_t raw = 0;

-	raw |= rx->ResetFlagsH;

-	raw <<= 8;

-	raw |= rx->ResetFlagsL;

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetFirmVers(int &param)

-{

-	GET_STATUS5();

-	uint32_t raw = 0;

-	raw |= rx->FirmVersH;

-	raw <<= 8;

-	raw |= rx->FirmVersL;

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::SetDemand(int param)

-{

-	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

-	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

-	toFill->DemandH = param>>16;

-	toFill->DemandM = param>>8;

-	toFill->DemandL = param>>0;

-	FlushTx(toFill);

-	return CTR_OKAY;

-}

-CTR_Code CanTalonSRX::SetOverrideLimitSwitchEn(int param)

-{

-	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

-	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

-	toFill->OverrideLimitSwitchEn = param;

-	FlushTx(toFill);

-	return CTR_OKAY;

-}

-CTR_Code CanTalonSRX::SetFeedbackDeviceSelect(int param)

-{

-	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

-	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

-	toFill->FeedbackDeviceSelect = param;

-	FlushTx(toFill);

-	return CTR_OKAY;

-}

-CTR_Code CanTalonSRX::SetRevMotDuringCloseLoopEn(int param)

-{

-	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

-	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

-	toFill->RevMotDuringCloseLoopEn = param;

-	FlushTx(toFill);

-	return CTR_OKAY;

-}

-CTR_Code CanTalonSRX::SetOverrideBrakeType(int param)

-{

-	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

-	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

-	toFill->OverrideBrakeType = param;

-	FlushTx(toFill);

-	return CTR_OKAY;

-}

-CTR_Code CanTalonSRX::SetModeSelect(int param)

-{

-	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

-	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

-	toFill->ModeSelect = param;

-	FlushTx(toFill);

-	return CTR_OKAY;

-}

-/**

- * @param modeSelect selects which mode.

- * @param demand setpt or throttle or masterId to follow.

- * @return error code, 0 iff successful.

- * This function has the advantage of atomically setting mode and demand.

- */

-CTR_Code CanTalonSRX::SetModeSelect(int modeSelect,int demand)

-{

-	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

-	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

-	toFill->ModeSelect = modeSelect;

-	toFill->DemandH = demand>>16;

-	toFill->DemandM = demand>>8;

-	toFill->DemandL = demand>>0;

-	FlushTx(toFill);

-	return CTR_OKAY;

-}

-CTR_Code CanTalonSRX::SetProfileSlotSelect(int param)

-{

-	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

-	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

-	toFill->ProfileSlotSelect = param;

-	FlushTx(toFill);

-	return CTR_OKAY;

-}

-CTR_Code CanTalonSRX::SetRampThrottle(int param)

-{

-	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

-	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

-	toFill->RampThrottle = param;

-	FlushTx(toFill);

-	return CTR_OKAY;

-}

-CTR_Code CanTalonSRX::SetRevFeedbackSensor(int param)

-{

-	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

-	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

-	toFill->RevFeedbackSensor = param ? 1 : 0;

-	FlushTx(toFill);

-	return CTR_OKAY;

-}

-CTR_Code CanTalonSRX::GetPulseWidthPosition(int &param)

-{

-	GET_STATUS8();

-	int32_t raw = 0;

-	raw |= rx->PulseWidPositionH;

-	raw <<= 8;

-	raw |= rx->PulseWidPositionM;

-	raw <<= 8;

-	raw |= rx->PulseWidPositionL;

-	raw <<= (32-24); /* sign extend */

-	raw >>= (32-24); /* sign extend */

-	if(rx->PosDiv8)

-		raw *= 8;

-	param = (int)raw;

-	return rx.err;

-}

-CTR_Code CanTalonSRX::GetPulseWidthVelocity(int &param)

-{

-	GET_STATUS8();

-	int32_t raw = 0;

-	raw |= rx->PulseWidVelH;

-	raw <<= 8;

-	raw |= rx->PulseWidVelL;

-	raw <<= (32-16); /* sign extend */

-	raw >>= (32-16); /* sign extend */

-	if(rx->VelDiv4)

-		raw *= 4;

-	param = (int)raw;

-	return rx.err;

-}

-/**

- * @param param [out]	Rise to rise timeperiod in microseconds.

- */

-CTR_Code CanTalonSRX::GetPulseWidthRiseToRiseUs(int &param)

-{

-	GET_STATUS8();

-	uint32_t raw = 0;

-	raw |= rx->PeriodUsM8;

-	raw <<= 8;

-	raw |= rx->PeriodUsL8;

-	param = (int)raw;

-	return rx.err;

-}

-/**

- * @param param [out]	Rise to fall time period in microseconds.

- */

-CTR_Code CanTalonSRX::GetPulseWidthRiseToFallUs(int &param)

-{

-	int temp = 0;

-	int periodUs = 0;

-	/* first grab our 12.12 position */

-	CTR_Code retval1 = GetPulseWidthPosition(temp);

-	/* mask off number of turns */

-	temp &= 0xFFF;

-	/* next grab the waveform period. This value

-	 * will be zero if we stop getting pulses **/

-	CTR_Code retval2 = GetPulseWidthRiseToRiseUs(periodUs);

-	/* now we have 0.12 position that is scaled to the waveform period.

-		Use fixed pt multiply to scale our 0.16 period into us.*/

-	param = (temp * periodUs) / BIT12;

-	/* pass the worst error code to caller.

-		Assume largest value is the most pressing error code.*/

-	return (CTR_Code)std::max((int)retval1, (int)retval2);

-}

-CTR_Code CanTalonSRX::IsPulseWidthSensorPresent(int &param)

-{

-	int periodUs = 0;

-	CTR_Code retval = GetPulseWidthRiseToRiseUs(periodUs);

-	/* if a nonzero period is present, we are getting good pules.

-		Otherwise the sensor is not present. */

-	if(periodUs != 0)

-		param = 1;

-	else

-		param = 0;

-	return retval;

-}

-//------------------ C interface --------------------------------------------//

-extern "C" {

-void *c_TalonSRX_Create(int deviceNumber, int controlPeriodMs)

-{

-	return new CanTalonSRX(deviceNumber, controlPeriodMs);

-}

-void c_TalonSRX_Destroy(void *handle)

-{

-	delete (CanTalonSRX*)handle;

-}

-CTR_Code c_TalonSRX_SetParam(void *handle, int paramEnum, double value)

-{

-	return ((CanTalonSRX*)handle)->SetParam((CanTalonSRX::param_t)paramEnum, value);

-}

-CTR_Code c_TalonSRX_RequestParam(void *handle, int paramEnum)

-{

-	return ((CanTalonSRX*)handle)->RequestParam((CanTalonSRX::param_t)paramEnum);

-}

-CTR_Code c_TalonSRX_GetParamResponse(void *handle, int paramEnum, double *value)

-{

-	return ((CanTalonSRX*)handle)->GetParamResponse((CanTalonSRX::param_t)paramEnum, *value);

-}

-CTR_Code c_TalonSRX_GetParamResponseInt32(void *handle, int paramEnum, int *value)

-{

-	return ((CanTalonSRX*)handle)->GetParamResponseInt32((CanTalonSRX::param_t)paramEnum, *value);

-}

-CTR_Code c_TalonSRX_SetStatusFrameRate(void *handle, unsigned frameEnum, unsigned periodMs)

-{

-	return ((CanTalonSRX*)handle)->SetStatusFrameRate(frameEnum, periodMs);

-}

-CTR_Code c_TalonSRX_ClearStickyFaults(void *handle)

-{

-	return ((CanTalonSRX*)handle)->ClearStickyFaults();

-}

-CTR_Code c_TalonSRX_GetFault_OverTemp(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetFault_OverTemp(*param);

-}

-CTR_Code c_TalonSRX_GetFault_UnderVoltage(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetFault_UnderVoltage(*param);

-}

-CTR_Code c_TalonSRX_GetFault_ForLim(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetFault_ForLim(*param);

-}

-CTR_Code c_TalonSRX_GetFault_RevLim(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetFault_RevLim(*param);

-}

-CTR_Code c_TalonSRX_GetFault_HardwareFailure(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetFault_HardwareFailure(*param);

-}

-CTR_Code c_TalonSRX_GetFault_ForSoftLim(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetFault_ForSoftLim(*param);

-}

-CTR_Code c_TalonSRX_GetFault_RevSoftLim(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetFault_RevSoftLim(*param);

-}

-CTR_Code c_TalonSRX_GetStckyFault_OverTemp(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetStckyFault_OverTemp(*param);

-}

-CTR_Code c_TalonSRX_GetStckyFault_UnderVoltage(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetStckyFault_UnderVoltage(*param);

-}

-CTR_Code c_TalonSRX_GetStckyFault_ForLim(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetStckyFault_ForLim(*param);

-}

-CTR_Code c_TalonSRX_GetStckyFault_RevLim(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetStckyFault_RevLim(*param);

-}

-CTR_Code c_TalonSRX_GetStckyFault_ForSoftLim(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetStckyFault_ForSoftLim(*param);

-}

-CTR_Code c_TalonSRX_GetStckyFault_RevSoftLim(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetStckyFault_RevSoftLim(*param);

-}

-CTR_Code c_TalonSRX_GetAppliedThrottle(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetAppliedThrottle(*param);

-}

-CTR_Code c_TalonSRX_GetCloseLoopErr(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetCloseLoopErr(*param);

-}

-CTR_Code c_TalonSRX_GetFeedbackDeviceSelect(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetFeedbackDeviceSelect(*param);

-}

-CTR_Code c_TalonSRX_GetModeSelect(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetModeSelect(*param);

-}

-CTR_Code c_TalonSRX_GetLimitSwitchEn(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetLimitSwitchEn(*param);

-}

-CTR_Code c_TalonSRX_GetLimitSwitchClosedFor(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetLimitSwitchClosedFor(*param);

-}

-CTR_Code c_TalonSRX_GetLimitSwitchClosedRev(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetLimitSwitchClosedRev(*param);

-}

-CTR_Code c_TalonSRX_GetSensorPosition(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetSensorPosition(*param);

-}

-CTR_Code c_TalonSRX_GetSensorVelocity(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetSensorVelocity(*param);

-}

-CTR_Code c_TalonSRX_GetCurrent(void *handle, double *param)

-{

-	return ((CanTalonSRX*)handle)->GetCurrent(*param);

-}

-CTR_Code c_TalonSRX_GetBrakeIsEnabled(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetBrakeIsEnabled(*param);

-}

-CTR_Code c_TalonSRX_GetEncPosition(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetEncPosition(*param);

-}

-CTR_Code c_TalonSRX_GetEncVel(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetEncVel(*param);

-}

-CTR_Code c_TalonSRX_GetEncIndexRiseEvents(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetEncIndexRiseEvents(*param);

-}

-CTR_Code c_TalonSRX_GetQuadApin(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetQuadApin(*param);

-}

-CTR_Code c_TalonSRX_GetQuadBpin(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetQuadBpin(*param);

-}

-CTR_Code c_TalonSRX_GetQuadIdxpin(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetQuadIdxpin(*param);

-}

-CTR_Code c_TalonSRX_GetAnalogInWithOv(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetAnalogInWithOv(*param);

-}

-CTR_Code c_TalonSRX_GetAnalogInVel(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetAnalogInVel(*param);

-}

-CTR_Code c_TalonSRX_GetTemp(void *handle, double *param)

-{

-	return ((CanTalonSRX*)handle)->GetTemp(*param);

-}

-CTR_Code c_TalonSRX_GetBatteryV(void *handle, double *param)

-{

-	return ((CanTalonSRX*)handle)->GetBatteryV(*param);

-}

-CTR_Code c_TalonSRX_GetResetCount(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetResetCount(*param);

-}

-CTR_Code c_TalonSRX_GetResetFlags(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetResetFlags(*param);

-}

-CTR_Code c_TalonSRX_GetFirmVers(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetFirmVers(*param);

-}

-CTR_Code c_TalonSRX_SetDemand(void *handle, int param)

-{

-	return ((CanTalonSRX*)handle)->SetDemand(param);

-}

-CTR_Code c_TalonSRX_SetOverrideLimitSwitchEn(void *handle, int param)

-{

-	return ((CanTalonSRX*)handle)->SetOverrideLimitSwitchEn(param);

-}

-CTR_Code c_TalonSRX_SetFeedbackDeviceSelect(void *handle, int param)

-{

-	return ((CanTalonSRX*)handle)->SetFeedbackDeviceSelect(param);

-}

-CTR_Code c_TalonSRX_SetRevMotDuringCloseLoopEn(void *handle, int param)

-{

-	return ((CanTalonSRX*)handle)->SetRevMotDuringCloseLoopEn(param);

-}

-CTR_Code c_TalonSRX_SetOverrideBrakeType(void *handle, int param)

-{

-	return ((CanTalonSRX*)handle)->SetOverrideBrakeType(param);

-}

-CTR_Code c_TalonSRX_SetModeSelect(void *handle, int param)

-{

-	return ((CanTalonSRX*)handle)->SetModeSelect(param);

-}

-CTR_Code c_TalonSRX_SetModeSelect2(void *handle, int modeSelect, int demand)

-{

-	return ((CanTalonSRX*)handle)->SetModeSelect(modeSelect, demand);

-}

-CTR_Code c_TalonSRX_SetProfileSlotSelect(void *handle, int param)

-{

-	return ((CanTalonSRX*)handle)->SetProfileSlotSelect(param);

-}

-CTR_Code c_TalonSRX_SetRampThrottle(void *handle, int param)

-{

-	return ((CanTalonSRX*)handle)->SetRampThrottle(param);

-}

-CTR_Code c_TalonSRX_SetRevFeedbackSensor(void *handle, int param)

-{

-	return ((CanTalonSRX*)handle)->SetRevFeedbackSensor(param);

-}

-CTR_Code c_TalonSRX_GetPulseWidthPosition(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetPulseWidthPosition(*param);

-}

-CTR_Code c_TalonSRX_GetPulseWidthVelocity(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetPulseWidthVelocity(*param);

-}

-CTR_Code c_TalonSRX_GetPulseWidthRiseToFallUs(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetPulseWidthRiseToFallUs(*param);

-}

-CTR_Code c_TalonSRX_GetPulseWidthRiseToRiseUs(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->GetPulseWidthRiseToRiseUs(*param);

-}

-CTR_Code c_TalonSRX_IsPulseWidthSensorPresent(void *handle, int *param)

-{

-	return ((CanTalonSRX*)handle)->IsPulseWidthSensorPresent(*param);

-}

-}

+/**
+ * @brief CAN TALON SRX driver.
+ *
+ * The TALON SRX is designed to instrument all runtime signals periodically.
+ * The default periods are chosen to support 16 TALONs with 10ms update rate
+ * for control (throttle or setpoint).  However these can be overridden with
+ * SetStatusFrameRate. @see SetStatusFrameRate
+ * The getters for these unsolicited signals are auto generated at the bottom
+ * of this module.
+ *
+ * Likewise most control signals are sent periodically using the fire-and-forget
+ * CAN API.  The setters for these unsolicited signals are auto generated at the
+ * bottom of this module.
+ *
+ * Signals that are not available in an unsolicited fashion are the Close Loop
+ * gains.  For teams that have a single profile for their TALON close loop they
+ * can use either the webpage to configure their TALONs once or set the PIDF,
+ * Izone, CloseLoopRampRate, etc... once in the robot application.  These
+ * parameters are saved to flash so once they are loaded in the TALON, they
+ * will persist through power cycles and mode changes.
+ *
+ * For teams that have one or two profiles to switch between, they can use the
+ * same strategy since there are two slots to choose from and the
+ * ProfileSlotSelect is periodically sent in the 10 ms control frame.
+ *
+ * For teams that require changing gains frequently, they can use the soliciting
+ * API to get and set those parameters.  Most likely they will only need to set
+ * them in a periodic fashion as a function of what motion the application is
+ * attempting.  If this API is used, be mindful of the CAN utilization reported
+ * in the driver station.
+ *
+ * If calling application has used the config routines to configure the
+ * selected feedback sensor, then all positions are measured in floating point
+ * precision rotations.  All sensor velocities are specified in floating point
+ * precision RPM.
+ * @see ConfigPotentiometerTurns
+ * @see ConfigEncoderCodesPerRev
+ * HOWEVER, if calling application has not called the config routine for
+ * selected feedback sensor, then all getters/setters for position/velocity use
+ * the native engineering units of the Talon SRX firm (just like in 2015).
+ * Signals explained below.
+ *
+ * Encoder position is measured in encoder edges.  Every edge is counted
+ * (similar to roboRIO 4X mode).  Analog position is 10 bits, meaning 1024
+ * ticks per rotation (0V => 3.3V).  Use SetFeedbackDeviceSelect to select
+ * which sensor type you need.  Once you do that you can use GetSensorPosition()
+ * and GetSensorVelocity().  These signals are updated on CANBus every 20ms (by
+ * default).  If a relative sensor is selected, you can zero (or change the
+ * current value) using SetSensorPosition.
+ *
+ * Analog Input and quadrature position (and velocity) are also explicitly
+ * reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel.
+ * These signals are available all the time, regardless of what sensor is
+ * selected at a rate of 100ms.  This allows easy instrumentation for "in the
+ * pits" checking of all sensors regardless of modeselect.  The 100ms rate is
+ * overridable for teams who want to acquire sensor data for processing, not
+ * just instrumentation.  Or just select the sensor using
+ * SetFeedbackDeviceSelect to get it at 20ms.
+ *
+ * Velocity is in position ticks / 100ms.
+ *
+ * All output units are in respect to duty cycle (throttle) which is -1023(full
+ * reverse) to +1023 (full forward).  This includes demand (which specifies
+ * duty cycle when in duty cycle mode) and rampRamp, which is in throttle units
+ * per 10ms (if nonzero).
+ *
+ * Pos and velocity close loops are calc'd as
+ *   err = target - posOrVel.
+ *   iErr += err;
+ *   if(   (IZone!=0)  and  abs(err) > IZone)
+ *       ClearIaccum()
+ *   output = P X err + I X iErr + D X dErr + F X target
+ *   dErr = err - lastErr
+ * P, I, and D gains are always positive. F can be negative.
+ * Motor direction can be reversed using SetRevMotDuringCloseLoopEn if
+ * sensor and motor are out of phase. Similarly feedback sensor can also be
+ * reversed (multiplied by -1) if you prefer the sensor to be inverted.
+ *
+ * P gain is specified in throttle per error tick.  For example, a value of 102
+ * is ~9.9% (which is 102/1023) throttle per 1 ADC unit(10bit) or 1 quadrature
+ * encoder edge depending on selected sensor.
+ *
+ * I gain is specified in throttle per integrated error. For example, a value
+ * of 10 equates to ~0.99% (which is 10/1023) for each accumulated ADC unit
+ * (10 bit) or 1 quadrature encoder edge depending on selected sensor.
+ * Close loop and integral accumulator runs every 1ms.
+ *
+ * D gain is specified in throttle per derivative error. For example a value of
+ * 102 equates to ~9.9% (which is 102/1023) per change of 1 unit (ADC or
+ * encoder) per ms.
+ *
+ * I Zone is specified in the same units as sensor position (ADC units or
+ * quadrature edges).  If pos/vel error is outside of this value, the
+ * integrated error will auto-clear...
+ *   if(   (IZone!=0)  and  abs(err) > IZone)
+ *       ClearIaccum()
+ * ...this is very useful in preventing integral windup and is highly
+ * recommended if using full PID to keep stability low.
+ *
+ * CloseLoopRampRate is in throttle units per 1ms.  Set to zero to disable
+ * ramping.  Works the same as RampThrottle but only is in effect when a close
+ * loop mode and profile slot is selected.
+ *
+ * auto generated using spreadsheet and wpiclassgen.py
+ * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967
+ */
+#include "HAL/CanTalonSRX.h"
+#include "FRC_NetworkCommunication/CANSessionMux.h"  //CAN Comm
+#include <string.h>                                  // memset
+#include <unistd.h>                                  // usleep
+
+#define STATUS_1 0x02041400
+#define STATUS_2 0x02041440
+#define STATUS_3 0x02041480
+#define STATUS_4 0x020414C0
+#define STATUS_5 0x02041500
+#define STATUS_6 0x02041540
+#define STATUS_7 0x02041580
+#define STATUS_8 0x020415C0
+#define STATUS_9 0x02041600
+
+#define CONTROL_1 0x02040000
+#define CONTROL_2 0x02040040
+#define CONTROL_3 0x02040080
+#define CONTROL_5 0x02040100
+#define CONTROL_6 0x02040140
+
+#define EXPECTED_RESPONSE_TIMEOUT_MS (200)
+#define GET_STATUS1()                                                    \
+  CtreCanNode::recMsg<TALON_Status_1_General_10ms_t> rx =                \
+      GetRx<TALON_Status_1_General_10ms_t>(STATUS_1 | GetDeviceNumber(), \
+                                           EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS2()                                                     \
+  CtreCanNode::recMsg<TALON_Status_2_Feedback_20ms_t> rx =                \
+      GetRx<TALON_Status_2_Feedback_20ms_t>(STATUS_2 | GetDeviceNumber(), \
+                                            EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS3()                                                 \
+  CtreCanNode::recMsg<TALON_Status_3_Enc_100ms_t> rx =                \
+      GetRx<TALON_Status_3_Enc_100ms_t>(STATUS_3 | GetDeviceNumber(), \
+                                        EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS4()                                                         \
+  CtreCanNode::recMsg<TALON_Status_4_AinTempVbat_100ms_t> rx =                \
+      GetRx<TALON_Status_4_AinTempVbat_100ms_t>(STATUS_4 | GetDeviceNumber(), \
+                                                EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS5()                                                       \
+  CtreCanNode::recMsg<TALON_Status_5_Startup_OneShot_t> rx =                \
+      GetRx<TALON_Status_5_Startup_OneShot_t>(STATUS_5 | GetDeviceNumber(), \
+                                              EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS6()                                                         \
+  CtreCanNode::recMsg<TALON_Status_6_Eol_t> rx = GetRx<TALON_Status_6_Eol_t>( \
+      STATUS_6 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS7()                                                   \
+  CtreCanNode::recMsg<TALON_Status_7_Debug_200ms_t> rx =                \
+      GetRx<TALON_Status_7_Debug_200ms_t>(STATUS_7 | GetDeviceNumber(), \
+                                          EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS8()                                                      \
+  CtreCanNode::recMsg<TALON_Status_8_PulseWid_100ms_t> rx =                \
+      GetRx<TALON_Status_8_PulseWid_100ms_t>(STATUS_8 | GetDeviceNumber(), \
+                                             EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS9()                                            \
+  CtreCanNode::recMsg<TALON_Status_9_MotProfBuffer_100ms_t> rx = \
+      GetRx<TALON_Status_9_MotProfBuffer_100ms_t>(               \
+          STATUS_9 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
+
+#define PARAM_REQUEST 0x02041800
+#define PARAM_RESPONSE 0x02041840
+#define PARAM_SET 0x02041880
+
+const int kParamArbIdValue = PARAM_RESPONSE;
+const int kParamArbIdMask = 0xFFFFFFFF;
+
+const double FLOAT_TO_FXP_10_22 = (double)0x400000;
+const double FXP_TO_FLOAT_10_22 = 0.0000002384185791015625;
+
+const double FLOAT_TO_FXP_0_8 = (double)0x100;
+const double FXP_TO_FLOAT_0_8 = 0.00390625;
+
+CanTalonSRX::CanTalonSRX(int deviceNumber, int controlPeriodMs,
+                         int enablePeriodMs)
+    : CtreCanNode(deviceNumber), _can_h(0), _can_stat(0) {
+  _controlPeriodMs = controlPeriodMs;
+  _enablePeriodMs = enablePeriodMs;
+
+  /* bound period to be within [1 ms,95 ms] */
+  if (_controlPeriodMs < 1)
+    _controlPeriodMs = 1;
+  else if (_controlPeriodMs > 95)
+    _controlPeriodMs = 95;
+  if (_enablePeriodMs < 1)
+    _enablePeriodMs = 1;
+  else if (_enablePeriodMs > 95)
+    _enablePeriodMs = 95;
+
+  RegisterRx(STATUS_1 | (UINT8)deviceNumber);
+  RegisterRx(STATUS_2 | (UINT8)deviceNumber);
+  RegisterRx(STATUS_3 | (UINT8)deviceNumber);
+  RegisterRx(STATUS_4 | (UINT8)deviceNumber);
+  RegisterRx(STATUS_5 | (UINT8)deviceNumber);
+  RegisterRx(STATUS_6 | (UINT8)deviceNumber);
+  RegisterRx(STATUS_7 | (UINT8)deviceNumber);
+  /* use the legacy command frame until we have evidence we can use the new
+   * frame.
+   */
+  RegisterTx(CONTROL_1 | (UINT8)deviceNumber, (UINT8)_controlPeriodMs);
+  _controlFrameArbId = CONTROL_1;
+  /* the only default param that is nonzero is limit switch.
+   * Default to using the flash settings.
+   */
+  SetOverrideLimitSwitchEn(kLimitSwitchOverride_UseDefaultsFromFlash);
+  /* Check if we can upgrade the control framing */
+  UpdateControlId();
+}
+/* CanTalonSRX D'tor
+ */
+CanTalonSRX::~CanTalonSRX() {
+  if (m_hasBeenMoved) {
+    /* Another CANTalonSRX still exists, so don't un-register the periodic
+     * control frame
+     */
+  } else {
+    /* un-register the control frame so Talon is disabled */
+    RegisterTx(CONTROL_1 | (UINT8)GetDeviceNumber(), 0);
+    RegisterTx(CONTROL_5 | (UINT8)GetDeviceNumber(), 0);
+  }
+  /* free the stream we used for SetParam/GetParamResponse */
+  if (_can_h) {
+    FRC_NetworkCommunication_CANSessionMux_closeStreamSession(_can_h);
+    _can_h = 0;
+  }
+}
+/**
+ * @return true if Talon is reporting that it supports control5, and therefore
+ *         RIO can send control5 to update control params (even when disabled).
+ */
+bool CanTalonSRX::IsControl5Supported() {
+  /* only bother to poll status2 if we are looking for cmd5allowed */
+  GET_STATUS2();
+  if (rx.err != CTR_OKAY) {
+    /* haven't received it */
+    return false;
+  } else if (0 == rx->Cmd5Allowed) {
+    /* firmware doesn't support it */
+    return false;
+  }
+  /* we can use control5, this gives application the ability to set control
+   * params prior to Talon-enable */
+  return true;
+}
+/**
+ * Get a copy of the control frame to send.
+ * @param [out] pointer to eight byte array to fill.
+ */
+void CanTalonSRX::GetControlFrameCopy(uint8_t *toFill) {
+  /* get the copy of the control frame in control1 */
+  CtreCanNode::txTask<TALON_Control_1_General_10ms_t> task =
+      GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId |
+                                            GetDeviceNumber());
+  /* control1's payload will move to 5, but update the new sigs in control5 */
+  if (task.IsEmpty())
+    memset(toFill, 0, 8);
+  else
+    memcpy(toFill, task.toSend, 8);
+  /* zero first two bytes - these are reserved. */
+  toFill[0] = 0;
+  toFill[1] = 0;
+}
+/**
+ * Called in various places to double check we are using the best control frame.
+ * If the Talon firmware is too old, use control 1 framing, which does not allow
+ * setting
+ * control signals until robot is enabled.  If Talon firmware can suport
+ * control5, use that
+ * since that frame can be transmitted during robot-disable.  If calling
+ * application
+ * uses setParam to set the signal eLegacyControlMode, caller can force using
+ * control1
+ * if needed for some reason.
+ */
+void CanTalonSRX::UpdateControlId() {
+  uint8_t work[8];
+  uint32_t frameToUse;
+  /* deduce if we should change IDs.  If firm supports the new frame, and
+   * calling app isn't forcing legacy mode
+   * use control5.*/
+  if (_useControl5ifSupported && IsControl5Supported()) {
+    frameToUse = CONTROL_5;
+  } else {
+    frameToUse = CONTROL_1;
+  }
+  /* is there anything to do */
+  if (frameToUse == _controlFrameArbId) {
+    /* nothing to do, we are using the best frame. */
+  } else if (frameToUse == CONTROL_5) {
+    /* get a copy of the control frame */
+    GetControlFrameCopy(work);
+    /* Change control1's DLC to 2.  Passing nullptr means all payload bytes are
+     * zero. */
+    RegisterTx(CONTROL_1 | GetDeviceNumber(), _enablePeriodMs, 2, nullptr);
+    /* reregister the control frame using the new ID */
+    RegisterTx(frameToUse | GetDeviceNumber(), _controlPeriodMs, 8, work);
+    /* save the correct frame ArbID */
+    _controlFrameArbId = frameToUse;
+  } else if (frameToUse == CONTROL_1) {
+    GetControlFrameCopy(work);
+    /* stop sending control 5 */
+    UnregisterTx(CONTROL_5 | GetDeviceNumber());
+    /* reregister the control frame using the new ID */
+    RegisterTx(frameToUse | GetDeviceNumber(), _controlPeriodMs, 8, work);
+    /* save the correct frame ArbID */
+    _controlFrameArbId = frameToUse;
+  }
+}
+void CanTalonSRX::OpenSessionIfNeedBe() {
+  _can_stat = 0;
+  if (_can_h == 0) {
+    /* bit30 - bit8 must match $000002XX.  Top bit is not masked to get remote
+     * frames */
+    FRC_NetworkCommunication_CANSessionMux_openStreamSession(
+        &_can_h, kParamArbIdValue | GetDeviceNumber(), kParamArbIdMask,
+        kMsgCapacity, &_can_stat);
+    if (_can_stat == 0) {
+      /* success */
+    } else {
+      /* something went wrong, try again later */
+      _can_h = 0;
+    }
+  }
+}
+void CanTalonSRX::ProcessStreamMessages() {
+  if (0 == _can_h) OpenSessionIfNeedBe();
+  /* process receive messages */
+  uint32_t i;
+  uint32_t messagesToRead = sizeof(_msgBuff) / sizeof(_msgBuff[0]);
+  uint32_t messagesRead = 0;
+  /* read out latest bunch of messages */
+  _can_stat = 0;
+  if (_can_h) {
+    FRC_NetworkCommunication_CANSessionMux_readStreamSession(
+        _can_h, _msgBuff, messagesToRead, &messagesRead, &_can_stat);
+  }
+  /* loop thru each message of interest */
+  for (i = 0; i < messagesRead; ++i) {
+    tCANStreamMessage *msg = _msgBuff + i;
+    if (msg->messageID == (PARAM_RESPONSE | GetDeviceNumber())) {
+      TALON_Param_Response_t *paramResp = (TALON_Param_Response_t *)msg->data;
+      /* decode value */
+      int32_t val = paramResp->ParamValueH;
+      val <<= 8;
+      val |= paramResp->ParamValueMH;
+      val <<= 8;
+      val |= paramResp->ParamValueML;
+      val <<= 8;
+      val |= paramResp->ParamValueL;
+      /* save latest signal */
+      _sigs[paramResp->ParamEnum] = val;
+    } else {
+      int brkpthere = 42;
+      ++brkpthere;
+    }
+  }
+}
+void CanTalonSRX::Set(double value) {
+  if (value > 1)
+    value = 1;
+  else if (value < -1)
+    value = -1;
+  SetDemand(1023 * value); /* must be within [-1023,1023] */
+}
+/*---------------------setters and getters that use the param
+ * request/response-------------*/
+/**
+ * Send a one shot frame to set an arbitrary signal.
+ * Most signals are in the control frame so avoid using this API unless you have
+ * to.
+ * Use this api for...
+ * -A motor controller profile signal eProfileParam_XXXs.  These are backed up
+ * in flash.  If you are gain-scheduling then call this periodically.
+ * -Default brake and limit switch signals... eOnBoot_XXXs.  Avoid doing this,
+ * use the override signals in the control frame.
+ * Talon will automatically send a PARAM_RESPONSE after the set, so
+ * GetParamResponse will catch the latest value after a couple ms.
+ */
+CTR_Code CanTalonSRX::SetParamRaw(unsigned paramEnum, int rawBits) {
+  /* caller is using param API.  Open session if it hasn'T been done. */
+  if (0 == _can_h) OpenSessionIfNeedBe();
+  TALON_Param_Response_t frame;
+  memset(&frame, 0, sizeof(frame));
+  frame.ParamEnum = paramEnum;
+  frame.ParamValueH = rawBits >> 0x18;
+  frame.ParamValueMH = rawBits >> 0x10;
+  frame.ParamValueML = rawBits >> 0x08;
+  frame.ParamValueL = rawBits;
+  int32_t status = 0;
+  FRC_NetworkCommunication_CANSessionMux_sendMessage(
+      PARAM_SET | GetDeviceNumber(), (const uint8_t *)&frame, 5, 0, &status);
+  /* small hook here if we want the API itself to react to set commands */
+  switch (paramEnum) {
+    case eLegacyControlMode:
+      if (rawBits != 0) {
+        /* caller wants to force legacy framing */
+        _useControl5ifSupported = false;
+      } else {
+        /* caller wants to let the API decide */
+        _useControl5ifSupported = true;
+      }
+      /* recheck IDs now that flag has changed */
+      UpdateControlId();
+      break;
+  }
+  /* for now have a general failure if we can't transmit */
+  if (status) return CTR_TxFailed;
+  return CTR_OKAY;
+}
+/**
+ * Checks cached CAN frames and updating solicited signals.
+ */
+CTR_Code CanTalonSRX::GetParamResponseRaw(unsigned paramEnum, int &rawBits) {
+  CTR_Code retval = CTR_OKAY;
+  /* process received param events. We don't expect many since this API is not
+   * used often. */
+  ProcessStreamMessages();
+  /* grab the solicited signal value */
+  sigs_t::iterator i = _sigs.find(paramEnum);
+  if (i == _sigs.end()) {
+    retval = CTR_SigNotUpdated;
+  } else {
+    rawBits = i->second;
+  }
+  return retval;
+}
+/**
+ * Asks TALON to immedietely respond with signal value.  This API is only used
+ * for signals that are not sent periodically.
+ * This can be useful for reading params that rarely change like Limit Switch
+ * settings and PIDF values.
+  * @param param to request.
+ */
+CTR_Code CanTalonSRX::RequestParam(param_t paramEnum) {
+  /* process received param events. We don't expect many since this API is not
+   * used often. */
+  ProcessStreamMessages();
+  TALON_Param_Request_t frame;
+  memset(&frame, 0, sizeof(frame));
+  frame.ParamEnum = paramEnum;
+  int32_t status = 0;
+  FRC_NetworkCommunication_CANSessionMux_sendMessage(
+      PARAM_REQUEST | GetDeviceNumber(), (const uint8_t *)&frame, 1, 0,
+      &status);
+  if (status) return CTR_TxFailed;
+  return CTR_OKAY;
+}
+
+CTR_Code CanTalonSRX::SetParam(param_t paramEnum, double value) {
+  int32_t rawbits = 0;
+  switch (paramEnum) {
+    case eProfileParamSlot0_P: /* unsigned 10.22 fixed pt value */
+    case eProfileParamSlot0_I:
+    case eProfileParamSlot0_D:
+    case eProfileParamSlot1_P:
+    case eProfileParamSlot1_I:
+    case eProfileParamSlot1_D: {
+      uint32_t urawbits;
+      value = std::min(
+          value, 1023.0); /* bounds check doubles that are outside u10.22 */
+      value = std::max(value, 0.0);
+      urawbits = value * FLOAT_TO_FXP_10_22; /* perform unsign arithmetic */
+      rawbits = urawbits; /* copy bits over.  SetParamRaw just stuffs into CAN
+                             frame with no sense of signedness */
+    } break;
+    case eProfileParamSlot1_F: /* signed 10.22 fixed pt value */
+    case eProfileParamSlot0_F:
+      value = std::min(
+          value, 512.0); /* bounds check doubles that are outside s10.22 */
+      value = std::max(value, -512.0);
+      rawbits = value * FLOAT_TO_FXP_10_22;
+      break;
+    case eProfileParamVcompRate: /* unsigned 0.8 fixed pt value volts per ms */
+                                 /* within [0,1) volts per ms.
+                                         Slowest ramp is 1/256 VperMilliSec or 3.072 seconds from 0-to-12V.
+                                         Fastest ramp is 255/256 VperMilliSec or 12.1ms from 0-to-12V.
+                                         */
+      if (value <= 0) {
+        /* negative or zero (disable), send raw value of zero */
+        rawbits = 0;
+      } else {
+        /* nonzero ramping */
+        rawbits = value * FLOAT_TO_FXP_0_8;
+        /* since whole part is cleared, cap to just under whole unit */
+        if (rawbits > (FLOAT_TO_FXP_0_8 - 1)) rawbits = (FLOAT_TO_FXP_0_8 - 1);
+        /* since ramping is nonzero, cap to smallest ramp rate possible */
+        if (rawbits == 0) {
+          /* caller is providing a nonzero ramp rate that's too small
+                  to serialize, so cap to smallest possible */
+          rawbits = 1;
+        }
+      }
+      break;
+    default: /* everything else is integral */
+      rawbits = (int32_t)value;
+      break;
+  }
+  return SetParamRaw(paramEnum, rawbits);
+}
+CTR_Code CanTalonSRX::GetParamResponse(param_t paramEnum, double &value) {
+  int32_t rawbits = 0;
+  CTR_Code retval = GetParamResponseRaw(paramEnum, rawbits);
+  switch (paramEnum) {
+    case eProfileParamSlot0_P: /* 10.22 fixed pt value */
+    case eProfileParamSlot0_I:
+    case eProfileParamSlot0_D:
+    case eProfileParamSlot0_F:
+    case eProfileParamSlot1_P:
+    case eProfileParamSlot1_I:
+    case eProfileParamSlot1_D:
+    case eProfileParamSlot1_F:
+    case eCurrent:
+    case eTemp:
+    case eBatteryV:
+      value = ((double)rawbits) * FXP_TO_FLOAT_10_22;
+      break;
+    case eProfileParamVcompRate:
+      value = ((double)rawbits) * FXP_TO_FLOAT_0_8;
+      break;
+    default: /* everything else is integral */
+      value = (double)rawbits;
+      break;
+  }
+  return retval;
+}
+CTR_Code CanTalonSRX::GetParamResponseInt32(param_t paramEnum, int &value) {
+  double dvalue = 0;
+  CTR_Code retval = GetParamResponse(paramEnum, dvalue);
+  value = (int32_t)dvalue;
+  return retval;
+}
+/*----- getters and setters that use param request/response. These signals are
+ * backed up in flash and will survive a power cycle. ---------*/
+/*----- If your application requires changing these values consider using both
+ * slots and switch between slot0 <=> slot1. ------------------*/
+/*----- If your application requires changing these signals frequently then it
+ * makes sense to leverage this API. --------------------------*/
+/*----- Getters don't block, so it may require several calls to get the latest
+ * value. --------------------------*/
+CTR_Code CanTalonSRX::SetPgain(unsigned slotIdx, double gain) {
+  if (slotIdx == 0) return SetParam(eProfileParamSlot0_P, gain);
+  return SetParam(eProfileParamSlot1_P, gain);
+}
+CTR_Code CanTalonSRX::SetIgain(unsigned slotIdx, double gain) {
+  if (slotIdx == 0) return SetParam(eProfileParamSlot0_I, gain);
+  return SetParam(eProfileParamSlot1_I, gain);
+}
+CTR_Code CanTalonSRX::SetDgain(unsigned slotIdx, double gain) {
+  if (slotIdx == 0) return SetParam(eProfileParamSlot0_D, gain);
+  return SetParam(eProfileParamSlot1_D, gain);
+}
+CTR_Code CanTalonSRX::SetFgain(unsigned slotIdx, double gain) {
+  if (slotIdx == 0) return SetParam(eProfileParamSlot0_F, gain);
+  return SetParam(eProfileParamSlot1_F, gain);
+}
+CTR_Code CanTalonSRX::SetIzone(unsigned slotIdx, int zone) {
+  if (slotIdx == 0) return SetParam(eProfileParamSlot0_IZone, zone);
+  return SetParam(eProfileParamSlot1_IZone, zone);
+}
+CTR_Code CanTalonSRX::SetCloseLoopRampRate(unsigned slotIdx,
+                                           int closeLoopRampRate) {
+  if (slotIdx == 0)
+    return SetParam(eProfileParamSlot0_CloseLoopRampRate, closeLoopRampRate);
+  return SetParam(eProfileParamSlot1_CloseLoopRampRate, closeLoopRampRate);
+}
+CTR_Code CanTalonSRX::SetVoltageCompensationRate(double voltagePerMs) {
+  return SetParam(eProfileParamVcompRate, voltagePerMs);
+}
+CTR_Code CanTalonSRX::GetPgain(unsigned slotIdx, double &gain) {
+  if (slotIdx == 0) return GetParamResponse(eProfileParamSlot0_P, gain);
+  return GetParamResponse(eProfileParamSlot1_P, gain);
+}
+CTR_Code CanTalonSRX::GetIgain(unsigned slotIdx, double &gain) {
+  if (slotIdx == 0) return GetParamResponse(eProfileParamSlot0_I, gain);
+  return GetParamResponse(eProfileParamSlot1_I, gain);
+}
+CTR_Code CanTalonSRX::GetDgain(unsigned slotIdx, double &gain) {
+  if (slotIdx == 0) return GetParamResponse(eProfileParamSlot0_D, gain);
+  return GetParamResponse(eProfileParamSlot1_D, gain);
+}
+CTR_Code CanTalonSRX::GetFgain(unsigned slotIdx, double &gain) {
+  if (slotIdx == 0) return GetParamResponse(eProfileParamSlot0_F, gain);
+  return GetParamResponse(eProfileParamSlot1_F, gain);
+}
+CTR_Code CanTalonSRX::GetIzone(unsigned slotIdx, int &zone) {
+  if (slotIdx == 0)
+    return GetParamResponseInt32(eProfileParamSlot0_IZone, zone);
+  return GetParamResponseInt32(eProfileParamSlot1_IZone, zone);
+}
+CTR_Code CanTalonSRX::GetCloseLoopRampRate(unsigned slotIdx,
+                                           int &closeLoopRampRate) {
+  if (slotIdx == 0)
+    return GetParamResponseInt32(eProfileParamSlot0_CloseLoopRampRate,
+                                 closeLoopRampRate);
+  return GetParamResponseInt32(eProfileParamSlot1_CloseLoopRampRate,
+                               closeLoopRampRate);
+}
+CTR_Code CanTalonSRX::GetVoltageCompensationRate(double &voltagePerMs) {
+  return GetParamResponse(eProfileParamVcompRate, voltagePerMs);
+}
+CTR_Code CanTalonSRX::SetSensorPosition(int pos) {
+  return SetParam(eSensorPosition, pos);
+}
+CTR_Code CanTalonSRX::SetForwardSoftLimit(int forwardLimit) {
+  return SetParam(eProfileParamSoftLimitForThreshold, forwardLimit);
+}
+CTR_Code CanTalonSRX::SetReverseSoftLimit(int reverseLimit) {
+  return SetParam(eProfileParamSoftLimitRevThreshold, reverseLimit);
+}
+CTR_Code CanTalonSRX::SetForwardSoftEnable(int enable) {
+  return SetParam(eProfileParamSoftLimitForEnable, enable);
+}
+CTR_Code CanTalonSRX::SetReverseSoftEnable(int enable) {
+  return SetParam(eProfileParamSoftLimitRevEnable, enable);
+}
+CTR_Code CanTalonSRX::GetForwardSoftLimit(int &forwardLimit) {
+  return GetParamResponseInt32(eProfileParamSoftLimitForThreshold,
+                               forwardLimit);
+}
+CTR_Code CanTalonSRX::GetReverseSoftLimit(int &reverseLimit) {
+  return GetParamResponseInt32(eProfileParamSoftLimitRevThreshold,
+                               reverseLimit);
+}
+CTR_Code CanTalonSRX::GetForwardSoftEnable(int &enable) {
+  return GetParamResponseInt32(eProfileParamSoftLimitForEnable, enable);
+}
+CTR_Code CanTalonSRX::GetReverseSoftEnable(int &enable) {
+  return GetParamResponseInt32(eProfileParamSoftLimitRevEnable, enable);
+}
+/**
+ * @param param [out] Rise to fall time period in microseconds.
+ */
+CTR_Code CanTalonSRX::GetPulseWidthRiseToFallUs(int &param) {
+  int temp = 0;
+  int periodUs = 0;
+  /* first grab our 12.12 position */
+  CTR_Code retval1 = GetPulseWidthPosition(temp);
+  /* mask off number of turns */
+  temp &= 0xFFF;
+  /* next grab the waveform period. This value
+   * will be zero if we stop getting pulses **/
+  CTR_Code retval2 = GetPulseWidthRiseToRiseUs(periodUs);
+  /* now we have 0.12 position that is scaled to the waveform period.
+          Use fixed pt multiply to scale our 0.16 period into us.*/
+  param = (temp * periodUs) / BIT12;
+  /* pass the worst error code to caller.
+          Assume largest value is the most pressing error code.*/
+  return (CTR_Code)std::max((int)retval1, (int)retval2);
+}
+CTR_Code CanTalonSRX::IsPulseWidthSensorPresent(int &param) {
+  int periodUs = 0;
+  CTR_Code retval = GetPulseWidthRiseToRiseUs(periodUs);
+  /* if a nonzero period is present, we are getting good pules.
+          Otherwise the sensor is not present. */
+  if (periodUs != 0)
+    param = 1;
+  else
+    param = 0;
+  return retval;
+}
+/**
+ * @param modeSelect selects which mode.
+ * @param demand setpt or throttle or masterId to follow.
+ * @return error code, 0 iff successful.
+ * This function has the advantage of atomically setting mode and demand.
+ */
+CTR_Code CanTalonSRX::SetModeSelect(int modeSelect, int demand) {
+  CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill =
+      GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId |
+                                            GetDeviceNumber());
+  if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+  toFill->ModeSelect = modeSelect;
+  toFill->DemandH = demand >> 16;
+  toFill->DemandM = demand >> 8;
+  toFill->DemandL = demand >> 0;
+  FlushTx(toFill);
+  return CTR_OKAY;
+}
+/**
+ * Change the periodMs of a TALON's status frame.  See kStatusFrame_* enums for
+ * what's available.
+ */
+CTR_Code CanTalonSRX::SetStatusFrameRate(unsigned frameEnum,
+                                         unsigned periodMs) {
+  CTR_Code retval = CTR_OKAY;
+  int32_t paramEnum = 0;
+  /* bounds check the period */
+  if (periodMs < 1)
+    periodMs = 1;
+  else if (periodMs > 255)
+    periodMs = 255;
+  uint8_t period = (uint8_t)periodMs;
+  /* lookup the correct param enum based on what frame to rate-change */
+  switch (frameEnum) {
+    case kStatusFrame_General:
+      paramEnum = eStatus1FrameRate;
+      break;
+    case kStatusFrame_Feedback:
+      paramEnum = eStatus2FrameRate;
+      break;
+    case kStatusFrame_Encoder:
+      paramEnum = eStatus3FrameRate;
+      break;
+    case kStatusFrame_AnalogTempVbat:
+      paramEnum = eStatus4FrameRate;
+      break;
+    case kStatusFrame_PulseWidthMeas:
+      paramEnum = eStatus8FrameRate;
+      break;
+    case kStatusFrame_MotionProfile:
+      paramEnum = eStatus9FrameRate;
+      break;
+    default:
+      /* caller's request is not support, return an error code */
+      retval = CTR_InvalidParamValue;
+      break;
+  }
+  /* if lookup was succesful, send set-request out */
+  if (retval == CTR_OKAY) {
+    /* paramEnum is updated, sent it out */
+    retval = SetParamRaw(paramEnum, period);
+  }
+  return retval;
+}
+/**
+ * Clear all sticky faults in TALON.
+ */
+CTR_Code CanTalonSRX::ClearStickyFaults() {
+  int32_t status = 0;
+  /* build request frame */
+  TALON_Control_3_ClearFlags_OneShot_t frame;
+  memset(&frame, 0, sizeof(frame));
+  frame.ClearStickyFaults = 1;
+  FRC_NetworkCommunication_CANSessionMux_sendMessage(
+      CONTROL_3 | GetDeviceNumber(), (const uint8_t *)&frame, sizeof(frame), 0,
+      &status);
+  if (status) return CTR_TxFailed;
+  return CTR_OKAY;
+}
+/**
+ * @return the tx task that transmits Control6 (motion profile control).
+ *         If it's not scheduled, then schedule it.  This is part of firing
+ *         the MotionProf framing only when needed to save bandwidth.
+ */
+CtreCanNode::txTask<TALON_Control_6_MotProfAddTrajPoint_t>
+CanTalonSRX::GetControl6() {
+  CtreCanNode::txTask<TALON_Control_6_MotProfAddTrajPoint_t> control6 =
+      GetTx<TALON_Control_6_MotProfAddTrajPoint_t>(CONTROL_6 |
+                                                   GetDeviceNumber());
+  if (control6.IsEmpty()) {
+    /* control6 never started, arm it now */
+    RegisterTx(CONTROL_6 | GetDeviceNumber(), _control6PeriodMs);
+    control6 = GetTx<TALON_Control_6_MotProfAddTrajPoint_t>(CONTROL_6 |
+                                                            GetDeviceNumber());
+    control6->Idx = 0;
+    _motProfFlowControl = 0;
+    FlushTx(control6);
+  }
+  return control6;
+}
+/**
+ * Calling application can opt to speed up the handshaking between the robot API
+ * and the Talon to increase the download rate of the Talon's Motion Profile.
+ * Ideally the period should be no more than half the period of a trajectory
+ * point.
+ */
+void CanTalonSRX::ChangeMotionControlFramePeriod(uint32_t periodMs) {
+  std::unique_lock<std::mutex> lock(_mutMotProf);
+  /* if message is already registered, it will get updated.
+   * Otherwise it will error if it hasn't been setup yet, but that's ok
+   * because the _control6PeriodMs will be used later.
+   * @see GetControl6
+   */
+  _control6PeriodMs = periodMs;
+  ChangeTxPeriod(CONTROL_6 | GetDeviceNumber(), _control6PeriodMs);
+}
+/**
+ * Clear the buffered motion profile in both Talon RAM (bottom), and in the API
+ * (top).
+ */
+void CanTalonSRX::ClearMotionProfileTrajectories() {
+  std::unique_lock<std::mutex> lock(_mutMotProf);
+  /* clear the top buffer */
+  _motProfTopBuffer.Clear();
+  /* send signal to clear bottom buffer */
+  auto toFill = CanTalonSRX::GetControl6();
+  toFill->Idx = 0;
+  _motProfFlowControl = 0; /* match the transmitted flow control */
+  FlushTx(toFill);
+}
+/**
+ * Retrieve just the buffer count for the api-level (top) buffer.
+ * This routine performs no CAN or data structure lookups, so its fast and ideal
+ * if caller needs to quickly poll the progress of trajectory points being
+ * emptied into Talon's RAM. Otherwise just use GetMotionProfileStatus.
+ * @return number of trajectory points in the top buffer.
+ */
+uint32_t CanTalonSRX::GetMotionProfileTopLevelBufferCount() {
+  std::unique_lock<std::mutex> lock(_mutMotProf);
+  uint32_t retval = (uint32_t)_motProfTopBuffer.GetNumTrajectories();
+  return retval;
+}
+/**
+ * Retrieve just the buffer full for the api-level (top) buffer.
+ * This routine performs no CAN or data structure lookups, so its fast and ideal
+ * if caller needs to quickly poll. Otherwise just use GetMotionProfileStatus.
+ * @return number of trajectory points in the top buffer.
+ */
+bool CanTalonSRX::IsMotionProfileTopLevelBufferFull() {
+  std::unique_lock<std::mutex> lock(_mutMotProf);
+  if (_motProfTopBuffer.GetNumTrajectories() >= kMotionProfileTopBufferCapacity)
+    return true;
+  return false;
+}
+/**
+ * Push another trajectory point into the top level buffer (which is emptied
+ * into the Talon's bottom buffer as room allows).
+ * @param targPos  servo position in native Talon units (sensor units).
+ * @param targVel  velocity to feed-forward in native Talon units (sensor units
+ *                 per 100ms).
+ * @param profileSlotSelect  which slot to pull PIDF gains from.  Currently
+ *                           supports 0 or 1.
+ * @param timeDurMs  time in milliseconds of how long to apply this point.
+ * @param velOnly  set to nonzero to signal Talon that only the feed-foward
+ *                 velocity should be used, i.e. do not perform PID on position.
+ *                 This is equivalent to setting PID gains to zero, but much
+ *                 more efficient and synchronized to MP.
+ * @param isLastPoint  set to nonzero to signal Talon to keep processing this
+ *                     trajectory point, instead of jumping to the next one
+ *                     when timeDurMs expires.  Otherwise MP executer will
+ *                     eventually see an empty buffer after the last point
+ *                     expires, causing it to assert the IsUnderRun flag.
+ *                     However this may be desired if calling application
+ *                     never wants to terminate the MP.
+ * @param zeroPos  set to nonzero to signal Talon to "zero" the selected
+ *                 position sensor before executing this trajectory point.
+ *                 Typically the first point should have this set only thus
+ *                 allowing the remainder of the MP positions to be relative to
+ *                 zero.
+ * @return CTR_OKAY if trajectory point push ok. CTR_BufferFull if buffer is
+ *         full due to kMotionProfileTopBufferCapacity.
+ */
+CTR_Code CanTalonSRX::PushMotionProfileTrajectory(int targPos, int targVel,
+                                                  int profileSlotSelect,
+                                                  int timeDurMs, int velOnly,
+                                                  int isLastPoint,
+                                                  int zeroPos) {
+  ReactToMotionProfileCall();
+  /* create our trajectory point */
+  TALON_Control_6_MotProfAddTrajPoint_huff0_t traj;
+  memset((void *)&traj, 0, sizeof(traj));
+  traj.NextPt_ZeroPosition = zeroPos ? 1 : 0;
+  traj.NextPt_VelOnly = velOnly ? 1 : 0;
+  traj.NextPt_IsLast = isLastPoint ? 1 : 0;
+  traj.NextPt_ProfileSlotSelect = (profileSlotSelect > 0) ? 1 : 0;
+  if (timeDurMs < 0)
+    timeDurMs = 0;
+  else if (timeDurMs > 255)
+    timeDurMs = 255;
+  traj.NextPt_DurationMs = timeDurMs;
+  traj.NextPt_VelocityH = targVel >> 0x08;
+  traj.NextPt_VelocityL = targVel & 0xFF;
+  traj.NextPt_PositionH = targPos >> 0x10;
+  traj.NextPt_PositionM = targPos >> 0x08;
+  traj.NextPt_PositionL = targPos & 0xFF;
+
+  std::unique_lock<std::mutex> lock(_mutMotProf);
+  if (_motProfTopBuffer.GetNumTrajectories() >= kMotionProfileTopBufferCapacity)
+    return CTR_BufferFull;
+  _motProfTopBuffer.Push(traj);
+  return CTR_OKAY;
+}
+/**
+ * Increment our flow control to manage streaming to the Talon.
+ * f(x) = { 1,   x = 15,
+ *          x+1,  x < 15
+ *        }
+ */
+#define MotionProf_IncrementSync(idx) ((idx >= 15) ? 1 : 0) + ((idx + 1) & 0xF)
+/**
+ * Update the NextPt signals inside the control frame given the next pt to send.
+ * @param control pointer to the CAN frame payload containing control6.  Only
+ * the signals that serialize the next trajectory point are updated from the
+ * contents of newPt.
+ * @param newPt point to the next trajectory that needs to be inserted into
+ *        Talon RAM.
+ */
+void CanTalonSRX::CopyTrajPtIntoControl(
+    TALON_Control_6_MotProfAddTrajPoint_t *control,
+    const TALON_Control_6_MotProfAddTrajPoint_t *newPt) {
+  /* Bring over the common signals in the first two bytes */
+  control->NextPt_ProfileSlotSelect = newPt->NextPt_ProfileSlotSelect;
+  control->NextPt_ZeroPosition = newPt->NextPt_ZeroPosition;
+  control->NextPt_VelOnly = newPt->NextPt_VelOnly;
+  control->NextPt_IsLast = newPt->NextPt_IsLast;
+  control->huffCode = newPt->huffCode;
+  /* the last six bytes are entirely for hold NextPt's values. */
+  uint8_t *dest = (uint8_t *)control;
+  const uint8_t *src = (const uint8_t *)newPt;
+  dest[2] = src[2];
+  dest[3] = src[3];
+  dest[4] = src[4];
+  dest[5] = src[5];
+  dest[6] = src[6];
+  dest[7] = src[7];
+}
+/**
+ * Caller is either pushing a new motion profile point, or is
+ * calling the Process buffer routine.  In either case check our
+ * flow control to see if we need to start sending control6.
+ */
+void CanTalonSRX::ReactToMotionProfileCall() {
+  if (_motProfFlowControl < 0) {
+    /* we have not yet armed the periodic frame.  We do this lazilly to
+     * save bus utilization since most Talons on the bus probably are not
+     * MP'ing.
+     */
+    ClearMotionProfileTrajectories(); /* this moves flow control so only fires
+                                         once if ever */
+  }
+}
+/**
+ * This must be called periodically to funnel the trajectory points from the
+ * API's top level buffer to the Talon's bottom level buffer.  Recommendation
+ * is to call this twice as fast as the executation rate of the motion profile.
+ * So if MP is running with 20ms trajectory points, try calling this routine
+ * every 10ms.  All motion profile functions are thread-safe through the use of
+ * a mutex, so there is no harm in having the caller utilize threading.
+ */
+void CanTalonSRX::ProcessMotionProfileBuffer() {
+  ReactToMotionProfileCall();
+  /* get the latest status frame */
+  GET_STATUS9();
+  /* lock */
+  std::unique_lock<std::mutex> lock(_mutMotProf);
+  /* calc what we expect to receive */
+  if (_motProfFlowControl == rx->NextID) {
+    /* Talon has completed the last req */
+    if (_motProfTopBuffer.IsEmpty()) {
+      /* nothing to do */
+    } else {
+      /* get the latest control frame */
+      auto toFill = GetControl6();
+      TALON_Control_6_MotProfAddTrajPoint_t *front = _motProfTopBuffer.Front();
+      CopyTrajPtIntoControl(toFill.toSend, front);
+      _motProfTopBuffer.Pop();
+      _motProfFlowControl = MotionProf_IncrementSync(_motProfFlowControl);
+      toFill->Idx = _motProfFlowControl;
+      FlushTx(toFill);
+    }
+  } else {
+    /* still waiting on Talon */
+  }
+}
+/**
+ * Retrieve all status information.
+ * Since this all comes from one CAN frame, its ideal to have one routine to
+ * retrieve the frame once and decode everything.
+ * @param [out] flags  bitfield for status bools. Starting with least
+ *        significant bit: IsValid, HasUnderrun, IsUnderrun, IsLast, VelOnly.
+ *
+ *        IsValid  set when MP executer is processing a trajectory point,
+ *                 and that point's status is instrumented with IsLast,
+ *                 VelOnly, targPos, targVel.  However if MP executor is
+ *                 not processing a trajectory point, then this flag is
+ *                 false, and the instrumented signals will be zero.
+ *        HasUnderrun  is set anytime the MP executer is ready to pop
+ *                     another trajectory point from the Talon's RAM,
+ *                     but the buffer is empty.  It can only be cleared
+ *                     by using SetParam(eMotionProfileHasUnderrunErr,0);
+ *        IsUnderrun  is set when the MP executer is ready for another
+ *                    point, but the buffer is empty, and cleared when
+ *                    the MP executer does not need another point.
+ *                    HasUnderrun shadows this registor when this
+ *                    register gets set, however HasUnderrun stays
+ *                    asserted until application has process it, and
+ *                    IsUnderrun auto-clears when the condition is
+ *                    resolved.
+ *        IsLast  is set/cleared based on the MP executer's current
+ *                trajectory point's IsLast value.  This assumes
+ *                IsLast was set when PushMotionProfileTrajectory
+ *                was used to insert the currently processed trajectory
+ *                point.
+ *        VelOnly  is set/cleared based on the MP executer's current
+ *                 trajectory point's VelOnly value.
+ *
+ * @param [out] profileSlotSelect  The currently processed trajectory point's
+ *        selected slot.  This can differ in the currently selected slot used
+ *        for Position and Velocity servo modes.
+ * @param [out] targPos The currently processed trajectory point's position
+ *        in native units.  This param is zero if IsValid is zero.
+ * @param [out] targVel The currently processed trajectory point's velocity
+ *        in native units.  This param is zero if IsValid is zero.
+ * @param [out] topBufferRem The remaining number of points in the top level
+ *        buffer.
+ * @param [out] topBufferCnt The number of points in the top level buffer to
+ *        be sent to Talon.
+ * @param [out] btmBufferCnt The number of points in the bottom level buffer
+ *        inside Talon.
+ * @return CTR error code
+ */
+CTR_Code CanTalonSRX::GetMotionProfileStatus(
+    uint32_t &flags, uint32_t &profileSlotSelect, int32_t &targPos,
+    int32_t &targVel, uint32_t &topBufferRem, uint32_t &topBufferCnt,
+    uint32_t &btmBufferCnt, uint32_t &outputEnable) {
+  /* get the latest status frame */
+  GET_STATUS9();
+
+  /* clear signals in case we never received an update, caller should check
+   * return
+   */
+  flags = 0;
+  profileSlotSelect = 0;
+  targPos = 0;
+  targVel = 0;
+  btmBufferCnt = 0;
+
+  /* these signals are always available */
+  topBufferCnt = _motProfTopBuffer.GetNumTrajectories();
+  topBufferRem =
+      kMotionProfileTopBufferCapacity - _motProfTopBuffer.GetNumTrajectories();
+
+  /* TODO: make enums or make a better method prototype */
+  if (rx->ActTraj_IsValid) flags |= kMotionProfileFlag_ActTraj_IsValid;
+  if (rx->HasUnderrun) flags |= kMotionProfileFlag_HasUnderrun;
+  if (rx->IsUnderrun) flags |= kMotionProfileFlag_IsUnderrun;
+  if (rx->ActTraj_IsLast) flags |= kMotionProfileFlag_ActTraj_IsLast;
+  if (rx->ActTraj_VelOnly) flags |= kMotionProfileFlag_ActTraj_VelOnly;
+
+  btmBufferCnt = rx->Count;
+
+  targPos = rx->ActTraj_PositionH;
+  targPos <<= 8;
+  targPos |= rx->ActTraj_PositionM;
+  targPos <<= 8;
+  targPos |= rx->ActTraj_PositionL;
+
+  targVel = rx->ActTraj_VelocityH;
+  targVel <<= 8;
+  targVel |= rx->ActTraj_VelocityL;
+
+  profileSlotSelect = rx->ActTraj_ProfileSlotSelect;
+
+  switch (rx->OutputType) {
+    case kMotionProf_Disabled:
+    case kMotionProf_Enable:
+    case kMotionProf_Hold:
+      outputEnable = rx->OutputType;
+      break;
+    default:
+      /* do now allow invalid values for sake of user-facing enum types */
+      outputEnable = kMotionProf_Disabled;
+      break;
+  }
+  return rx.err;
+}
+//------------------------ auto generated ------------------------------------//
+/* This API is optimal since it uses the fire-and-forget CAN interface.
+ * These signals should cover the majority of all use cases.
+ */
+CTR_Code CanTalonSRX::GetFault_OverTemp(int &param)
+{
+  GET_STATUS1();
+  param = rx->Fault_OverTemp;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetFault_UnderVoltage(int &param)
+{
+  GET_STATUS1();
+  param = rx->Fault_UnderVoltage;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetFault_ForLim(int &param)
+{
+  GET_STATUS1();
+  param = rx->Fault_ForLim;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetFault_RevLim(int &param)
+{
+  GET_STATUS1();
+  param = rx->Fault_RevLim;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetFault_HardwareFailure(int &param)
+{
+  GET_STATUS1();
+  param = rx->Fault_HardwareFailure;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetFault_ForSoftLim(int &param)
+{
+  GET_STATUS1();
+  param = rx->Fault_ForSoftLim;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetFault_RevSoftLim(int &param)
+{
+  GET_STATUS1();
+  param = rx->Fault_RevSoftLim;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetStckyFault_OverTemp(int &param)
+{
+  GET_STATUS2();
+  param = rx->StckyFault_OverTemp;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetStckyFault_UnderVoltage(int &param)
+{
+  GET_STATUS2();
+  param = rx->StckyFault_UnderVoltage;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetStckyFault_ForLim(int &param)
+{
+  GET_STATUS2();
+  param = rx->StckyFault_ForLim;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetStckyFault_RevLim(int &param)
+{
+  GET_STATUS2();
+  param = rx->StckyFault_RevLim;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetStckyFault_ForSoftLim(int &param)
+{
+  GET_STATUS2();
+  param = rx->StckyFault_ForSoftLim;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetStckyFault_RevSoftLim(int &param)
+{
+  GET_STATUS2();
+  param = rx->StckyFault_RevSoftLim;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetAppliedThrottle(int &param)
+{
+  GET_STATUS1();
+  int32_t raw = 0;
+  raw |= rx->AppliedThrottle_h3;
+  raw <<= 8;
+  raw |= rx->AppliedThrottle_l8;
+  raw <<= (32-11); /* sign extend */
+  raw >>= (32-11); /* sign extend */
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetCloseLoopErr(int &param)
+{
+  GET_STATUS1();
+  int32_t raw = 0;
+  raw |= rx->CloseLoopErrH;
+  raw <<= 16 - 8;
+  raw |= rx->CloseLoopErrM;
+  raw <<= 8;
+  raw |= rx->CloseLoopErrL;
+  raw <<= (32-24); /* sign extend */
+  raw >>= (32-24); /* sign extend */
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetFeedbackDeviceSelect(int &param)
+{
+  GET_STATUS1();
+  param = rx->FeedbackDeviceSelect;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetModeSelect(int &param)
+{
+  GET_STATUS1();
+  uint32_t raw = 0;
+  raw |= rx->ModeSelect_h1;
+  raw <<= 3;
+  raw |= rx->ModeSelect_b3;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetLimitSwitchEn(int &param)
+{
+  GET_STATUS1();
+  param = rx->LimitSwitchEn;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetLimitSwitchClosedFor(int &param)
+{
+  GET_STATUS1();
+  param = rx->LimitSwitchClosedFor;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetLimitSwitchClosedRev(int &param)
+{
+  GET_STATUS1();
+  param = rx->LimitSwitchClosedRev;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetSensorPosition(int &param)
+{
+  GET_STATUS2();
+  int32_t raw = 0;
+  raw |= rx->SensorPositionH;
+  raw <<= 16 - 8;
+  raw |= rx->SensorPositionM;
+  raw <<= 8;
+  raw |= rx->SensorPositionL;
+  raw <<= (32-24); /* sign extend */
+  raw >>= (32-24); /* sign extend */
+  if(rx->PosDiv8)
+    raw *= 8;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetSensorVelocity(int &param)
+{
+  GET_STATUS2();
+  int32_t raw = 0;
+  raw |= rx->SensorVelocityH;
+  raw <<= 8;
+  raw |= rx->SensorVelocityL;
+  raw <<= (32-16); /* sign extend */
+  raw >>= (32-16); /* sign extend */
+  if(rx->VelDiv4)
+    raw *= 4;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetCurrent(double &param)
+{
+  GET_STATUS2();
+  uint32_t raw = 0;
+  raw |= rx->Current_h8;
+  raw <<= 2;
+  raw |= rx->Current_l2;
+  param = (double)raw * 0.125 + 0;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetBrakeIsEnabled(int &param)
+{
+  GET_STATUS2();
+  param = rx->BrakeIsEnabled;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetEncPosition(int &param)
+{
+  GET_STATUS3();
+  int32_t raw = 0;
+  raw |= rx->EncPositionH;
+  raw <<= 16 - 8;
+  raw |= rx->EncPositionM;
+  raw <<= 8;
+  raw |= rx->EncPositionL;
+  raw <<= (32-24); /* sign extend */
+  raw >>= (32-24); /* sign extend */
+  if(rx->PosDiv8)
+    raw *= 8;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetEncVel(int &param)
+{
+  GET_STATUS3();
+  int32_t raw = 0;
+  raw |= rx->EncVelH;
+  raw <<= 8;
+  raw |= rx->EncVelL;
+  raw <<= (32-16); /* sign extend */
+  raw >>= (32-16); /* sign extend */
+  if(rx->VelDiv4)
+    raw *= 4;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetEncIndexRiseEvents(int &param)
+{
+  GET_STATUS3();
+  uint32_t raw = 0;
+  raw |= rx->EncIndexRiseEventsH;
+  raw <<= 8;
+  raw |= rx->EncIndexRiseEventsL;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetQuadApin(int &param)
+{
+  GET_STATUS3();
+  param = rx->QuadApin;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetQuadBpin(int &param)
+{
+  GET_STATUS3();
+  param = rx->QuadBpin;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetQuadIdxpin(int &param)
+{
+  GET_STATUS3();
+  param = rx->QuadIdxpin;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetAnalogInWithOv(int &param)
+{
+  GET_STATUS4();
+  int32_t raw = 0;
+  raw |= rx->AnalogInWithOvH;
+  raw <<= 16 - 8;
+  raw |= rx->AnalogInWithOvM;
+  raw <<= 8;
+  raw |= rx->AnalogInWithOvL;
+  raw <<= (32-24); /* sign extend */
+  raw >>= (32-24); /* sign extend */
+  if(rx->PosDiv8)
+    raw *= 8;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetAnalogInVel(int &param)
+{
+  GET_STATUS4();
+  int32_t raw = 0;
+  raw |= rx->AnalogInVelH;
+  raw <<= 8;
+  raw |= rx->AnalogInVelL;
+  raw <<= (32-16); /* sign extend */
+  raw >>= (32-16); /* sign extend */
+  if(rx->VelDiv4)
+    raw *= 4;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetTemp(double &param)
+{
+  GET_STATUS4();
+  uint32_t raw = rx->Temp;
+  param = (double)raw * 0.6451612903 + -50;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetBatteryV(double &param)
+{
+  GET_STATUS4();
+  uint32_t raw = rx->BatteryV;
+  param = (double)raw * 0.05 + 4;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetResetCount(int &param)
+{
+  GET_STATUS5();
+  uint32_t raw = 0;
+  raw |= rx->ResetCountH;
+  raw <<= 8;
+  raw |= rx->ResetCountL;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetResetFlags(int &param)
+{
+  GET_STATUS5();
+  uint32_t raw = 0;
+  raw |= rx->ResetFlagsH;
+  raw <<= 8;
+  raw |= rx->ResetFlagsL;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetFirmVers(int &param)
+{
+  GET_STATUS5();
+  uint32_t raw = 0;
+  raw |= rx->FirmVersH;
+  raw <<= 8;
+  raw |= rx->FirmVersL;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetPulseWidthPosition(int &param)
+{
+  GET_STATUS8();
+  int32_t raw = 0;
+  raw |= rx->PulseWidPositionH;
+  raw <<= 16 - 8;
+  raw |= rx->PulseWidPositionM;
+  raw <<= 8;
+  raw |= rx->PulseWidPositionL;
+  raw <<= (32-24); /* sign extend */
+  raw >>= (32-24); /* sign extend */
+  if(rx->PosDiv8)
+    raw *= 8;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetPulseWidthVelocity(int &param)
+{
+  GET_STATUS8();
+  int32_t raw = 0;
+  raw |= rx->PulseWidVelH;
+  raw <<= 8;
+  raw |= rx->PulseWidVelL;
+  raw <<= (32-16); /* sign extend */
+  raw >>= (32-16); /* sign extend */
+  if(rx->VelDiv4)
+    raw *= 4;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetPulseWidthRiseToRiseUs(int &param)
+{
+  GET_STATUS8();
+  uint32_t raw = 0;
+  raw |= rx->PeriodUsM8;
+  raw <<= 8;
+  raw |= rx->PeriodUsL8;
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetActTraj_IsValid(int &param)
+{
+  GET_STATUS9();
+  param = rx->ActTraj_IsValid;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetActTraj_ProfileSlotSelect(int &param)
+{
+  GET_STATUS9();
+  param = rx->ActTraj_ProfileSlotSelect;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetActTraj_VelOnly(int &param)
+{
+  GET_STATUS9();
+  param = rx->ActTraj_VelOnly;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetActTraj_IsLast(int &param)
+{
+  GET_STATUS9();
+  param = rx->ActTraj_IsLast;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetOutputType(int &param)
+{
+  GET_STATUS9();
+  param = rx->OutputType;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetHasUnderrun(int &param)
+{
+  GET_STATUS9();
+  param = rx->HasUnderrun;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetIsUnderrun(int &param)
+{
+  GET_STATUS9();
+  param = rx->IsUnderrun;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetNextID(int &param)
+{
+  GET_STATUS9();
+  param = rx->NextID;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetBufferIsFull(int &param)
+{
+  GET_STATUS9();
+  param = rx->BufferIsFull;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetCount(int &param)
+{
+  GET_STATUS9();
+  param = rx->Count;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetActTraj_Velocity(int &param)
+{
+  GET_STATUS9();
+  int32_t raw = 0;
+  raw |= rx->ActTraj_VelocityH;
+  raw <<= 8;
+  raw |= rx->ActTraj_VelocityL;
+  raw <<= (32-16); /* sign extend */
+  raw >>= (32-16); /* sign extend */
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::GetActTraj_Position(int &param)
+{
+  GET_STATUS9();
+  int32_t raw = 0;
+  raw |= rx->ActTraj_PositionH;
+  raw <<= 16 - 8;
+  raw |= rx->ActTraj_PositionM;
+  raw <<= 8;
+  raw |= rx->ActTraj_PositionL;
+  raw <<= (32-24); /* sign extend */
+  raw >>= (32-24); /* sign extend */
+  param = (int)raw;
+  return rx.err;
+}
+CTR_Code CanTalonSRX::SetDemand(int param)
+{
+  CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
+  if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+  toFill->DemandH = param>>16;
+  toFill->DemandM = param>>8;
+  toFill->DemandL = param>>0;
+  FlushTx(toFill);
+  return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetOverrideLimitSwitchEn(int param)
+{
+  CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
+  if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+  toFill->OverrideLimitSwitchEn = param;
+  FlushTx(toFill);
+  return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetFeedbackDeviceSelect(int param)
+{
+  CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
+  if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+  toFill->FeedbackDeviceSelect = param;
+  FlushTx(toFill);
+  return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetRevMotDuringCloseLoopEn(int param)
+{
+  CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
+  if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+  toFill->RevMotDuringCloseLoopEn = param;
+  FlushTx(toFill);
+  return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetOverrideBrakeType(int param)
+{
+  CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
+  if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+  toFill->OverrideBrakeType = param;
+  FlushTx(toFill);
+  return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetModeSelect(int param)
+{
+  CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
+  if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+  toFill->ModeSelect = param;
+  FlushTx(toFill);
+  return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetProfileSlotSelect(int param)
+{
+  CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
+  if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+  toFill->ProfileSlotSelect = param;
+  FlushTx(toFill);
+  return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetRampThrottle(int param)
+{
+  CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
+  if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+  toFill->RampThrottle = param;
+  FlushTx(toFill);
+  return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetRevFeedbackSensor(int param)
+{
+  CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
+  if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+  toFill->RevFeedbackSensor = param ? 1 : 0;
+  FlushTx(toFill);
+  return CTR_OKAY;
+}
+//------------------ C interface --------------------------------------------//
+extern "C" {
+void *c_TalonSRX_Create3(int deviceNumber, int controlPeriodMs, int enablePeriodMs)
+{
+  return new CanTalonSRX(deviceNumber, controlPeriodMs, enablePeriodMs);
+}
+void *c_TalonSRX_Create2(int deviceNumber, int controlPeriodMs)
+{
+  return new CanTalonSRX(deviceNumber, controlPeriodMs);
+}
+void *c_TalonSRX_Create1(int deviceNumber)
+{
+  return new CanTalonSRX(deviceNumber);
+}
+void c_TalonSRX_Destroy(void *handle)
+{
+  delete (CanTalonSRX*)handle;
+}
+void c_TalonSRX_Set(void *handle, double value)
+{
+  return ((CanTalonSRX*)handle)->Set(value);
+}
+CTR_Code c_TalonSRX_SetParam(void *handle, int paramEnum, double value)
+{
+  return ((CanTalonSRX*)handle)->SetParam((CanTalonSRX::param_t)paramEnum, value);
+}
+CTR_Code c_TalonSRX_RequestParam(void *handle, int paramEnum)
+{
+  return ((CanTalonSRX*)handle)->RequestParam((CanTalonSRX::param_t)paramEnum);
+}
+CTR_Code c_TalonSRX_GetParamResponse(void *handle, int paramEnum, double *value)
+{
+  return ((CanTalonSRX*)handle)->GetParamResponse((CanTalonSRX::param_t)paramEnum, *value);
+}
+CTR_Code c_TalonSRX_GetParamResponseInt32(void *handle, int paramEnum, int *value)
+{
+  return ((CanTalonSRX*)handle)->GetParamResponseInt32((CanTalonSRX::param_t)paramEnum, *value);
+}
+CTR_Code c_TalonSRX_SetPgain(void *handle, int slotIdx, double gain)
+{
+  return ((CanTalonSRX*)handle)->SetPgain((unsigned)slotIdx, gain);
+}
+CTR_Code c_TalonSRX_SetIgain(void *handle, int slotIdx, double gain)
+{
+  return ((CanTalonSRX*)handle)->SetIgain((unsigned)slotIdx, gain);
+}
+CTR_Code c_TalonSRX_SetDgain(void *handle, int slotIdx, double gain)
+{
+  return ((CanTalonSRX*)handle)->SetDgain((unsigned)slotIdx, gain);
+}
+CTR_Code c_TalonSRX_SetFgain(void *handle, int slotIdx, double gain)
+{
+  return ((CanTalonSRX*)handle)->SetFgain((unsigned)slotIdx, gain);
+}
+CTR_Code c_TalonSRX_SetIzone(void *handle, int slotIdx, int zone)
+{
+  return ((CanTalonSRX*)handle)->SetIzone((unsigned)slotIdx, zone);
+}
+CTR_Code c_TalonSRX_SetCloseLoopRampRate(void *handle, int slotIdx, int closeLoopRampRate)
+{
+  return ((CanTalonSRX*)handle)->SetCloseLoopRampRate((unsigned)slotIdx, closeLoopRampRate);
+}
+CTR_Code c_TalonSRX_SetVoltageCompensationRate(void *handle, double voltagePerMs)
+{
+  return ((CanTalonSRX*)handle)->SetVoltageCompensationRate(voltagePerMs);
+}
+CTR_Code c_TalonSRX_SetSensorPosition(void *handle, int pos)
+{
+  return ((CanTalonSRX*)handle)->SetSensorPosition(pos);
+}
+CTR_Code c_TalonSRX_SetForwardSoftLimit(void *handle, int forwardLimit)
+{
+  return ((CanTalonSRX*)handle)->SetForwardSoftLimit(forwardLimit);
+}
+CTR_Code c_TalonSRX_SetReverseSoftLimit(void *handle, int reverseLimit)
+{
+  return ((CanTalonSRX*)handle)->SetReverseSoftLimit(reverseLimit);
+}
+CTR_Code c_TalonSRX_SetForwardSoftEnable(void *handle, int enable)
+{
+  return ((CanTalonSRX*)handle)->SetForwardSoftEnable(enable);
+}
+CTR_Code c_TalonSRX_SetReverseSoftEnable(void *handle, int enable)
+{
+  return ((CanTalonSRX*)handle)->SetReverseSoftEnable(enable);
+}
+CTR_Code c_TalonSRX_GetPgain(void *handle, int slotIdx, double *gain)
+{
+  return ((CanTalonSRX*)handle)->GetPgain((unsigned)slotIdx, *gain);
+}
+CTR_Code c_TalonSRX_GetIgain(void *handle, int slotIdx, double *gain)
+{
+  return ((CanTalonSRX*)handle)->GetIgain((unsigned)slotIdx, *gain);
+}
+CTR_Code c_TalonSRX_GetDgain(void *handle, int slotIdx, double *gain)
+{
+  return ((CanTalonSRX*)handle)->GetDgain((unsigned)slotIdx, *gain);
+}
+CTR_Code c_TalonSRX_GetFgain(void *handle, int slotIdx, double *gain)
+{
+  return ((CanTalonSRX*)handle)->GetFgain((unsigned)slotIdx, *gain);
+}
+CTR_Code c_TalonSRX_GetIzone(void *handle, int slotIdx, int *zone)
+{
+  return ((CanTalonSRX*)handle)->GetIzone((unsigned)slotIdx, *zone);
+}
+CTR_Code c_TalonSRX_GetCloseLoopRampRate(void *handle, int slotIdx, int *closeLoopRampRate)
+{
+  return ((CanTalonSRX*)handle)->GetCloseLoopRampRate((unsigned)slotIdx, *closeLoopRampRate);
+}
+CTR_Code c_TalonSRX_GetVoltageCompensationRate(void *handle, double *voltagePerMs)
+{
+  return ((CanTalonSRX*)handle)->GetVoltageCompensationRate(*voltagePerMs);
+}
+CTR_Code c_TalonSRX_GetForwardSoftLimit(void *handle, int *forwardLimit)
+{
+  return ((CanTalonSRX*)handle)->GetForwardSoftLimit(*forwardLimit);
+}
+CTR_Code c_TalonSRX_GetReverseSoftLimit(void *handle, int *reverseLimit)
+{
+  return ((CanTalonSRX*)handle)->GetReverseSoftLimit(*reverseLimit);
+}
+CTR_Code c_TalonSRX_GetForwardSoftEnable(void *handle, int *enable)
+{
+  return ((CanTalonSRX*)handle)->GetForwardSoftEnable(*enable);
+}
+CTR_Code c_TalonSRX_GetReverseSoftEnable(void *handle, int *enable)
+{
+  return ((CanTalonSRX*)handle)->GetReverseSoftEnable(*enable);
+}
+CTR_Code c_TalonSRX_GetPulseWidthRiseToFallUs(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetPulseWidthRiseToFallUs(*param);
+}
+CTR_Code c_TalonSRX_IsPulseWidthSensorPresent(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->IsPulseWidthSensorPresent(*param);
+}
+CTR_Code c_TalonSRX_SetModeSelect2(void *handle, int modeSelect, int demand)
+{
+  return ((CanTalonSRX*)handle)->SetModeSelect(modeSelect, demand);
+}
+CTR_Code c_TalonSRX_SetStatusFrameRate(void *handle, int frameEnum, int periodMs)
+{
+  return ((CanTalonSRX*)handle)->SetStatusFrameRate((unsigned)frameEnum, (unsigned)periodMs);
+}
+CTR_Code c_TalonSRX_ClearStickyFaults(void *handle)
+{
+  return ((CanTalonSRX*)handle)->ClearStickyFaults();
+}
+void c_TalonSRX_ChangeMotionControlFramePeriod(void *handle, int periodMs)
+{
+  return ((CanTalonSRX*)handle)->ChangeMotionControlFramePeriod((uint32_t)periodMs);
+}
+void c_TalonSRX_ClearMotionProfileTrajectories(void *handle)
+{
+  return ((CanTalonSRX*)handle)->ClearMotionProfileTrajectories();
+}
+int c_TalonSRX_GetMotionProfileTopLevelBufferCount(void *handle)
+{
+  return ((CanTalonSRX*)handle)->GetMotionProfileTopLevelBufferCount();
+}
+int c_TalonSRX_IsMotionProfileTopLevelBufferFull(void *handle)
+{
+  return ((CanTalonSRX*)handle)->IsMotionProfileTopLevelBufferFull();
+}
+CTR_Code c_TalonSRX_PushMotionProfileTrajectory(void *handle, int targPos, int targVel, int profileSlotSelect, int timeDurMs, int velOnly, int isLastPoint, int zeroPos)
+{
+  return ((CanTalonSRX*)handle)->PushMotionProfileTrajectory(targPos, targVel, profileSlotSelect, timeDurMs, velOnly, isLastPoint, zeroPos);
+}
+void c_TalonSRX_ProcessMotionProfileBuffer(void *handle)
+{
+  return ((CanTalonSRX*)handle)->ProcessMotionProfileBuffer();
+}
+CTR_Code c_TalonSRX_GetMotionProfileStatus(void *handle, int *flags, int *profileSlotSelect, int *targPos, int *targVel, int *topBufferRemaining, int *topBufferCnt, int *btmBufferCnt, int *outputEnable)
+{
+  uint32_t flags_val;
+  uint32_t profileSlotSelect_val;
+  int32_t targPos_val;
+  int32_t targVel_val;
+  uint32_t topBufferRemaining_val;
+  uint32_t topBufferCnt_val;
+  uint32_t btmBufferCnt_val;
+  uint32_t outputEnable_val;
+  CTR_Code retval = ((CanTalonSRX*)handle)->GetMotionProfileStatus(flags_val, profileSlotSelect_val, targPos_val, targVel_val, topBufferRemaining_val, topBufferCnt_val, btmBufferCnt_val, outputEnable_val);
+  *flags = (int)flags_val;
+  *profileSlotSelect = (int)profileSlotSelect_val;
+  *targPos = (int)targPos_val;
+  *targVel = (int)targVel_val;
+  *topBufferRemaining = (int)topBufferRemaining_val;
+  *topBufferCnt = (int)topBufferCnt_val;
+  *btmBufferCnt = (int)btmBufferCnt_val;
+  *outputEnable = (int)outputEnable_val;
+  return retval;
+}
+CTR_Code c_TalonSRX_GetFault_OverTemp(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetFault_OverTemp(*param);
+}
+CTR_Code c_TalonSRX_GetFault_UnderVoltage(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetFault_UnderVoltage(*param);
+}
+CTR_Code c_TalonSRX_GetFault_ForLim(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetFault_ForLim(*param);
+}
+CTR_Code c_TalonSRX_GetFault_RevLim(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetFault_RevLim(*param);
+}
+CTR_Code c_TalonSRX_GetFault_HardwareFailure(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetFault_HardwareFailure(*param);
+}
+CTR_Code c_TalonSRX_GetFault_ForSoftLim(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetFault_ForSoftLim(*param);
+}
+CTR_Code c_TalonSRX_GetFault_RevSoftLim(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetFault_RevSoftLim(*param);
+}
+CTR_Code c_TalonSRX_GetStckyFault_OverTemp(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetStckyFault_OverTemp(*param);
+}
+CTR_Code c_TalonSRX_GetStckyFault_UnderVoltage(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetStckyFault_UnderVoltage(*param);
+}
+CTR_Code c_TalonSRX_GetStckyFault_ForLim(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetStckyFault_ForLim(*param);
+}
+CTR_Code c_TalonSRX_GetStckyFault_RevLim(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetStckyFault_RevLim(*param);
+}
+CTR_Code c_TalonSRX_GetStckyFault_ForSoftLim(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetStckyFault_ForSoftLim(*param);
+}
+CTR_Code c_TalonSRX_GetStckyFault_RevSoftLim(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetStckyFault_RevSoftLim(*param);
+}
+CTR_Code c_TalonSRX_GetAppliedThrottle(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetAppliedThrottle(*param);
+}
+CTR_Code c_TalonSRX_GetCloseLoopErr(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetCloseLoopErr(*param);
+}
+CTR_Code c_TalonSRX_GetFeedbackDeviceSelect(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetFeedbackDeviceSelect(*param);
+}
+CTR_Code c_TalonSRX_GetModeSelect(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetModeSelect(*param);
+}
+CTR_Code c_TalonSRX_GetLimitSwitchEn(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetLimitSwitchEn(*param);
+}
+CTR_Code c_TalonSRX_GetLimitSwitchClosedFor(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetLimitSwitchClosedFor(*param);
+}
+CTR_Code c_TalonSRX_GetLimitSwitchClosedRev(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetLimitSwitchClosedRev(*param);
+}
+CTR_Code c_TalonSRX_GetSensorPosition(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetSensorPosition(*param);
+}
+CTR_Code c_TalonSRX_GetSensorVelocity(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetSensorVelocity(*param);
+}
+CTR_Code c_TalonSRX_GetCurrent(void *handle, double *param)
+{
+  return ((CanTalonSRX*)handle)->GetCurrent(*param);
+}
+CTR_Code c_TalonSRX_GetBrakeIsEnabled(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetBrakeIsEnabled(*param);
+}
+CTR_Code c_TalonSRX_GetEncPosition(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetEncPosition(*param);
+}
+CTR_Code c_TalonSRX_GetEncVel(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetEncVel(*param);
+}
+CTR_Code c_TalonSRX_GetEncIndexRiseEvents(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetEncIndexRiseEvents(*param);
+}
+CTR_Code c_TalonSRX_GetQuadApin(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetQuadApin(*param);
+}
+CTR_Code c_TalonSRX_GetQuadBpin(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetQuadBpin(*param);
+}
+CTR_Code c_TalonSRX_GetQuadIdxpin(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetQuadIdxpin(*param);
+}
+CTR_Code c_TalonSRX_GetAnalogInWithOv(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetAnalogInWithOv(*param);
+}
+CTR_Code c_TalonSRX_GetAnalogInVel(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetAnalogInVel(*param);
+}
+CTR_Code c_TalonSRX_GetTemp(void *handle, double *param)
+{
+  return ((CanTalonSRX*)handle)->GetTemp(*param);
+}
+CTR_Code c_TalonSRX_GetBatteryV(void *handle, double *param)
+{
+  return ((CanTalonSRX*)handle)->GetBatteryV(*param);
+}
+CTR_Code c_TalonSRX_GetResetCount(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetResetCount(*param);
+}
+CTR_Code c_TalonSRX_GetResetFlags(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetResetFlags(*param);
+}
+CTR_Code c_TalonSRX_GetFirmVers(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetFirmVers(*param);
+}
+CTR_Code c_TalonSRX_GetPulseWidthPosition(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetPulseWidthPosition(*param);
+}
+CTR_Code c_TalonSRX_GetPulseWidthVelocity(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetPulseWidthVelocity(*param);
+}
+CTR_Code c_TalonSRX_GetPulseWidthRiseToRiseUs(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetPulseWidthRiseToRiseUs(*param);
+}
+CTR_Code c_TalonSRX_GetActTraj_IsValid(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetActTraj_IsValid(*param);
+}
+CTR_Code c_TalonSRX_GetActTraj_ProfileSlotSelect(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetActTraj_ProfileSlotSelect(*param);
+}
+CTR_Code c_TalonSRX_GetActTraj_VelOnly(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetActTraj_VelOnly(*param);
+}
+CTR_Code c_TalonSRX_GetActTraj_IsLast(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetActTraj_IsLast(*param);
+}
+CTR_Code c_TalonSRX_GetOutputType(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetOutputType(*param);
+}
+CTR_Code c_TalonSRX_GetHasUnderrun(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetHasUnderrun(*param);
+}
+CTR_Code c_TalonSRX_GetIsUnderrun(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetIsUnderrun(*param);
+}
+CTR_Code c_TalonSRX_GetNextID(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetNextID(*param);
+}
+CTR_Code c_TalonSRX_GetBufferIsFull(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetBufferIsFull(*param);
+}
+CTR_Code c_TalonSRX_GetCount(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetCount(*param);
+}
+CTR_Code c_TalonSRX_GetActTraj_Velocity(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetActTraj_Velocity(*param);
+}
+CTR_Code c_TalonSRX_GetActTraj_Position(void *handle, int *param)
+{
+  return ((CanTalonSRX*)handle)->GetActTraj_Position(*param);
+}
+CTR_Code c_TalonSRX_SetDemand(void *handle, int param)
+{
+  return ((CanTalonSRX*)handle)->SetDemand(param);
+}
+CTR_Code c_TalonSRX_SetOverrideLimitSwitchEn(void *handle, int param)
+{
+  return ((CanTalonSRX*)handle)->SetOverrideLimitSwitchEn(param);
+}
+CTR_Code c_TalonSRX_SetFeedbackDeviceSelect(void *handle, int param)
+{
+  return ((CanTalonSRX*)handle)->SetFeedbackDeviceSelect(param);
+}
+CTR_Code c_TalonSRX_SetRevMotDuringCloseLoopEn(void *handle, int param)
+{
+  return ((CanTalonSRX*)handle)->SetRevMotDuringCloseLoopEn(param);
+}
+CTR_Code c_TalonSRX_SetOverrideBrakeType(void *handle, int param)
+{
+  return ((CanTalonSRX*)handle)->SetOverrideBrakeType(param);
+}
+CTR_Code c_TalonSRX_SetModeSelect(void *handle, int param)
+{
+  return ((CanTalonSRX*)handle)->SetModeSelect(param);
+}
+CTR_Code c_TalonSRX_SetProfileSlotSelect(void *handle, int param)
+{
+  return ((CanTalonSRX*)handle)->SetProfileSlotSelect(param);
+}
+CTR_Code c_TalonSRX_SetRampThrottle(void *handle, int param)
+{
+  return ((CanTalonSRX*)handle)->SetRampThrottle(param);
+}
+CTR_Code c_TalonSRX_SetRevFeedbackSensor(void *handle, int param)
+{
+  return ((CanTalonSRX*)handle)->SetRevFeedbackSensor(param);
+}
+}
diff --git a/hal/lib/Athena/ctre/CtreCanNode.cpp b/hal/lib/Athena/ctre/CtreCanNode.cpp
index 18cd24b..0f190a5 100644
--- a/hal/lib/Athena/ctre/CtreCanNode.cpp
+++ b/hal/lib/Athena/ctre/CtreCanNode.cpp
@@ -18,20 +18,57 @@
 {

 	/* no need to do anything, we just use new API to poll last received message */

 }

-void CtreCanNode::RegisterTx(uint32_t arbId, uint32_t periodMs)

+/**

+ * Schedule a CAN Frame for periodic transmit.

+ * @param arbId 	CAN Frame Arbitration ID.  Set BIT31 for 11bit ids, otherwise we use 29bit ids.

+ * @param periodMs	Period to transmit CAN frame.  Pass 0 for one-shot, which also disables that ArbID's preceding periodic transmit.

+ * @param dlc 		Number of bytes to transmit (0 to 8).

+ * @param initialFrame	Ptr to the frame data to schedule for transmitting.  Passing null will result

+ *						in defaulting to zero data value.

+ */

+void CtreCanNode::RegisterTx(uint32_t arbId, uint32_t periodMs, uint32_t dlc, const uint8_t * initialFrame)

 {

 	int32_t status = 0;

-

+	if(dlc > 8)

+		dlc = 8;

 	txJob_t job = {0};

 	job.arbId = arbId;

 	job.periodMs = periodMs;

+	job.dlc = dlc;

+	if(initialFrame){

+		/* caller wants to specify original data */

+		memcpy(job.toSend, initialFrame, dlc);

+	}

 	_txJobs[arbId] = job;

 	FRC_NetworkCommunication_CANSessionMux_sendMessage(	job.arbId,

 														job.toSend,

-														8,

+														job.dlc,

 														job.periodMs,

 														&status);

 }

+/**

+ * Schedule a CAN Frame for periodic transmit.  Assume eight byte DLC and zero value for initial transmission.

+ * @param arbId 	CAN Frame Arbitration ID.  Set BIT31 for 11bit ids, otherwise we use 29bit ids.

+ * @param periodMs	Period to transmit CAN frame.  Pass 0 for one-shot, which also disables that ArbID's preceding periodic transmit.

+ */

+void CtreCanNode::RegisterTx(uint32_t arbId, uint32_t periodMs)

+{

+	RegisterTx(arbId,periodMs, 8, 0);

+}

+/**

+ * Remove a CAN frame Arbid to stop transmission.

+ * @param arbId 	CAN Frame Arbitration ID.  Set BIT31 for 11bit ids, otherwise we use 29bit ids.

+ */

+void CtreCanNode::UnregisterTx(uint32_t arbId)

+{

+	/* set period to zero */

+	ChangeTxPeriod(arbId, 0);

+	/* look and remove */

+	txJobs_t::iterator iter = _txJobs.find(arbId);

+	if(iter != _txJobs.end()) {

+		_txJobs.erase(iter);

+	}

+}

 timespec diff(const timespec & start, const timespec & end)

 {

 	timespec temp;

@@ -94,8 +131,34 @@
 	if(iter != _txJobs.end())

 		FRC_NetworkCommunication_CANSessionMux_sendMessage(	iter->second.arbId,

 															iter->second.toSend,

-															8,

+															iter->second.dlc,

 															iter->second.periodMs,

 															&status);

 }

+/**

+ * Change the transmit period of an already scheduled CAN frame.

+ * This keeps the frame payload contents the same without caller having to perform

+ * a read-modify-write.

+ * @param arbId 	CAN Frame Arbitration ID.  Set BIT31 for 11bit ids, otherwise we use 29bit ids.

+ * @param periodMs	Period to transmit CAN frame.  Pass 0 for one-shot, which also disables that ArbID's preceding periodic transmit.

+ * @return true if scheduled job was found and updated, false if there was no preceding job for the specified arbID.

+ */

+bool CtreCanNode::ChangeTxPeriod(uint32_t arbId, uint32_t periodMs)

+{

+	int32_t status = 0;

+	/* lookup the data bytes and period for this message */

+	txJobs_t::iterator iter = _txJobs.find(arbId);

+	if(iter != _txJobs.end()) {

+		/* modify th periodMs */

+		iter->second.periodMs = periodMs;

+		/* reinsert into scheduler with the same data bytes, only the period changed. */

+		FRC_NetworkCommunication_CANSessionMux_sendMessage(	iter->second.arbId,

+															iter->second.toSend,

+															iter->second.dlc,

+															iter->second.periodMs,

+															&status);

+		return true;

+	}

+	return false;

+}

 

diff --git a/hal/lib/Athena/ctre/PDP.cpp b/hal/lib/Athena/ctre/PDP.cpp
index cae2264..89abce1 100644
--- a/hal/lib/Athena/ctre/PDP.cpp
+++ b/hal/lib/Athena/ctre/PDP.cpp
@@ -11,10 +11,10 @@
 #define CONTROL_1		0x08041C00	/* PDP_Control_ClearStats */

 

 #define EXPECTED_RESPONSE_TIMEOUT_MS	(50)

-#define GET_STATUS1()		CtreCanNode::recMsg<PdpStatus1_t> rx = GetRx<PdpStatus1_t>(STATUS_1,EXPECTED_RESPONSE_TIMEOUT_MS)

-#define GET_STATUS2()		CtreCanNode::recMsg<PdpStatus2_t> rx = GetRx<PdpStatus2_t>(STATUS_2,EXPECTED_RESPONSE_TIMEOUT_MS)

-#define GET_STATUS3()		CtreCanNode::recMsg<PdpStatus3_t> rx = GetRx<PdpStatus3_t>(STATUS_3,EXPECTED_RESPONSE_TIMEOUT_MS)

-#define GET_STATUS_ENERGY()	CtreCanNode::recMsg<PDP_Status_Energy_t> rx = GetRx<PDP_Status_Energy_t>(STATUS_ENERGY,EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_STATUS1()		CtreCanNode::recMsg<PdpStatus1_t> rx = GetRx<PdpStatus1_t>(STATUS_1|GetDeviceNumber(),EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_STATUS2()		CtreCanNode::recMsg<PdpStatus2_t> rx = GetRx<PdpStatus2_t>(STATUS_2|GetDeviceNumber(),EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_STATUS3()		CtreCanNode::recMsg<PdpStatus3_t> rx = GetRx<PdpStatus3_t>(STATUS_3|GetDeviceNumber(),EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_STATUS_ENERGY()	CtreCanNode::recMsg<PDP_Status_Energy_t> rx = GetRx<PDP_Status_Energy_t>(STATUS_ENERGY|GetDeviceNumber(),EXPECTED_RESPONSE_TIMEOUT_MS)

 

 /* encoder/decoders */

 typedef struct _PdpStatus1_t{

diff --git a/hal/lib/Shared/HAL.cpp b/hal/lib/Shared/HAL.cpp
index 9781278..42582a9 100644
--- a/hal/lib/Shared/HAL.cpp
+++ b/hal/lib/Shared/HAL.cpp
@@ -3,6 +3,8 @@
 #include "FRC_NetworkCommunication/FRCComm.h"
 #include <cstring>
 
+extern "C" {
+
 int HALGetControlWord(HALControlWord *data)
 {
 	return FRC_NetworkCommunication_getControlWord((ControlWord_t*) data);
@@ -32,11 +34,32 @@
 {
 	return FRC_NetworkCommunication_getJoystickButtons(joystickNum, &buttons->buttons, &buttons->count);
 }
-
+/**
+ * Retrieve the Joystick Descriptor for particular slot
+ * @param desc [out] descriptor (data transfer object) to fill in.  desc is filled in regardless of success.
+ *                              In other words, if descriptor is not available, desc is filled in with default
+ *                              values matching the init-values in Java and C++ Driverstation for when caller
+ *                              requests a too-large joystick index.
+ *
+ * @return error code reported from Network Comm back-end.  Zero is good, nonzero is bad.
+ */
 int HALGetJoystickDescriptor(uint8_t joystickNum, HALJoystickDescriptor *desc)
 {
-	return FRC_NetworkCommunication_getJoystickDesc(joystickNum, &desc->isXbox, &desc->type, (char *)(&desc->name),
+	desc->isXbox = 0;
+	desc->type = -1;
+	desc->name[0] = '\0';
+	desc->axisCount = kMaxJoystickAxes; /* set to the desc->axisTypes's capacity */
+	desc->buttonCount = 0;
+	desc->povCount = 0;
+	int retval = FRC_NetworkCommunication_getJoystickDesc(joystickNum, &desc->isXbox, &desc->type, (char *)(&desc->name),
 		&desc->axisCount, (uint8_t *)&desc->axisTypes, &desc->buttonCount, &desc->povCount);
+	/* check the return, if there is an error and the RIOimage predates FRC2017, then axisCount needs to be cleared */
+	if(retval != 0)
+	{
+		/* set count to zero so downstream code doesn't decode invalid axisTypes. */
+		desc->axisCount = 0;
+	}
+	return retval;
 }
 
 int HALGetJoystickIsXbox(uint8_t joystickNum)
@@ -126,3 +149,5 @@
 {
 	FRC_NetworkCommunication_observeUserProgramTest();
 }
+
+}  // extern "C"
diff --git a/settings.gradle b/settings.gradle
index 9a43e3c..9c570c4 100644
--- a/settings.gradle
+++ b/settings.gradle
@@ -2,6 +2,10 @@
         'wpilibc',
         'wpilibcIntegrationTests',
         'wpilibj',
-        'wpilibjIntegrationTests',
+        'wpilibjIntegrationTests'
+
+if (hasProperty("makeSim")){
+include 'simulation',
         'simulation:JavaGazebo',
         'simulation:SimDS'
+}
diff --git a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Connection.java b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Connection.java
index 994c78f..8ab6fff 100644
--- a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Connection.java
+++ b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Connection.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package org.gazebosim.transport;
 
 import gazebo.msgs.GzPacket.Packet;
diff --git a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Msgs.java b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Msgs.java
index 5062408..cd20d40 100644
--- a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Msgs.java
+++ b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Msgs.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package org.gazebosim.transport;
 
 import gazebo.msgs.GzBool.Bool;
diff --git a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Node.java b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Node.java
index 455d452..0aaeeb5 100644
--- a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Node.java
+++ b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Node.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package org.gazebosim.transport;
 
 import gazebo.msgs.GzPacket.Packet;
diff --git a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Publisher.java b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Publisher.java
index ebf9749..fccc65d 100644
--- a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Publisher.java
+++ b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Publisher.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package org.gazebosim.transport;
 
 import java.io.IOException;
diff --git a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/PublisherRecord.java b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/PublisherRecord.java
index 90ab604..a49193f 100644
--- a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/PublisherRecord.java
+++ b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/PublisherRecord.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package org.gazebosim.transport;
 
 public interface PublisherRecord {
diff --git a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/RemotePublisherRecord.java b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/RemotePublisherRecord.java
index 83d290e..86adf16 100644
--- a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/RemotePublisherRecord.java
+++ b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/RemotePublisherRecord.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package org.gazebosim.transport;
 
 import gazebo.msgs.GzPublish.Publish;
diff --git a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/ServerCallback.java b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/ServerCallback.java
index b9a6576..c0a67a5 100644
--- a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/ServerCallback.java
+++ b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/ServerCallback.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package org.gazebosim.transport;
 
 import java.io.IOException;
diff --git a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Subscriber.java b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Subscriber.java
index 12770ee..a385e27 100644
--- a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Subscriber.java
+++ b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/Subscriber.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package org.gazebosim.transport;
 
 import gazebo.msgs.GzSubscribe.Subscribe;
diff --git a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/SubscriberCallback.java b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/SubscriberCallback.java
index 5ed5269..4dc63ba 100644
--- a/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/SubscriberCallback.java
+++ b/simulation/JavaGazebo/src/main/java/org/gazebosim/transport/SubscriberCallback.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package org.gazebosim.transport;
 
 public interface SubscriberCallback<T> {
diff --git a/simulation/README.md b/simulation/README.md
index eb58dd5..d171be7 100644
--- a/simulation/README.md
+++ b/simulation/README.md
@@ -1,29 +1,32 @@
-## Simulation Directory
+## Components and Location
 
-Observe the following directory structure
-
-.
-|-- frc_gazebo_plugins (contains Gazebo Plugins)
-|   |-- clock
-|   |-- dc_motor
-|   |-- encoder
-|   |-- gyro
-|   |-- plugins
-|   |-- pneumatic_piston
-|   |-- potentiometer
-|   |-- rangefinder
-|   |-- servo
-|
-|-- frcsim.bat (launches gazebo with model/plugin paths on windows)
-|-- frcsim.sh (launches gazebo with model/plugin paths on linux/mac)
-|-- install.sh (convenient linux script to install Eclipse, Eclipse Plugins, and Gazebo)
-|-- JavaGazebo (java library used by java simulation. Equivelant of the C++ gazebo_transport)
-|-- SimDS (linux driverstation)
+Simluation is a mix of wpilib and other components.
+The wpilib components are in their respective locations in the /wpilibc and /wpilibj directories.
 
 The gazbeo plugins are currently built with CMake.
 Eventually they will be built with gradle.
 
-All of this is delivered to students via the eclipse plugins
+## Simulation delivery and installation
+
+For 2016 FRCSim is only officially supported on Ubuntu 14.04 or greater.
+However it is possible on any platform that runs Gazebo.
+FRCSim is currently delivered via a zip file published by this project,
+and is available at first.wpi.edu/FRC/roborio/maven/PROMOTION_STATUS/edu/wpi/first/wpilib/simulation/simulation/1.0.0/simulation-1.0.0.zip
+where PROMOTION_STATUS is one of:
+- development (the latest commit merged into wpilib)
+- beta (used periodically before release)
+- release (used just before kick-off and possibly a few other times)
+- stable (used for old releases we want to keep around)
+
+The zip contains most of the contents of ~/wpilib/simulation, such as C++ libraries, jars, and scripts
+
+The exmple robot model files are seperate, and can be found under "file releases" on collabnet.
+
+All together you need eclipse, gazebo, those two zips, g++ 4.9, java8, and a few other small packages.
+See the frcsim-installer script or the screensteps on manual install for all the nitty-gritty details
+
+The frcsim-installer script is meant for quick and painless setup on Ubuntu 14.04, 15.04, or 15.10
+A manual install is a more tedious process, so this is an easy option for students.
 
 ## Building
-see the top level building.md
+See the top level README.md.
diff --git a/simulation/SimDS/build.gradle b/simulation/SimDS/build.gradle
index 0acaaee..58270b7 100644
--- a/simulation/SimDS/build.gradle
+++ b/simulation/SimDS/build.gradle
@@ -51,4 +51,14 @@
     group = 'WPILib'
     classifier = 'javadoc'
     from javadoc.destinationDir
-}
\ No newline at end of file
+}
+
+//we need to move the simulation jars to the install directory
+task copyJars(type: Copy) {
+    description = 'copy SimDS-all.jar to make simulation zip'
+    group = 'WPILib Simulation'
+    from shadowJar.archivePath
+    into "$simulationInstallDir/jar"
+}
+
+build.dependsOn shadowJar
diff --git a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/DS.java b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/DS.java
index bd12c41..d62958a 100644
--- a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/DS.java
+++ b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/DS.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package edu.wpi.first.wpilibj.simulation.ds;
 
 import java.awt.Dimension;
diff --git a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/EnableAction.java b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/EnableAction.java
index f847568..9751e74 100644
--- a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/EnableAction.java
+++ b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/EnableAction.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package edu.wpi.first.wpilibj.simulation.ds;
 
 import java.awt.event.ActionEvent;
diff --git a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/FakeJoystick.java b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/FakeJoystick.java
index 4831a27..b548930 100644
--- a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/FakeJoystick.java
+++ b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/FakeJoystick.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package edu.wpi.first.wpilibj.simulation.ds;
 
 import org.gazebosim.transport.Node;
diff --git a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/ISimJoystick.java b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/ISimJoystick.java
index 9263a1b..b9fb0ab 100644
--- a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/ISimJoystick.java
+++ b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/ISimJoystick.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package edu.wpi.first.wpilibj.simulation.ds;
 
 import org.gazebosim.transport.Node;
diff --git a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/JoystickList.java b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/JoystickList.java
index f598a3d..f1bd684 100644
--- a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/JoystickList.java
+++ b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/JoystickList.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package edu.wpi.first.wpilibj.simulation.ds;
 
 import java.awt.datatransfer.DataFlavor;
diff --git a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/JoystickProvider.java b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/JoystickProvider.java
index 4c22320..80119d0 100644
--- a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/JoystickProvider.java
+++ b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/JoystickProvider.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package edu.wpi.first.wpilibj.simulation.ds;
 
 import java.util.ArrayList;
diff --git a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/Main.java b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/Main.java
index 2f5188a..b93bdd0 100644
--- a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/Main.java
+++ b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/Main.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package edu.wpi.first.wpilibj.simulation.ds;
 
 import gazebo.msgs.GzFloat64.Float64;
diff --git a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/ModeAction.java b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/ModeAction.java
index 532ef67..362e8c6 100644
--- a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/ModeAction.java
+++ b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/ModeAction.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package edu.wpi.first.wpilibj.simulation.ds;
 
 import java.awt.event.ActionEvent;
diff --git a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/RefreshAction.java b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/RefreshAction.java
index 5f264e0..6320aac 100644
--- a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/RefreshAction.java
+++ b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/RefreshAction.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package edu.wpi.first.wpilibj.simulation.ds;
 
 import java.awt.event.ActionEvent;
diff --git a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/SimJoystick.java b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/SimJoystick.java
index 23794ca..7239cac 100644
--- a/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/SimJoystick.java
+++ b/simulation/SimDS/src/main/java/edu/wpi/first/wpilibj/simulation/ds/SimJoystick.java
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 package edu.wpi.first.wpilibj.simulation.ds;
 
 import gazebo.msgs.GzJoystick.Joystick;
diff --git a/simulation/build.gradle b/simulation/build.gradle
new file mode 100644
index 0000000..c0d1ff0
--- /dev/null
+++ b/simulation/build.gradle
@@ -0,0 +1,35 @@
+apply plugin: 'java'
+apply plugin: 'maven-publish'
+
+publishing {
+    publications {
+        simulation(MavenPublication) {
+            artifact zip
+            groupId 'edu.wpi.first.wpilib.simulation'
+            artifactId 'simulation'
+            version '1.0.0'
+        }
+    }
+
+    setupWpilibRepo(it)
+}
+
+task copy_resources(type: Copy) {
+    description = 'copy gz_msgs and install_resources to make simulation zip'
+    group = 'WPILib Simulation'
+    into ('gz_msgs') {
+        from 'gz_msgs'
+    }
+    into "$simulationInstallDir"
+    from 'install_resources'
+}
+
+task zip(type: Zip, dependsOn: [copy_resources,
+        ':wpilibc:wpilibcSimCopy',
+        ':simulation:SimDS:copyJars',
+        ':wpilibj:copyJars']) {
+    description = 'zip of all the resources for simulation'
+    group = 'WPILib Simulation'
+    baseName = 'simulation-trusty'
+    from "$simulationInstallDir"
+}
diff --git a/simulation/frc_gazebo_plugins/CMakeLists.txt b/simulation/frc_gazebo_plugins/CMakeLists.txt
index 1d45789..e3574dd 100644
--- a/simulation/frc_gazebo_plugins/CMakeLists.txt
+++ b/simulation/frc_gazebo_plugins/CMakeLists.txt
@@ -12,8 +12,6 @@
 	rangefinder
 	servo)
 
-set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/plugins)
-
 link_directories(${GAZEBO_LIBRARY_DIRS})
 
 foreach(PLUGIN ${PLUGINS})
@@ -29,7 +27,11 @@
 	endif()
 
 	target_link_libraries(${PLUGIN} gz_msgs ${GAZEBO_LIBRARIES} ${Boost_LIBRARIES})
-
-  install(TARGETS ${PLUGIN} DESTINATION $ENV{HOME}/wpilib/simulation/plugins)
+  set_target_properties(${PLUGIN}
+    PROPERTIES
+    LIBRARY_OUTPUT_DIRECTORY ${SIMULATION_INSTALL_DIR}/plugins)
 
 endforeach()
+
+# create a dummy target the depends on all the plugins
+add_custom_target(${PROJECT_NAME} DEPENDS ${PLUGINS})
diff --git a/simulation/frc_gazebo_plugins/clock/src/clock.cpp b/simulation/frc_gazebo_plugins/clock/src/clock.cpp
index 32cd3b7..0297943 100644
--- a/simulation/frc_gazebo_plugins/clock/src/clock.cpp
+++ b/simulation/frc_gazebo_plugins/clock/src/clock.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "clock.h"
 
 GZ_REGISTER_MODEL_PLUGIN(Clock)
diff --git a/simulation/frc_gazebo_plugins/clock/src/clock.h b/simulation/frc_gazebo_plugins/clock/src/clock.h
index 4590471..403fcb1 100644
--- a/simulation/frc_gazebo_plugins/clock/src/clock.h
+++ b/simulation/frc_gazebo_plugins/clock/src/clock.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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
 
 
diff --git a/simulation/frc_gazebo_plugins/dc_motor/src/dc_motor.cpp b/simulation/frc_gazebo_plugins/dc_motor/src/dc_motor.cpp
index 0b4bbab..1074d70 100644
--- a/simulation/frc_gazebo_plugins/dc_motor/src/dc_motor.cpp
+++ b/simulation/frc_gazebo_plugins/dc_motor/src/dc_motor.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "dc_motor.h"
 
 GZ_REGISTER_MODEL_PLUGIN(DCMotor)
diff --git a/simulation/frc_gazebo_plugins/dc_motor/src/dc_motor.h b/simulation/frc_gazebo_plugins/dc_motor/src/dc_motor.h
index 22d70be..d162ff8 100644
--- a/simulation/frc_gazebo_plugins/dc_motor/src/dc_motor.h
+++ b/simulation/frc_gazebo_plugins/dc_motor/src/dc_motor.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "simulation/gz_msgs/msgs.h"
diff --git a/simulation/frc_gazebo_plugins/encoder/src/encoder.cpp b/simulation/frc_gazebo_plugins/encoder/src/encoder.cpp
index aea246f..0742edd 100644
--- a/simulation/frc_gazebo_plugins/encoder/src/encoder.cpp
+++ b/simulation/frc_gazebo_plugins/encoder/src/encoder.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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"
 
 GZ_REGISTER_MODEL_PLUGIN(Encoder)
diff --git a/simulation/frc_gazebo_plugins/encoder/src/encoder.h b/simulation/frc_gazebo_plugins/encoder/src/encoder.h
index 728341d..f3d3ea1 100644
--- a/simulation/frc_gazebo_plugins/encoder/src/encoder.h
+++ b/simulation/frc_gazebo_plugins/encoder/src/encoder.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "simulation/gz_msgs/msgs.h"
diff --git a/simulation/frc_gazebo_plugins/gyro/src/gyro.cpp b/simulation/frc_gazebo_plugins/gyro/src/gyro.cpp
index e918bbb..0895c6a 100644
--- a/simulation/frc_gazebo_plugins/gyro/src/gyro.cpp
+++ b/simulation/frc_gazebo_plugins/gyro/src/gyro.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "gyro.h"
 
 
diff --git a/simulation/frc_gazebo_plugins/gyro/src/gyro.h b/simulation/frc_gazebo_plugins/gyro/src/gyro.h
index fee48b3..29f62a9 100644
--- a/simulation/frc_gazebo_plugins/gyro/src/gyro.h
+++ b/simulation/frc_gazebo_plugins/gyro/src/gyro.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "simulation/gz_msgs/msgs.h"
diff --git a/simulation/frc_gazebo_plugins/limit_switch/src/external_limit_switch.cpp b/simulation/frc_gazebo_plugins/limit_switch/src/external_limit_switch.cpp
index 67c2c7a..c871212 100644
--- a/simulation/frc_gazebo_plugins/limit_switch/src/external_limit_switch.cpp
+++ b/simulation/frc_gazebo_plugins/limit_switch/src/external_limit_switch.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "external_limit_switch.h"
 
 
diff --git a/simulation/frc_gazebo_plugins/limit_switch/src/external_limit_switch.h b/simulation/frc_gazebo_plugins/limit_switch/src/external_limit_switch.h
index 573e93b..08e9198 100644
--- a/simulation/frc_gazebo_plugins/limit_switch/src/external_limit_switch.h
+++ b/simulation/frc_gazebo_plugins/limit_switch/src/external_limit_switch.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "switch.h"
diff --git a/simulation/frc_gazebo_plugins/limit_switch/src/internal_limit_switch.cpp b/simulation/frc_gazebo_plugins/limit_switch/src/internal_limit_switch.cpp
index 3b6d7de..b410ca5 100644
--- a/simulation/frc_gazebo_plugins/limit_switch/src/internal_limit_switch.cpp
+++ b/simulation/frc_gazebo_plugins/limit_switch/src/internal_limit_switch.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "internal_limit_switch.h"
 
 InternalLimitSwitch::InternalLimitSwitch(physics::ModelPtr model, sdf::ElementPtr sdf) {
diff --git a/simulation/frc_gazebo_plugins/limit_switch/src/internal_limit_switch.h b/simulation/frc_gazebo_plugins/limit_switch/src/internal_limit_switch.h
index bf08cbb..b7b007a 100644
--- a/simulation/frc_gazebo_plugins/limit_switch/src/internal_limit_switch.h
+++ b/simulation/frc_gazebo_plugins/limit_switch/src/internal_limit_switch.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "switch.h"
diff --git a/simulation/frc_gazebo_plugins/limit_switch/src/limit_switch.cpp b/simulation/frc_gazebo_plugins/limit_switch/src/limit_switch.cpp
index f32e65c..88f8846 100644
--- a/simulation/frc_gazebo_plugins/limit_switch/src/limit_switch.cpp
+++ b/simulation/frc_gazebo_plugins/limit_switch/src/limit_switch.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "limit_switch.h"
 
 GZ_REGISTER_MODEL_PLUGIN(LimitSwitch)
diff --git a/simulation/frc_gazebo_plugins/limit_switch/src/limit_switch.h b/simulation/frc_gazebo_plugins/limit_switch/src/limit_switch.h
index 4d590d5..17ae8cf 100644
--- a/simulation/frc_gazebo_plugins/limit_switch/src/limit_switch.h
+++ b/simulation/frc_gazebo_plugins/limit_switch/src/limit_switch.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "simulation/gz_msgs/msgs.h"
diff --git a/simulation/frc_gazebo_plugins/limit_switch/src/switch.h b/simulation/frc_gazebo_plugins/limit_switch/src/switch.h
index d7d5aac..8c204a3 100644
--- a/simulation/frc_gazebo_plugins/limit_switch/src/switch.h
+++ b/simulation/frc_gazebo_plugins/limit_switch/src/switch.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 Switch {
diff --git a/simulation/frc_gazebo_plugins/pneumatic_piston/src/pneumatic_piston.cpp b/simulation/frc_gazebo_plugins/pneumatic_piston/src/pneumatic_piston.cpp
index 11cf432..4dbe57d 100644
--- a/simulation/frc_gazebo_plugins/pneumatic_piston/src/pneumatic_piston.cpp
+++ b/simulation/frc_gazebo_plugins/pneumatic_piston/src/pneumatic_piston.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
 #ifdef _WIN32
   // Ensure that Winsock2.h is included before Windows.h, which can get
   // pulled in by anybody (e.g., Boost).
diff --git a/simulation/frc_gazebo_plugins/pneumatic_piston/src/pneumatic_piston.h b/simulation/frc_gazebo_plugins/pneumatic_piston/src/pneumatic_piston.h
index 8bfb7b1..488d9f3 100644
--- a/simulation/frc_gazebo_plugins/pneumatic_piston/src/pneumatic_piston.h
+++ b/simulation/frc_gazebo_plugins/pneumatic_piston/src/pneumatic_piston.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "simulation/gz_msgs/msgs.h"
diff --git a/simulation/frc_gazebo_plugins/potentiometer/src/potentiometer.cpp b/simulation/frc_gazebo_plugins/potentiometer/src/potentiometer.cpp
index f7f4251..0b0ad54 100644
--- a/simulation/frc_gazebo_plugins/potentiometer/src/potentiometer.cpp
+++ b/simulation/frc_gazebo_plugins/potentiometer/src/potentiometer.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
 #ifdef _WIN32
   // Ensure that Winsock2.h is included before Windows.h, which can get
   // pulled in by anybody (e.g., Boost).
diff --git a/simulation/frc_gazebo_plugins/potentiometer/src/potentiometer.h b/simulation/frc_gazebo_plugins/potentiometer/src/potentiometer.h
index 422ff20..5cb96cd 100644
--- a/simulation/frc_gazebo_plugins/potentiometer/src/potentiometer.h
+++ b/simulation/frc_gazebo_plugins/potentiometer/src/potentiometer.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 <simulation/gz_msgs/msgs.h>
diff --git a/simulation/frc_gazebo_plugins/rangefinder/src/rangefinder.cpp b/simulation/frc_gazebo_plugins/rangefinder/src/rangefinder.cpp
index c91cfb2..dd76107 100644
--- a/simulation/frc_gazebo_plugins/rangefinder/src/rangefinder.cpp
+++ b/simulation/frc_gazebo_plugins/rangefinder/src/rangefinder.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
 #ifdef _WIN32
   // Ensure that Winsock2.h is included before Windows.h, which can get
   // pulled in by anybody (e.g., Boost).
diff --git a/simulation/frc_gazebo_plugins/rangefinder/src/rangefinder.h b/simulation/frc_gazebo_plugins/rangefinder/src/rangefinder.h
index f9a7ef4..a205368 100644
--- a/simulation/frc_gazebo_plugins/rangefinder/src/rangefinder.h
+++ b/simulation/frc_gazebo_plugins/rangefinder/src/rangefinder.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 <simulation/gz_msgs/msgs.h>
diff --git a/simulation/frc_gazebo_plugins/servo/src/servo.cpp b/simulation/frc_gazebo_plugins/servo/src/servo.cpp
index 8298280..e1b61f3 100644
--- a/simulation/frc_gazebo_plugins/servo/src/servo.cpp
+++ b/simulation/frc_gazebo_plugins/servo/src/servo.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
 #ifdef _WIN32
   // Ensure that Winsock2.h is included before Windows.h, which can get
   // pulled in by anybody (e.g., Boost).
diff --git a/simulation/frc_gazebo_plugins/servo/src/servo.h b/simulation/frc_gazebo_plugins/servo/src/servo.h
index a998761..dd6d18b 100644
--- a/simulation/frc_gazebo_plugins/servo/src/servo.h
+++ b/simulation/frc_gazebo_plugins/servo/src/servo.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "simulation/gz_msgs/msgs.h"
diff --git a/simulation/frcsim-installer.sh b/simulation/frcsim-installer.sh
new file mode 100755
index 0000000..c82bc2a
--- /dev/null
+++ b/simulation/frcsim-installer.sh
@@ -0,0 +1,308 @@
+#!/bin/bash
+
+function check-environment {
+  # Ensure root access
+  if [ "$(id -u)" != "0" ]; then
+    echo "*** This script must be run as root!" 1>&2
+    echo "*** Make sure that you followed the instructions properly." 1>&2
+    install-fail
+  fi
+
+  # Make sure that we're on Ubuntu.
+  if [ "$(lsb_release -is)" != "Ubuntu" ]; then
+    if [ "$(lsb_release -is)" = "" ]; then
+      echo "*** Distributions other than Ubuntu (such as yours, probably) are not supported." 1>&2
+    else
+      echo "*** Distributions other than Ubuntu (such as $(lsb_release -is)) are not supported." 1>&2
+    fi
+    echo "*** This means that the install will likely fail." 1>&2
+    echo "*** Continue anyway? (y/n)" 1>&2
+    read CONT
+    if [ "$CONT" != "y" -a "$CONT" != "Y" ]; then
+      install-fail
+    fi
+  fi
+
+  # Make sure that we have /etc/apt/sources.list.d available.
+  if [ ! -e /etc/apt/sources.list.d ]; then
+    echo "*** Cannot find /etc/apt/sources.list.d - is apt installed?"
+    install-fail
+  fi
+
+  # Make sure that apt-key is installed.
+  if ! which apt-key >/dev/null; then
+    echo "*** You don't appear to have apt-key installed." 1>&2
+    echo "*** Please install apt and run the script again." 1>&2
+    install-fail
+  fi
+
+  # Make sure that apt-get is installed.
+  if ! which apt-get >/dev/null; then
+    echo "*** You don't appear to have apt-get installed." 1>&2
+    echo "*** Please install apt and run the script again." 1>&2
+    install-fail
+  fi
+
+  # Make sure that we have internet access.
+  if ! ping 8.8.8.8 -c 1 >/dev/null; then
+    echo "*** You don't appear to be able to access the internet! (Can't ping 8.8.8.8)" 1>&2
+    install-fail
+  fi
+
+  # Make sure that wget is installed.
+  if ! which wget >/dev/null; then
+    echo "*** You don't appear to have wget installed." 1>&2
+    echo "*** Install? (y/n)" 1>&2
+    read CONT
+    if [ "$CONT" != "y" -a "$CONT" != "Y" ]; then
+      install-fail
+    fi
+    apt-get install wget -y
+  fi
+
+  # Make sure that python is installed
+  if ! which python >/dev/null; then
+    echo "*** You don't appear to have python installed." 1>&2
+    echo "*** Install? (y/n)" 1>&2
+    read CONT
+    if [ "$CONT" != "y" -a "$CONT" != "Y" ]; then
+      install-fail
+    fi
+    apt-get install python -y
+  fi
+
+  # Make sure that unzip is installed
+  if ! which unzip >/dev/null; then
+    echo "*** You don't appear to have unzip installed." 1>&2
+    echo "*** Install? (y/n)" 1>&2
+    read CONT
+    if [ "$CONT" != "y" -a "$CONT" != "Y" ]; then
+      install-fail
+    fi
+    apt-get install unzip -y
+  fi
+
+  # Make sure that app-apt-repository is installed
+  if ! which add-apt-repository >/dev/null; then
+    echo "*** You don't appear to have all apt commands installed." 1>&2
+    echo "*** Install? (y/n)" 1>&2
+    read CONT
+    if [ "$CONT" != "y" -a "$CONT" != "Y" ]; then
+      install-fail
+    fi
+    apt-get install software-properties-common -y
+  fi
+}
+
+function remove-frcsim {
+  echo "*** Remove Gazebo package entry too? (y/n)" 1>&2
+  read CONT
+  if [ "$CONT" == "y" -o "$CONT" == "Y" ]; then
+  rm -f /etc/apt/sources.list.d/gazebo-latest.list
+  fi
+
+  apt-get remove --auto-remove libgazebo6-dev gazebo6 g++-4.9 openjdk-8-jdk
+  rm -rf /opt/eclipse
+  rm -f /usr/share/applications/frcsim.desktop /usr/share/applications/eclipse.desktop /usr/share/applications/sim_ds.desktop
+  rm -f /usr/bin/frcism /usr/bin/sim_ds /usr/bin/eclipse
+  rm -rf ~/wpilib/simulation
+
+  add-apt-repository --remove ppa:openjdk-r/ppa -y
+  add-apt-repository --remove ppa:ubuntu-toolchain-r/test -y
+}
+
+function install-eclipse-plugins {
+  #valid URLs can have promotion status of any of the following
+  # - development (used for most recent merge into wpilib)
+  # - beta
+  # - release
+  # - stable
+
+  #this file is published to maven repo by simulation/build.gradle
+  if ! (wget -O /tmp/simulation.zip http://first.wpi.edu/FRC/roborio/maven/$PROMOTION_STATUS/edu/wpi/first/wpilib/simulation/simulation/1.0.0/simulation-1.0.0.zip)
+  then
+    echo "***could not download wpilib simulation plugins, wrong URL probably***"
+    echo "promotion status = $PROMOTION_STATUS"
+    echo "url = http://first.wpi.edu/FRC/roborio/maven/$PROMOTION_STATUS/edu/wpi/first/wpilib/simulation/simulation/1.0.0/simulation-1.0.0.zip"
+    install-fail
+  fi
+
+  mkdir -p ~/wpilib/simulation
+  unzip /tmp/simulation.zip -d ~/wpilib/simulation
+  rm -f /usr/bin/frcsim /usr/bin/sim_ds
+  ln -s ~/wpilib/simulation/frcsim /usr/bin/frcsim
+  ln -s ~/wpilib/simulation/sim_ds /usr/bin/sim_ds
+}
+
+function install-eclipse {
+  if ! (wget -O /tmp/eclipse.tar.gz http://eclipse.mirror.rafal.ca/technology/epp/downloads/release/mars/1/eclipse-cpp-mars-1-linux-gtk-x86_64.tar.gz)
+  then
+    echo "***could not download eclipse, wrong URL probably***"
+    install-fail
+  fi
+
+  tar -xf /tmp/eclipse.tar.gz -C /opt
+  rm -f /usr/bin/eclipse
+  ln -s /opt/eclipse/eclipse /usr/bin/eclipse
+}
+
+function install-desktops {
+  # desktop files allow ubuntu (unity) users to "search" for their programs in the sidebar
+  mv ~/wpilib/simulation/eclipse.desktop /usr/share/applications/eclipse.desktop
+  mv ~/wpilib/simulation/frcsim.desktop /usr/share/applications/frcsim.desktop
+  mv ~/wpilib/simulation/sim_ds.desktop /usr/share/applications/sim_ds.desktop
+  mkdir -p /usr/share/icons/sim_ds
+  mv ~/wpilib/simulation/sim_ds_logo.png /usr/share/icons/sim_ds/sim_ds_logo.png
+}
+
+function install-gz_msgs {
+  # gz_msgs is built on the end-user system
+  # that way the versions of protobuf will match whatever the default for that platform is
+  cd ~/wpilib/simulation/gz_msgs
+  mkdir build
+  cd build
+  cmake ..
+  make
+  make install
+  chmod u+x ~/wpilib/simulation/lib/libgz_msgs.so
+}
+
+function install-toolchain {
+  # older version of ubuntu like 14.04 don't have the versions of g++ and java we need
+  # we can add some very reliable PPAs to get them however
+  if [[ "`lsb_release -rs`" == "14.04" ]]
+  then
+    echo "*** You're using `lsb_release -r`, you will need additional repositories***"
+    echo "*** Install? (y/n)" 1>&2
+    read CONT
+    if [ "$CONT" != "y" -a "$CONT" != "Y" ]; then
+      install-fail
+    fi
+    add-apt-repository ppa:openjdk-r/ppa -y
+    add-apt-repository ppa:ubuntu-toolchain-r/test -y
+  fi
+  if [[ "`lsb_release -rs`" == "15.04" ]]
+  then
+    echo "*** You're using `lsb_release -r`, you will need additional repositories***"
+    echo "*** Install? (y/n)" 1>&2
+    read CONT
+    if [ "$CONT" != "y" -a "$CONT" != "Y" ]; then
+      install-fail
+    fi
+    add-apt-repository ppa:openjdk-r/ppa -y
+  fi
+
+  # Update and install dependencies
+  if ! apt-get update
+  then
+    echo "*** Could not resynchronize package index files." 1>&2
+    echo "*** Are you running another update or install?" 1>&2
+    install-fail
+  fi
+
+  apt-get install cmake libprotoc-dev libprotobuf-dev protobuf-compiler g++-4.9 openjdk-8-jdk -y
+  rm -f /usr/bin/g++
+  ln -s /usr/bin/g++-4.9 /usr/bin/g++
+}
+
+function install-models {
+  # this zip file is made by hand. A better option to add models is to use the gazebo repository
+  if ! (wget -O /tmp/models.zip https://usfirst.collab.net/sf/frs/do/downloadFile/projects.wpilib/frs.simulation.frcsim_gazebo_models/frs1160?)
+  then
+    echo "*** failed to download models. Check your internet connection! ***"
+    install-fail
+  fi
+
+  unzip /tmp/models.zip -d /tmp
+  mv /tmp/frcsim-gazebo-models/models ~/wpilib/simulation/models
+  mv /tmp/frcsim-gazebo-models/worlds ~/wpilib/simulation/worlds
+}
+
+function install-frcsim {
+  check-environment
+
+  # Add Gazebo Repository and Key
+  if ! echo "deb http://packages.osrfoundation.org/gazebo/ubuntu `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-latest.list
+  then
+    echo "*** Cannot add Gazebo repository!" 1>&2
+    install-fail
+  fi
+  if ! (wget http://packages.osrfoundation.org/gazebo.key -O - | apt-key add -)
+  then
+    echo "*** Cannot add Gazebo repository key!" 1>&2
+    if ! ping packages.osrfoundation.org -c 1 >/dev/null; then
+      echo "*** The package host for Gazebo appears to be down. Try again later." 1>&2
+    fi
+    install-fail
+  fi
+
+  install-toolchain
+
+  if ! apt-get install -y libgazebo6-dev gazebo6
+  then
+    echo "*** Could not install frcsim packages. See above output for details." 1>&2
+    echo "*** Are you running another update or install?" 1>&2
+    install-fail
+  fi
+
+  install-eclipse-plugins
+  install-gz_msgs
+  install-eclipse
+  install-desktops
+  install-models
+
+  change-ownership
+
+  # Done
+  echo "Installation Finished!!"
+}
+
+function install-fail {
+  echo "***INSTALLATION UNSUCCESSFUL***"
+  echo "***Check the output about for anything that looks like errors***"
+  echo "Please comment on the following to tutorial if you're unable to resolve your problem:"
+  echo "https://wpilib.screenstepslive.com/s/4485/m/23353/l/478421-installing-frcsim-with-a-script-ubuntu"
+  exit 1
+}
+
+function change-ownership {
+  chown -R $NON_SUDO_USER:$NON_SUDO_USER ~/wpilib
+}
+
+if [ "$1" == "INSTALL-ROOT" ]
+then
+
+  if [ -z "$2" ]
+  then
+    echo "*** Could not set user ~/wpilib ownership to empty user***"
+    install-fail
+  else
+    NON_SUDO_USER="$2"
+  fi
+
+  if [ -z "$3" ]
+  then
+    PROMOTION_STATUS="release"
+  else
+    PROMOTION_STATUS="$3"
+  fi
+
+  install-frcsim
+
+elif [ "$1" == "INSTALL" ]
+then
+  NON_SUDO_USER="$USER"
+  PROMOTION_STATUS="$2"
+  SUDO_ASKPASS=/usr/bin/ssh-askpass sudo bash -c "$0 INSTALL-ROOT $NON_SUDO_USER $PROMOTION_STATUS"
+elif [ "$1" == "REMOVE-ROOT" ]
+then
+  remove-frcsim
+elif [ "$1" == "REMOVE" ]
+then
+  NON_SUDO_USER="$USER"
+  SUDO_ASKPASS=/usr/bin/ssh-askpass sudo bash -c "$0 REMOVE-ROOT $NON_SUDO_USER $PROMOTION_STATUS"
+else
+  echo "***This script requires an argument!***"
+  echo "***Run ./frcsim_installer.sh INSTALL to install***"
+  echo "***The other option is REMOVE"
+fi
diff --git a/simulation/frcsim.sh b/simulation/frcsim.sh
deleted file mode 100755
index a923f53..0000000
--- a/simulation/frcsim.sh
+++ /dev/null
@@ -1,5 +0,0 @@
-#!/bin/bash
-export GAZEBO_PLUGIN_PATH="${GAZEBO_PLUGIN_PATH}:${HOME}/wpilib/simulation/plugins"
-export GAZEBO_MODEL_PATH="${GAZEBO_MODEL_PATH}:${HOME}/wpilib/simulation/models"
-export LD_LIBRARY_PATH="${LD_LIBRARY_PATH}:${HOME}/wpilib/simulation/plugins"
-gazebo $@
diff --git a/simulation/gz_msgs/CMakeLists.txt b/simulation/gz_msgs/CMakeLists.txt
index 17ecf5c..5e79a8b 100644
--- a/simulation/gz_msgs/CMakeLists.txt
+++ b/simulation/gz_msgs/CMakeLists.txt
@@ -1,6 +1,25 @@
-cmake_minimum_required(VERSION 2.8)
+Cmake_minimum_required(VERSION 2.8)
 project(gz_msgs)
 
+#copied from GazeboUtils.cmake
+macro (APPEND_TO_CACHED_STRING _string _cacheDesc)
+  FOREACH (newItem ${ARGN})
+    SET (${_string} "${${_string}} ${newItem}" CACHE INTERNAL ${_cacheDesc} FORCE)
+  ENDFOREACH (newItem ${ARGN})
+endmacro (APPEND_TO_CACHED_STRING)
+
+find_package(Protobuf REQUIRED)
+
+if (NOT PROTOBUF_FOUND)
+	MESSAGE ("Missing: Google Protobuf (libprotobuf-dev)")
+endif()
+if (NOT PROTOBUF_PROTOC_EXECUTABLE)
+	MESSAGE ( "Missing: Google Protobuf Compiler (protobuf-compiler)")
+endif()
+if (NOT PROTOBUF_PROTOC_LIBRARY)
+	MESSAGE ("Missing: Google Protobuf Compiler Library (libprotoc-dev)")
+endif()
+
 #list all proto files used
 get_filename_component(PROTO_DIR src/main/proto ABSOLUTE)
 set(msgs
@@ -62,3 +81,9 @@
 endif()
 
 target_link_libraries(${PROJECT_NAME} ${PROTOBUF_LIBRARIES})
+set_target_properties(${PROJECT_NAME} PROPERTIES INSTALL_RPATH "$ENV{HOME}/wpilib/simulation/lib")
+
+install(TARGETS ${PROJECT_NAME}
+  DESTINATION "$ENV{HOME}/wpilib/simulation/lib")
+install(DIRECTORY "${GZ_MSGS_INCLUDE_DIR}/simulation"
+  DESTINATION "$ENV{HOME}/wpilib/simulation/include")
diff --git a/simulation/gz_msgs/README.md b/simulation/gz_msgs/README.md
index 203457d..74266c3 100644
--- a/simulation/gz_msgs/README.md
+++ b/simulation/gz_msgs/README.md
@@ -1,6 +1,19 @@
 Building gz_msgs
 ================
 
-Currently uses cmake.
-This is build as a part of the whole cmake project.
-see top level building.md for detail
+gz_msgs currently uses cmake, is built on the end-users computer.
+This allows us to support various versions of protobuf (2.5 on Ubuntu 14.04, 2.6 on Ubuntu 15.10)
+
+To build, run the following commands in the ~/wpilib/simulation/gz_msgs directory.
+If that directory doesn't exist, it means you haven't installed correctly.
+
+If you're a developer for wpilib, you will need to unzip the simulation.zip file you published into ~/releases.
+If you are a student using FRCSim, you should have downloaded that zip when you installed frcsim.
+
+    mkdir build
+    cd build
+    cmake ..
+    make
+    make install
+
+If you are installing FRCSim with the script, then this *should* have be done for you.
diff --git a/simulation/install_resources/eclipse.desktop b/simulation/install_resources/eclipse.desktop
new file mode 100644
index 0000000..c6d8a86
--- /dev/null
+++ b/simulation/install_resources/eclipse.desktop
@@ -0,0 +1,7 @@
+[Desktop Entry]
+Name=Eclipse
+Exec=/usr/bin/eclipse
+Icon=/opt/eclipse/icon.xpm
+Type=Application
+Categories=Development;Education;Science;
+StartupNotify=true
diff --git a/simulation/install_resources/frcsim b/simulation/install_resources/frcsim
new file mode 100755
index 0000000..f8d6560
--- /dev/null
+++ b/simulation/install_resources/frcsim
@@ -0,0 +1,5 @@
+#!/bin/bash
+export GAZEBO_PLUGIN_PATH="${HOME}/wpilib/simulation/plugins:${GAZEBO_PLUGIN_PATH}"
+export GAZEBO_MODEL_PATH="${HOME}/wpilib/simulation/models:${GAZEBO_MODEL_PATH}"
+export LD_LIBRARY_PATH="${HOME}/wpilib/simulation/plugins:${HOME}/wpilib/simulation/lib:${LD_LIBRARY_PATH}"
+gazebo --verbose $@
diff --git a/simulation/install_resources/frcsim.desktop b/simulation/install_resources/frcsim.desktop
new file mode 100644
index 0000000..6434d9c
--- /dev/null
+++ b/simulation/install_resources/frcsim.desktop
@@ -0,0 +1,9 @@
+[Desktop Entry]
+Name=FRCSim
+Keywords=frcsim,gazebo
+Exec=/usr/bin/frcsim
+Icon=gazebo
+Type=Application
+StartupNotify=true
+Terminal=false
+Categories=Development;IDE;Java;Education;Science
diff --git a/simulation/install_resources/jar/jinput-2.0.5.jar b/simulation/install_resources/jar/jinput-2.0.5.jar
new file mode 100644
index 0000000..2081334
--- /dev/null
+++ b/simulation/install_resources/jar/jinput-2.0.5.jar
Binary files differ
diff --git a/simulation/install_resources/jar/jinput-platform-2.0.5-natives-linux.jar b/simulation/install_resources/jar/jinput-platform-2.0.5-natives-linux.jar
new file mode 100644
index 0000000..6423d54
--- /dev/null
+++ b/simulation/install_resources/jar/jinput-platform-2.0.5-natives-linux.jar
Binary files differ
diff --git a/simulation/install_resources/lib/libjinput-linux.so b/simulation/install_resources/lib/libjinput-linux.so
new file mode 100755
index 0000000..dba9e59
--- /dev/null
+++ b/simulation/install_resources/lib/libjinput-linux.so
Binary files differ
diff --git a/simulation/install_resources/lib/libjinput-linux64.so b/simulation/install_resources/lib/libjinput-linux64.so
new file mode 100755
index 0000000..8b5f9d8
--- /dev/null
+++ b/simulation/install_resources/lib/libjinput-linux64.so
Binary files differ
diff --git a/simulation/install_resources/sim_ds b/simulation/install_resources/sim_ds
new file mode 100755
index 0000000..4ea26de
--- /dev/null
+++ b/simulation/install_resources/sim_ds
@@ -0,0 +1 @@
+java -Djava.library.path=${HOME}/wpilib/simulation/lib -jar ~/wpilib/simulation/jar/SimDS-all.jar
diff --git a/simulation/install_resources/sim_ds.desktop b/simulation/install_resources/sim_ds.desktop
new file mode 100644
index 0000000..bf1a9c7
--- /dev/null
+++ b/simulation/install_resources/sim_ds.desktop
@@ -0,0 +1,9 @@
+[Desktop Entry]
+Name=Sim DS
+Keywords=frcsim,driverstation
+Exec=/usr/bin/sim_ds
+Icon=/usr/share/icons/sim_ds/sim_ds_logo.png
+Type=Application
+StartupNotify=true
+Terminal=false
+Categories=Development;IDE;Java;Education;Science
diff --git a/simulation/install_resources/sim_ds_logo.png b/simulation/install_resources/sim_ds_logo.png
new file mode 100644
index 0000000..39df91c
--- /dev/null
+++ b/simulation/install_resources/sim_ds_logo.png
Binary files differ
diff --git a/styleguide/cppguide.html b/styleguide/cppguide.html
new file mode 100644
index 0000000..f37c836
--- /dev/null
+++ b/styleguide/cppguide.html
@@ -0,0 +1,2470 @@
+<!DOCTYPE html>
+<html>
+<head>
+<meta http-equiv="content-type" content="text/html; charset=UTF-8">
+<title>WPILib C++ Style Guide</title>
+<link rel="stylesheet" type="text/css" href="include/styleguide.css">
+<script language="javascript" src="include/styleguide.js"></script>
+</head>
+<body onload="initStyleGuide();">
+<div id="content">
+<h1>WPILib C++ Style Guide (Based on the <a href=http://google-styleguide.googlecode.com/svn/trunk/cppguide.html>Google C++ Style Guide</a>)</h1>
+<div class="horizontal_toc" id="tocDiv"></div>
+
+<div class="main_body">
+
+<h2 class="ignoreLink" id="Background">Background</h2>
+
+<p><strong>This guide is a work in progress.</strong>
+We are currently working on getting this guide updated to
+a point where it is useful for WPILib developers to use.</p>
+
+<p>C++ is one of the two main languages (Java being the other)
+used in WPILib; in order to maintain consistency and keep the
+maintenance of the code manageable, we use this style guide.</p>
+
+<p>There are two main overarching purposes to this guide. The first
+is to act as a normal C++ style guide (both in terms fo formatting
+and programming practices) for C++ developers of WPILib.
+The other purpose is to help Java programmers who may
+know a moderate amount of C++ but may not be fully
+up to date with things like C++11 and so may not even
+realize that certain C++ features exist.</p>
+
+<p>This style guide is a heavily modified version of the
+<a href=http://google-styleguide.googlecode.com/svn/trunk/cppguide.html>
+Google C++ Style Guide</a>. The Google Style Guide has
+a lot of good points and is a good read, but in order
+to cut the style guide down to a more readable size and to
+focus mroe on WPILib-specific information, we have
+altetered the original style guide in several ways.</p>
+
+<p>One way in which we <em>haven't</em> done much to
+alter the original style guide is to keep the vast
+majority of the formatting/naming/etc. related
+information intact. This is both so that we
+do not have to write up our own standards and so
+that existing tools such as clang-format and
+the Google eclipse format configuration files
+can work out of the box. All of these things
+should be relatively non-controversial and do not
+require much discussion.</p>
+
+<p>Where we deviate more from the original guide is
+in the style of the code itself. At the moment (ie,
+when we first created this modified version), we
+deleted all of the sections of the original guide
+which mandate particular programming practices
+such as forbidding exceptions, multiple inheritance,
+etc. However, as time goes on, we gradually add in more
+information along this lines, either by copying
+directly from Google's Style Guide or by writing
+our own decisions and best practices, some of which
+may be very WPILib-specific.</p>
+
+<p>As the original guide makes very clear, consistency
+is extremely important to keeping the code base
+manageable, and so we encourage that, wherever
+reasonable, that you keep everything consistent
+with whatever the standard style is.</p>
+
+<p>Along with just C++ style, it is also important
+to keep in mind that WPILib consists of both a C++
+and Java half. In order to keep things consistent
+and easier for users, we ask that, in general,
+Java and C++ be kept as consistent with one another
+as reasonable. This includes everything from using
+two spaces for indentation in both language to
+keeping the inheritance structure essentially the
+same in both. Although the two do not have to be
+precisely the same, it does mean that if there is
+something that you are doing which will be imposssible
+to reproduce in some way in Java, then you may
+want to reconsider.</p>
+
+<p>One final thing to remember is that High School
+students with relatively little experience programming
+are the main user for this code, and throwing the full
+brunt of C++ at a student just learning how to program
+is likely not the best of ideas. As such, any
+user-facing APIs should minimize the use of any
+more complicated C++ features. As always,
+use your judgement and ask others in cases where
+there is something which may violate anything
+in this guide.</p>
+
+<h2 id="Programming_Guidelines">Programming Guidelines</h2>
+<p>C++ is a large, complicated language, and in order
+to ensure that we stay consistent and maintain certain
+best practices, we have certain rules. For the most part
+these are common sense rules and in some cases exist
+solely to point out features of C++ that someone more
+familiar with Java may not realize even exist.</p>
+
+<h3 id="Pointers">Pointers</h3>
+<p>In general, we strongly discourage the use of
+raw pointers in C++ code; instead, references or
+STL pointers should be used where appropriate.
+There are two exceptions to this rule:</p>
+<ul>
+  <li>When interfacing with lower-level C code or
+  with any libraries which force you to use raw pointers.</li>
+  <li>In order to keep user interfaces consistent,
+  we may keep around deprecated functions which
+  take raw pointers. Any user-facing functions
+  which take raw pointers should be deprecated
+  using the
+  <a href=https://en.wikipedia.org/wiki/C%2B%2B14#The_attribute_.5B.5Bdeprecated.5D.5D><code>[[deprecated]]</code></a>
+  attribute and replaced with either references
+  or STL pointers.</li>
+</ul>
+<p>As of C++11, the following are options in the
+place of raw pointers:</p>
+<ul>
+  <li><code>std::unique_ptr</code> Should be used
+  when you still need to use a pointer, but you
+  only need one entity to own the pointer. The
+  <code>std::unique_ptr</code> will automatically
+  be deleted when there are no more references to
+  it.</li>
+  <li><code>std::shared_ptr</code> Should be used
+  when you still need to use a pointer and you
+  need many references to the object. When
+  there are zero remaining references to the
+  object, it will be deleted. Use <code>std::weak_ptr</code>
+  where necessary to avoid circular dependencies
+  or other potential issues.</li>
+  <li>L-value references (the traditional sort
+  of reference that has been around since before C++11)
+  should be used when you want to pass around a
+  reference to an object and want to guarantee
+  that it won't be null. Use const references
+  if you want to avoid copying a large object
+  but don't want to modify it.</li>
+  <li>R-value references were introduced in C++11
+  and allow for the use of <code>std::move</code>.
+  R-value references should be used where it makes
+  sense that a parameter to a function is having
+  its ownership passed from one place to another.
+  In general, R-value references are not inherently
+  bad, but they do introduce additional complexity
+  that may confuse people who are not familiar
+  with them.</li>
+</ul>
+
+<h3 id="Deprecation">Deprecation</h3>
+<p>When updating APIs, make liberal use of the
+<code>[[deprecated]]</code> attribute (although if
+it is reasonable to simply remove any old interfaces
+then do so) to indicate that users should no longer
+use the function. Currently, this will cause warnings
+in user code and errors in the WPILib build.</p>
+
+<pre>
+[[deprecated("This is a deprecated function; this text will be displayed when"
+             " the compiler throws a warning.")]]
+void foo() {}
+class [[deprecated("This is a deprecated class.")]] Foo {};
+int bar [[deprecated("This is a deprecated variable.")]];
+</pre>
+
+<p>See <a href=http://josephmansfield.uk/articles/marking-deprecated-c++14.html>
+here</a> for more information on deprecation.</p>
+
+<h2 id="Header_Files">Header Files</h2>
+
+<p>In general, every <code>.cc</code> file should have an
+associated <code>.h</code> file. There are some common
+exceptions, such as  unittests and
+small <code>.cpp</code> files containing just a
+<code>main()</code> function.</p>
+
+<p>Correct use of header files can make a huge difference to
+the readability, size and performance of your code.</p>
+
+<p>The following rules will guide you through the various
+pitfalls of using header files.</p>
+
+<a id="The_-inl.h_Files"></a>
+<h3 id="Self_contained_Headers">Self-contained Headers</h3>
+
+<div class="summary">
+<p>Header files should be self-contained and end in <code>.h</code>. Files that
+are meant for textual inclusion, but are not headers, should end in
+<code>.inc</code>. Separate <code>-inl.h</code> headers are disallowed.</p>
+</div>
+
+<div class="stylebody">
+<p>All header files should be self-contained. In other
+words, users and refactoring tools should not have to adhere to special
+conditions in order to include the header. Specifically, a
+header should have <a href="#The__define_Guard">header guards</a>,
+should include all other headers it needs, and should not require any
+particular symbols to be defined.</p>
+
+<p>There are rare cases where a file is not meant to be self-contained, but
+instead is meant to be textually included at a specific point in the code.
+Examples are files that need to be included multiple times or
+platform-specific extensions that essentially are part of other headers. Such
+files should use the file extension <code>.inc</code>.</p>
+
+<p>If a template or inline function is declared in a <code>.h</code> file,
+define it in that same file. The definitions of these constructs must
+be included into every <code>.cc</code> file that uses them, or the
+program may fail to link in some build configurations. Do not move these
+definitions to separate <code>-inl.h</code> files.</p>
+
+<p>As an exception, a function template that is explicitly
+instantiated for all relevant sets of template arguments, or
+that is a private member of a class, may
+be defined in the only <code>.cc</code> file that
+instantiates the template.</p>
+
+</div>
+
+<h3 id="The__define_Guard">The #define Guard</h3>
+
+<div class="summary">
+<p>All header files should have <code>#define</code> guards to
+prevent multiple inclusion. The format of the symbol name
+should be
+<code><i>&lt;PROJECT&gt;</i>_<i>&lt;PATH&gt;</i>_<i>&lt;FILE&gt;</i>_H_</code>.</p>
+</div>
+
+<div class="stylebody">
+
+
+
+<p>To guarantee uniqueness, they should
+be based on the full path in a project's source tree. For
+example, the file <code>foo/src/bar/baz.h</code> in
+project <code>foo</code> should have the following
+guard:</p>
+
+<pre>#ifndef FOO_BAR_BAZ_H_
+#define FOO_BAR_BAZ_H_
+
+...
+
+#endif  // FOO_BAR_BAZ_H_
+</pre>
+
+
+
+
+</div>
+
+<h3 id="Forward_Declarations">Forward Declarations</h3>
+
+<div class="summary">
+<p>You may forward declare ordinary classes in order to avoid
+unnecessary <code>#include</code>s.</p>
+</div>
+
+<div class="stylebody">
+
+<div class="definition">
+<p>A "forward declaration" is a declaration of a class,
+function, or template without an associated definition.
+<code>#include</code> lines can often be replaced with
+forward declarations of whatever symbols are actually
+used by the client code.</p>
+</div>
+
+<div class="pros">
+<ul>
+  <li>Unnecessary <code>#include</code>s force the
+  compiler to open more files and process more
+  input.</li>
+
+  <li>They can also force your code to be recompiled more
+  often, due to changes in the header.</li>
+</ul>
+</div>
+
+<div class="cons">
+<ul>
+  <li>It can be difficult to determine the correct form
+  of a forward declaration in the presence of features
+  like templates, typedefs, default parameters, and using
+  declarations.</li>
+
+  <li>It can be difficult to determine whether a forward
+  declaration or a full <code>#include</code> is needed
+  for a given piece of code, particularly when implicit
+  conversion operations are involved. In extreme cases,
+  replacing an <code>#include</code> with a forward
+  declaration can silently change the meaning of
+  code.</li>
+
+  <li>Forward declaring multiple symbols from a header
+  can be more verbose than simply
+  <code>#include</code>ing the header.</li>
+
+  <li>Forward declarations of functions and templates can
+  prevent the header owners from making
+  otherwise-compatible changes to their APIs; for
+  example, widening a parameter type, or adding a
+  template parameter with a default value.</li>
+  <li>Forward declaring symbols from namespace
+  <code>std::</code> usually yields undefined
+  behavior.</li>
+
+  <li>Structuring code to enable forward declarations
+  (e.g. using pointer members instead of object members)
+  can make the code slower and more complex.</li>
+
+  <li>The practical efficiency benefits of forward
+  declarations are unproven.</li>
+</ul>
+</div>
+
+<div class="decision">
+<ul>
+  <li>When using a function declared in a header file,
+  always <code>#include</code> that header.</li>
+
+  <li>When using a class template, prefer to
+  <code>#include</code> its header file.</li>
+
+  <li>When using an ordinary class, relying on a forward
+  declaration is OK, but be wary of situations where a
+  forward declaration may be insufficient or incorrect;
+  when in doubt, just <code>#include</code> the
+  appropriate header.</li>
+
+  <li>Do not replace data members with pointers just to
+  avoid an <code>#include</code>.</li>
+</ul>
+
+<p>Please see <a href="#Names_and_Order_of_Includes">Names and Order
+of Includes</a> for rules about when to #include a header.</p>
+</div>
+
+</div>
+
+<h3 id="Inline_Functions">Inline Functions</h3>
+
+<div class="summary">
+<p>Define functions inline only when they are small, say, 10
+lines or less.</p>
+</div>
+
+<div class="stylebody">
+
+<div class="definition">
+<p>You can declare functions in a way that allows the compiler to expand
+them inline rather than calling them through the usual
+function call mechanism.</p>
+</div>
+
+<div class="pros">
+<p>Inlining a function can generate more efficient object
+code, as long as the inlined function is small. Feel free
+to inline accessors and mutators, and other short,
+performance-critical functions.</p>
+</div>
+
+<div class="cons">
+<p>Overuse of inlining can actually make programs slower.
+Depending on a function's size, inlining it can cause the
+code size to increase or decrease. Inlining a very small
+accessor function will usually decrease code size while
+inlining a very large function can dramatically increase
+code size. On modern processors smaller code usually runs
+faster due to better use of the instruction cache.</p>
+</div>
+
+<div class="decision">
+<p>A decent rule of thumb is to not inline a function if
+it is more than 10 lines long. Beware of destructors,
+which are often longer than they appear because of
+implicit member- and base-destructor calls!</p>
+
+<p>Another useful rule of thumb: it's typically not cost
+effective to inline functions with loops or switch
+statements (unless, in the common case, the loop or
+switch statement is never executed).</p>
+
+<p>It is important to know that functions are not always
+inlined even if they are declared as such; for example,
+virtual and recursive functions are not normally inlined.
+Usually recursive functions should not be inline. The
+main reason for making a virtual function inline is to
+place its definition in the class, either for convenience
+or to document its behavior, e.g., for accessors and
+mutators.</p>
+</div>
+
+</div>
+
+<h3 id="Function_Parameter_Ordering">Function Parameter Ordering</h3>
+
+<div class="summary">
+<p>When defining a function, parameter order is: inputs, then
+outputs.</p>
+</div>
+
+<div class="stylebody">
+<p>Parameters to C/C++ functions are either input to the
+function, output from the function, or both. Input
+parameters are usually values or <code>const</code>
+references, while output and input/output parameters will
+be non-<code>const</code> pointers. When ordering
+function parameters, put all input-only parameters before
+any output parameters. In particular, do not add new
+parameters to the end of the function just because they
+are new; place new input-only parameters before the
+output parameters.</p>
+
+<p>This is not a hard-and-fast rule. Parameters that are
+both input and output (often classes/structs) muddy the
+waters, and, as always, consistency with related
+functions may require you to bend the rule.</p>
+
+</div>
+
+<h3 id="Names_and_Order_of_Includes">Names and Order of Includes</h3>
+
+<div class="summary">
+<p>Use standard order for readability and to avoid hidden
+dependencies: Related header, C library, C++ library,  other libraries'
+<code>.h</code>, your project's <code>.h</code>.</p>
+</div>
+
+<div class="stylebody">
+<p>
+All of a project's header files should be
+listed as descendants of the project's source
+directory without use of UNIX directory shortcuts
+<code>.</code> (the current directory) or <code>..</code>
+(the parent directory). For example,
+
+<code>google-awesome-project/src/base/logging.h</code>
+should be included as:</p>
+
+<pre>#include "base/logging.h"
+</pre>
+
+<p>In <code><var>dir/foo</var>.cc</code> or
+<code><var>dir/foo_test</var>.cc</code>, whose main
+purpose is to implement or test the stuff in
+<code><var>dir2/foo2</var>.h</code>, order your includes
+as follows:</p>
+
+<ol>
+  <li><code><var>dir2/foo2</var>.h</code>.</li>
+
+  <li>C system files.</li>
+
+  <li>C++ system files.</li>
+
+  <li>Other libraries' <code>.h</code>
+  files.</li>
+
+  <li>
+  Your project's <code>.h</code>
+  files.</li>
+</ol>
+
+<p>With the preferred ordering, if
+<code><var>dir2/foo2</var>.h</code> omits any necessary
+includes, the build of <code><var>dir/foo</var>.cc</code>
+or <code><var>dir/foo</var>_test.cc</code> will break.
+Thus, this rule ensures that build breaks show up first
+for the people working on these files, not for innocent
+people in other packages.</p>
+
+<p><code><var>dir/foo</var>.cc</code> and
+<code><var>dir2/foo2</var>.h</code> are usually in the same
+directory (e.g. <code>base/basictypes_test.cc</code> and
+<code>base/basictypes.h</code>), but may sometimes be in different
+directories too.</p>
+
+
+
+<p>Within each section the includes should be ordered
+alphabetically. Note that older code might not conform to
+this rule and should be fixed when convenient.</p>
+
+<p>You should include all the headers that define the symbols you rely
+upon (except in cases of <a href="#Forward_Declarations">forward
+declaration</a>). If you rely on symbols from <code>bar.h</code>,
+don't count on the fact that you included <code>foo.h</code> which
+(currently) includes <code>bar.h</code>: include <code>bar.h</code>
+yourself, unless <code>foo.h</code> explicitly demonstrates its intent
+to provide you the symbols of <code>bar.h</code>.  However, any
+includes present in the related header do not need to be included
+again in the related <code>cc</code> (i.e., <code>foo.cc</code> can
+rely on <code>foo.h</code>'s includes).</p>
+
+<p>For example, the includes in
+
+<code>google-awesome-project/src/foo/internal/fooserver.cc</code>
+might look like this:</p>
+
+
+<pre>#include "foo/server/fooserver.h"
+
+#include &lt;sys/types.h&gt;
+#include &lt;unistd.h&gt;
+#include &lt;hash_map&gt;
+#include &lt;vector&gt;
+
+#include "base/basictypes.h"
+#include "base/commandlineflags.h"
+#include "foo/server/bar.h"
+</pre>
+
+<p class="exception">Sometimes, system-specific code needs
+conditional includes. Such code can put conditional
+includes after other includes. Of course, keep your
+system-specific code small and localized. Example:</p>
+
+<pre>#include "foo/public/fooserver.h"
+
+#include "base/port.h"  // For LANG_CXX11.
+
+#ifdef LANG_CXX11
+#include &lt;initializer_list&gt;
+#endif  // LANG_CXX11
+</pre>
+
+</div>
+
+<h2 id="Naming">Naming</h2>
+
+<p>The most important consistency rules are those that govern
+naming. The style of a name immediately informs us what sort of
+thing the named entity is: a type, a variable, a function, a
+constant, a macro, etc., without requiring us to search for the
+declaration of that entity. The pattern-matching engine in our
+brains relies a great deal on these naming rules.
+</p>
+
+<p>Naming rules are pretty arbitrary, but
+ we feel that
+consistency is more important than individual preferences in this
+area, so regardless of whether you find them sensible or not,
+the rules are the rules.</p>
+
+<h3 id="General_Naming_Rules">General Naming Rules</h3>
+
+<div class="summary">
+<p>Function names, variable names, and filenames should be
+descriptive; eschew abbreviation.</p>
+</div>
+
+<div class="stylebody">
+<p>Give as descriptive a name as possible, within reason.
+Do not worry about saving horizontal space as it is far
+more important to make your code immediately
+understandable by a new reader. Do not use abbreviations
+that are ambiguous or unfamiliar to readers outside your
+project, and do not abbreviate by deleting letters within
+a word.</p>
+
+<pre>int price_count_reader;    // No abbreviation.
+int num_errors;            // "num" is a widespread convention.
+int num_dns_connections;   // Most people know what "DNS" stands for.
+</pre>
+
+<pre class="badcode">int n;                     // Meaningless.
+int nerr;                  // Ambiguous abbreviation.
+int n_comp_conns;          // Ambiguous abbreviation.
+int wgc_connections;       // Only your group knows what this stands for.
+int pc_reader;             // Lots of things can be abbreviated "pc".
+int cstmr_id;              // Deletes internal letters.
+</pre>
+
+</div>
+
+<h3 id="File_Names">File Names</h3>
+
+<div class="summary">
+<p>Filenames should be all lowercase and can include
+underscores (<code>_</code>) or dashes (<code>-</code>).
+Follow the convention that your
+
+project uses. If there is no consistent
+local pattern to follow, prefer "_".</p>
+</div>
+
+<div class="stylebody">
+
+<p>Examples of acceptable file names:</p>
+
+<ul>
+  <li><code>my_useful_class.cc</code></li>
+  <li><code>my-useful-class.cc</code></li>
+  <li><code>myusefulclass.cc</code></li>
+  <li><code>myusefulclass_test.cc // _unittest and _regtest are deprecated.</code></li>
+</ul>
+
+<p>C++ files should end in <code>.cc</code> and header files should end in
+<code>.h</code>. Files that rely on being textually included at specific points
+should end in <code>.inc</code> (see also the section on
+<a href="#Self_contained_Headers">self-contained headers</a>).</p>
+
+<p>Do not use filenames that already exist in
+<code>/usr/include</code>, such as <code>db.h</code>.</p>
+
+<p>In general, make your filenames very specific. For
+example, use <code>http_server_logs.h</code> rather than
+<code>logs.h</code>. A very common case is to have a pair
+of files called, e.g., <code>foo_bar.h</code> and
+<code>foo_bar.cc</code>, defining a class called
+<code>FooBar</code>.</p>
+
+<p>Inline functions must be in a <code>.h</code> file. If
+your inline functions are very short, they should go
+directly into your <code>.h</code> file. </p>
+
+</div>
+
+<h3 id="Type_Names">Type Names</h3>
+
+<div class="summary">
+<p>Type names start with a capital letter and have a capital
+letter for each new word, with no underscores:
+<code>MyExcitingClass</code>, <code>MyExcitingEnum</code>.</p>
+</div>
+
+<div class="stylebody">
+
+<p>The names of all types &#8212; classes, structs, typedefs,
+and enums &#8212; have the same naming convention. Type names
+should start with a capital letter and have a capital letter
+for each new word. No underscores. For example:</p>
+
+<pre>// classes and structs
+class UrlTable { ...
+class UrlTableTester { ...
+struct UrlTableProperties { ...
+
+// typedefs
+typedef hash_map&lt;UrlTableProperties *, string&gt; PropertiesMap;
+
+// enums
+enum UrlTableErrors { ...
+</pre>
+
+</div>
+
+<h3 id="Variable_Names">Variable Names</h3>
+
+<div class="summary">
+<p>The names of variables and data members are all lowercase, with
+underscores between words. Data members of classes (but not structs)
+additionally are prefixed with "m_". For instance:
+<code>a_local_variable</code>, <code>a_struct_data_member</code>,
+<code>m_a_class_data_member</code>.</p>
+</div>
+
+<div class="stylebody">
+
+<h4 class="stylepoint_subsection">Common Variable names</h4>
+
+<p>For example:</p>
+
+<pre>string table_name;  // OK - uses underscore.
+string tablename;   // OK - all lowercase.
+</pre>
+
+<pre class="badcode">string tableName;   // Bad - mixed case.
+</pre>
+
+<h4 class="stylepoint_subsection">Class Data Members</h4>
+
+<p>Data members of classes, both static and non-static, are
+named like ordinary nonmember variables, but prefixed with a
+"m_".</p>
+
+<pre>class TableInfo {
+  ...
+ private:
+  string m_table_name;  // OK - m_ at beginning.
+  string m_tablename;   // OK.
+  static Pool&lt;TableInfo&gt;* m_pool;  // OK.
+};
+</pre>
+
+<h4 class="stylepoint_subsection">Struct Data Members</h4>
+
+<p>Data members of structs, both static and non-static,
+are named like ordinary nonmember variables. They do not have
+the preceding "m_" that data members in classes have.</p>
+
+<pre>struct UrlTableProperties {
+  string name;
+  int num_entries;
+  static Pool&lt;UrlTableProperties&gt;* pool;
+};
+</pre>
+
+
+<p>See <a href="#Structs_vs._Classes">Structs vs.
+Classes</a> for a discussion of when to use a struct
+versus a class.</p>
+
+<h4 class="stylepoint_subsection">Global Variables</h4>
+
+<p>There are no special requirements for global
+variables, which should be rare in any case, but if you
+use one, consider prefixing it with <code>g_</code> or
+some other marker to easily distinguish it from local
+variables.</p>
+
+</div>
+
+<h3 id="Constant_Names">Constant Names</h3>
+
+<div class="summary">
+<p>Use a <code>k</code> followed by mixed case, e.g.,
+<code>kDaysInAWeek</code>, for constants defined globally or within a class.</p>
+</div>
+
+<div class="stylebody">
+
+<p>As a convenience to the reader, compile-time constants of global or class scope
+follow a different naming convention from other variables.
+Use a <code>k</code> followed by words with uppercase first letters:</p>
+
+<pre>const int kDaysInAWeek = 7;
+</pre>
+
+<p>This convention may optionally be used for compile-time constants of local scope;
+otherwise the usual variable naming rules apply.
+
+</p></div>
+
+<h3 id="Function_Names">Function Names</h3>
+
+<div class="summary">
+<p>Regular functions have mixed case; accessors and mutators
+match the name of the variable:
+<code>MyExcitingFunction()</code>,
+<code>MyExcitingMethod()</code>,
+<code>my_exciting_member_variable()</code>,
+<code>set_my_exciting_member_variable()</code>.</p>
+</div>
+
+<div class="stylebody">
+
+<h4 class="stylepoint_subsection">Regular Functions</h4>
+
+<p>Functions should start with a capital letter and have
+a capital letter for each new word. No underscores.</p>
+
+<p>If your function crashes upon an error, you should
+append OrDie to the function name. This only applies to
+functions which could be used by production code and to
+errors that are reasonably likely to occur during normal
+operation.</p>
+
+            <pre>AddTableEntry()
+DeleteUrl()
+OpenFileOrDie()
+</pre>
+
+<h4 class="stylepoint_subsection">Accessors and Mutators</h4>
+
+<p>Accessors and mutators (get and set functions) should
+match the name of the variable they are getting and
+setting. This shows an excerpt of a class whose instance
+variable is <code>num_entries_</code>.</p>
+
+<pre>class MyClass {
+ public:
+  ...
+  int num_entries() const { return num_entries_; }
+  void set_num_entries(int num_entries) { num_entries_ = num_entries; }
+
+ private:
+  int num_entries_;
+};
+</pre>
+
+<p>You may also use lowercase letters for other very
+short inlined functions. For example if a function were
+so cheap you would not cache the value if you were
+calling it in a loop, then lowercase naming would be
+acceptable.</p>
+
+</div>
+
+<h3 id="Namespace_Names">Namespace Names</h3>
+
+<div class="summary">
+
+
+<p>Namespace names are all lower-case,
+and based on project names and possibly their directory
+structure: <code>google_awesome_project</code>.</p>
+</div>
+
+<div class="stylebody">
+
+<p>See <a href="#Namespaces">Namespaces</a> for a
+discussion of namespaces and how to name them.</p>
+
+</div>
+
+<h3 id="Enumerator_Names">Enumerator Names</h3>
+
+<div class="summary">
+<p>Enumerators should be named <i>either</i> like
+<a href="#Constant_Names">constants</a> or like
+<a href="#Macro_Names">macros</a>: either <code>kEnumName</code> or
+<code>ENUM_NAME</code>.</p>
+</div>
+
+<div class="stylebody">
+
+<p>Preferably, the individual enumerators should be named
+like <a href="#Constant_Names">constants</a>. However, it
+is also acceptable to name them like
+<a href="Macro_Names">macros</a>.  The enumeration name,
+<code>UrlTableErrors</code> (and
+<code>AlternateUrlTableErrors</code>), is a type, and
+therefore mixed case.</p>
+
+<pre>enum UrlTableErrors {
+  kOK = 0,
+  kErrorOutOfMemory,
+  kErrorMalformedInput,
+};
+enum AlternateUrlTableErrors {
+  OK = 0,
+  OUT_OF_MEMORY = 1,
+  MALFORMED_INPUT = 2,
+};
+</pre>
+
+<p>Until January 2009, the style was to name enum values
+like <a href="#Macro_Names">macros</a>. This caused
+problems with name collisions between enum values and
+macros. Hence, the change to prefer constant-style naming
+was put in place. New code should prefer constant-style
+naming if possible. However, there is no reason to change
+old code to use constant-style names, unless the old
+names are actually causing a compile-time problem.</p>
+
+
+
+</div>
+
+<h3 id="Macro_Names">Macro Names</h3>
+
+<div class="summary">
+<p>You're not really going to <a href="#Preprocessor_Macros">
+define a macro</a>, are you? If you do, they're like this:
+<code>MY_MACRO_THAT_SCARES_SMALL_CHILDREN</code>.</p>
+</div>
+
+<div class="stylebody">
+
+<p>Please see the <a href="#Preprocessor_Macros">description
+of macros</a>; in general macros should <em>not</em> be used.
+However, if they are absolutely needed, then they should be
+named with all capitals and underscores.</p>
+
+<pre>#define ROUND(x) ...
+#define PI_ROUNDED 3.0
+</pre>
+
+</div>
+
+<h3 id="Exceptions_to_Naming_Rules">Exceptions to Naming Rules</h3>
+
+<div class="summary">
+<p>If you are naming something that is analogous to an
+existing C or C++ entity then you can follow the existing
+naming convention scheme.</p>
+</div>
+
+<div class="stylebody">
+
+<dl>
+  <dt><code>bigopen()</code></dt>
+  <dd>function name, follows form of <code>open()</code></dd>
+
+  <dt><code>uint</code></dt>
+  <dd><code>typedef</code></dd>
+
+  <dt><code>bigpos</code></dt>
+  <dd><code>struct</code> or <code>class</code>, follows
+  form of <code>pos</code></dd>
+
+  <dt><code>sparse_hash_map</code></dt>
+  <dd>STL-like entity; follows STL naming conventions</dd>
+
+  <dt><code>LONGLONG_MAX</code></dt>
+  <dd>a constant, as in <code>INT_MAX</code></dd>
+</dl>
+
+</div>
+
+<h2 id="Comments">Comments</h2>
+
+<p>Though a pain to write, comments are absolutely vital to
+keeping our code readable. The following rules describe what
+you should comment and where. But remember: while comments are
+very important, the best code is self-documenting. Giving
+sensible names to types and variables is much better than using
+obscure names that you must then explain through comments.</p>
+
+<p>When writing your comments, write for your audience: the
+next
+contributor who will need to
+understand your code. Be generous &#8212; the next
+one may be you!</p>
+
+<h3 id="Comment_Style">Comment Style</h3>
+
+<div class="summary">
+<p>Use either the <code>//</code> or <code>/* */</code>
+syntax, as long as you are consistent.</p>
+</div>
+
+<div class="stylebody">
+
+<p>You can use either the <code>//</code> or the <code>/*
+*/</code> syntax; however, <code>//</code> is
+<em>much</em> more common. Be consistent with how you
+comment and what style you use where.</p>
+
+</div>
+
+<h3 id="File_Comments">File Comments</h3>
+
+<div class="summary">
+<p> Start each file with license
+boilerplate, followed by a description of its
+contents.</p>
+</div>
+
+<div class="stylebody">
+
+<h4 class="stylepoint_subsection">Legal Notice and Author
+Line</h4>
+
+
+
+<p>Every file should contain license
+boilerplate. Choose the appropriate boilerplate for the
+license used by the project (for example, Apache 2.0,
+BSD, LGPL, GPL).</p>
+
+<p>If you make significant changes to a file with an
+author line, consider deleting the author line.</p>
+
+<h4 class="stylepoint_subsection">File Contents</h4>
+
+<p>Every file should have a comment at the top describing
+its contents.</p>
+
+<p>Generally a <code>.h</code> file will describe the
+classes that are declared in the file with an overview of
+what they are for and how they are used. A
+<code>.cc</code> file should contain more information
+about implementation details or discussions of tricky
+algorithms. If you feel the implementation details or a
+discussion of the algorithms would be useful for someone
+reading the <code>.h</code>, feel free to put it there
+instead, but mention in the <code>.cc</code> that the
+documentation is in the <code>.h</code> file.</p>
+
+<p>Do not duplicate comments in both the <code>.h</code>
+and the <code>.cc</code>. Duplicated comments
+diverge.</p>
+
+</div>
+
+<h3 id="Class_Comments">Class Comments</h3>
+
+<div class="summary">
+<p>Every class definition should have an accompanying comment
+that describes what it is for and how it should be used.</p>
+</div>
+
+<div class="stylebody">
+
+<pre>// Iterates over the contents of a GargantuanTable.  Sample usage:
+//    GargantuanTableIterator* iter = table-&gt;NewIterator();
+//    for (iter-&gt;Seek("foo"); !iter-&gt;done(); iter-&gt;Next()) {
+//      process(iter-&gt;key(), iter-&gt;value());
+//    }
+//    delete iter;
+class GargantuanTableIterator {
+  ...
+};
+</pre>
+
+<p>If you have already described a class in detail in the
+comments at the top of your file feel free to simply
+state "See comment at top of file for a complete
+description", but be sure to have some sort of
+comment.</p>
+
+<p>Document the synchronization assumptions the class
+makes, if any. If an instance of the class can be
+accessed by multiple threads, take extra care to document
+the rules and invariants surrounding multithreaded
+use.</p>
+
+</div>
+
+<h3 id="Function_Comments">Function Comments</h3>
+
+<div class="summary">
+<p>Declaration comments describe use of the function; comments
+at the definition of a function describe operation.</p>
+</div>
+
+<div class="stylebody">
+
+<h4 class="stylepoint_subsection">Function Declarations</h4>
+
+<p>Every function declaration should have comments
+immediately preceding it that describe what the function
+does and how to use it. These comments should be
+descriptive ("Opens the file") rather than imperative
+("Open the file"); the comment describes the function, it
+does not tell the function what to do. In general, these
+comments do not describe how the function performs its
+task. Instead, that should be left to comments in the
+function definition.</p>
+
+<p>Types of things to mention in comments at the function
+declaration:</p>
+
+<ul>
+  <li>What the inputs and outputs are.</li>
+
+  <li>For class member functions: whether the object
+  remembers reference arguments beyond the duration of
+  the method call, and whether it will free them or
+  not.</li>
+
+  <li>If the function allocates memory that the caller
+  must free.</li>
+
+  <li>Whether any of the arguments can be a null
+  pointer.</li>
+
+  <li>If there are any performance implications of how a
+  function is used.</li>
+
+  <li>If the function is re-entrant. What are its
+  synchronization assumptions?</li>
+ </ul>
+
+<p>Here is an example:</p>
+
+<pre>// Returns an iterator for this table.  It is the client's
+// responsibility to delete the iterator when it is done with it,
+// and it must not use the iterator once the GargantuanTable object
+// on which the iterator was created has been deleted.
+//
+// The iterator is initially positioned at the beginning of the table.
+//
+// This method is equivalent to:
+//    Iterator* iter = table-&gt;NewIterator();
+//    iter-&gt;Seek("");
+//    return iter;
+// If you are going to immediately seek to another place in the
+// returned iterator, it will be faster to use NewIterator()
+// and avoid the extra seek.
+Iterator* GetIterator() const;
+</pre>
+
+<p>However, do not be unnecessarily verbose or state the
+completely obvious. Notice below that it is not necessary
+ to say "returns false otherwise" because this is
+implied.</p>
+
+<pre>// Returns true if the table cannot hold any more entries.
+bool IsTableFull();
+</pre>
+
+<p>When commenting constructors and destructors, remember
+that the person reading your code knows what constructors
+and destructors are for, so comments that just say
+something like "destroys this object" are not useful.
+Document what constructors do with their arguments (for
+example, if they take ownership of pointers), and what
+cleanup the destructor does. If this is trivial, just
+skip the comment. It is quite common for destructors not
+to have a header comment.</p>
+
+<h4 class="stylepoint_subsection">Function Definitions</h4>
+
+<p>If there is anything tricky about how a function does
+its job, the function definition should have an
+explanatory comment. For example, in the definition
+comment you might describe any coding tricks you use,
+give an overview of the steps you go through, or explain
+why you chose to implement the function in the way you
+did rather than using a viable alternative. For instance,
+you might mention why it must acquire a lock for the
+first half of the function but why it is not needed for
+the second half.</p>
+
+<p>Note you should <em>not</em> just repeat the comments
+given with the function declaration, in the
+<code>.h</code> file or wherever. It's okay to
+recapitulate briefly what the function does, but the
+focus of the comments should be on how it does it.</p>
+
+</div>
+
+<h3 id="Variable_Comments">Variable Comments</h3>
+
+<div class="summary">
+<p>In general the actual name of the variable should be
+descriptive enough to give a good idea of what the variable
+is used for. In certain cases, more comments are required.</p>
+</div>
+
+<div class="stylebody">
+
+<h4 class="stylepoint_subsection">Class Data Members</h4>
+
+<p>Each class data member (also called an instance
+variable or member variable) should have a comment
+describing what it is used for. If the variable can take
+sentinel values with special meanings, such as a null
+pointer or -1, document this. For example:</p>
+
+
+<pre>private:
+ // Keeps track of the total number of entries in the table.
+ // Used to ensure we do not go over the limit. -1 means
+ // that we don't yet know how many entries the table has.
+ int num_total_entries_;
+</pre>
+
+<h4 class="stylepoint_subsection">Global Variables</h4>
+
+<p>As with data members, all global variables should have
+a comment describing what they are and what they are used
+for. For example:</p>
+
+<pre>// The total number of tests cases that we run through in this regression test.
+const int kNumTestCases = 6;
+</pre>
+
+</div>
+
+<h3 id="Implementation_Comments">Implementation Comments</h3>
+
+<div class="summary">
+<p>In your implementation you should have comments in tricky,
+non-obvious, interesting, or important parts of your code.</p>
+</div>
+
+<div class="stylebody">
+
+<h4 class="stylepoint_subsection">Explanatory Comments</h4>
+
+<p>Tricky or complicated code blocks should have comments
+before them. Example:</p>
+
+<pre>// Divide result by two, taking into account that x
+// contains the carry from the add.
+for (int i = 0; i &lt; result-&gt;size(); i++) {
+  x = (x &lt;&lt; 8) + (*result)[i];
+  (*result)[i] = x &gt;&gt; 1;
+  x &amp;= 1;
+}
+</pre>
+
+<h4 class="stylepoint_subsection">Line Comments</h4>
+
+<p>Also, lines that are non-obvious should get a comment
+at the end of the line. These end-of-line comments should
+be separated from the code by 2 spaces. Example:</p>
+
+<pre>// If we have enough memory, mmap the data portion too.
+mmap_budget = max&lt;int64&gt;(0, mmap_budget - index_-&gt;length());
+if (mmap_budget &gt;= data_size_ &amp;&amp; !MmapData(mmap_chunk_bytes, mlock))
+  return;  // Error already logged.
+</pre>
+
+<p>Note that there are both comments that describe what
+the code is doing, and comments that mention that an
+error has already been logged when the function
+returns.</p>
+
+<p>If you have several comments on subsequent lines, it
+can often be more readable to line them up:</p>
+
+<pre>DoSomething();                  // Comment here so the comments line up.
+DoSomethingElseThatIsLonger();  // Two spaces between the code and the comment.
+{ // One space before comment when opening a new scope is allowed,
+  // thus the comment lines up with the following comments and code.
+  DoSomethingElse();  // Two spaces before line comments normally.
+}
+vector&lt;string&gt; list{// Comments in braced lists describe the next element ..
+                    "First item",
+                    // .. and should be aligned appropriately.
+                    "Second item"};
+DoSomething(); /* For trailing block comments, one space is fine. */
+</pre>
+
+<h4 class="stylepoint_subsection">nullptr/NULL, true/false, 1, 2, 3...</h4>
+
+<p>When you pass in a null pointer, boolean, or literal
+integer values to functions, you should consider adding a
+comment about what they are, or make your code
+self-documenting by using constants. For example,
+compare:</p>
+
+<pre class="badcode">bool success = CalculateSomething(interesting_value,
+                                  10,
+                                  false,
+                                  NULL);  // What are these arguments??
+</pre>
+
+<p>versus:</p>
+
+<pre>bool success = CalculateSomething(interesting_value,
+                                  10,     // Default base value.
+                                  false,  // Not the first time we're calling this.
+                                  NULL);  // No callback.
+</pre>
+
+<p>Or alternatively, constants or self-describing variables:</p>
+
+<pre>const int kDefaultBaseValue = 10;
+const bool kFirstTimeCalling = false;
+Callback *null_callback = NULL;
+bool success = CalculateSomething(interesting_value,
+                                  kDefaultBaseValue,
+                                  kFirstTimeCalling,
+                                  null_callback);
+</pre>
+
+<h4 class="stylepoint_subsection">Don'ts</h4>
+
+<p>Note that you should <em>never</em> describe the code
+itself. Assume that the person reading the code knows C++
+better than you do, even though he or she does not know
+what you are trying to do:</p>
+
+<pre class="badcode">// Now go through the b array and make sure that if i occurs,
+// the next element is i+1.
+...        // Geez.  What a useless comment.
+</pre>
+
+</div>
+
+<h3 id="Punctuation,_Spelling_and_Grammar">Punctuation, Spelling and Grammar</h3>
+
+<div class="summary">
+<p>Pay attention to punctuation, spelling, and grammar; it is
+easier to read well-written comments than badly written
+ones.</p>
+</div>
+
+<div class="stylebody">
+
+<p>Comments should be as readable as narrative text, with
+proper capitalization and punctuation. In many cases,
+complete sentences are more readable than sentence
+fragments. Shorter comments, such as comments at the end
+of a line of code, can sometimes be less formal, but you
+should be consistent with your style.</p>
+
+<p>Although it can be frustrating to have a code reviewer
+point out that you are using a comma when you should be
+using a semicolon, it is very important that source code
+maintain a high level of clarity and readability. Proper
+punctuation, spelling, and grammar help with that
+goal.</p>
+
+</div>
+
+<h3 id="TODO_Comments">TODO Comments</h3>
+
+<div class="summary">
+<p>Use <code>TODO</code> comments for code that is temporary,
+a short-term solution, or good-enough but not perfect.</p>
+</div>
+
+<div class="stylebody">
+
+<p><code>TODO</code>s should include the string
+<code>TODO</code> in all caps, followed by the
+
+name, e-mail address, or other
+identifier of the person
+ with the best context
+about the problem referenced by the <code>TODO</code>. The
+main purpose is to have a consistent <code>TODO</code> that
+can be searched to find out how to get more details upon
+request. A <code>TODO</code> is not a commitment that the
+person referenced will fix the problem. Thus when you create
+a <code>TODO</code>, it is almost always your
+
+name
+that is given.</p>
+
+
+
+<div>
+<pre>// TODO(kl@gmail.com): Use a "*" here for concatenation operator.
+// TODO(Zeke) change this to use relations.
+</pre>
+</div>
+
+<p>If your <code>TODO</code> is of the form "At a future
+date do something" make sure that you either include a
+very specific date ("Fix by November 2005") or a very
+specific event ("Remove this code when all clients can
+handle XML responses.").</p>
+
+</div>
+
+<h3 id="Deprecation_Comments">Deprecation Comments</h3>
+
+<div class="summary">
+<p>Mark deprecated interface points with <code>DEPRECATED</code>
+comments.</p>
+</div>
+
+<div class="stylebody">
+
+<p>You can mark an interface as deprecated by writing a
+comment containing the word <code>DEPRECATED</code> in
+all caps. The comment goes either before the declaration
+of the interface or on the same line as the
+declaration.</p>
+
+
+
+<p>After the word
+<code>DEPRECATED</code>, write your name, e-mail address,
+or other identifier in parentheses.</p>
+
+<p>A deprecation comment must include simple, clear
+directions for people to fix their callsites. In C++, you
+can implement a deprecated function as an inline function
+that calls the new interface point.</p>
+
+<p>Marking an interface point <code>DEPRECATED</code>
+will not magically cause any callsites to change. If you
+want people to actually stop using the deprecated
+facility, you will have to fix the callsites yourself or
+recruit a crew to help you.</p>
+
+<p>New code should not contain calls to deprecated
+interface points. Use the new interface point instead. If
+you cannot understand the directions, find the person who
+created the deprecation and ask them for help using the
+new interface point.</p>
+
+
+
+</div>
+
+<h2 id="Formatting">Formatting</h2>
+
+<p>Coding style and formatting are pretty arbitrary, but a
+
+project is much easier to follow
+if everyone uses the same style. Individuals may not agree with every
+aspect of the formatting rules, and some of the rules may take
+some getting used to, but it is important that all
+
+project contributors follow the
+style rules so that
+they can all read and understand
+everyone's code easily.</p>
+
+
+
+<p>To help you format code correctly, we've
+created a
+<a href="http://google-styleguide.googlecode.com/svn/trunk/google-c-style.el">
+settings file for emacs</a>.</p>
+
+<h3 id="Line_Length">Line Length</h3>
+
+<div class="summary">
+<p>Each line of text in your code should be at most 80
+characters long.</p>
+</div>
+
+<div class="stylebody">
+
+
+
+ <p>We recognize that this rule is
+controversial, but so much existing code already adheres
+to it, and we feel that consistency is important.</p>
+
+<div class="pros">
+<p>Those who favor  this rule
+argue that it is rude to force them to resize
+their windows and there is no need for anything longer.
+Some folks are used to having several code windows
+side-by-side, and thus don't have room to widen their
+windows in any case. People set up their work environment
+assuming a particular maximum window width, and 80
+columns has been the traditional standard. Why change
+it?</p>
+</div>
+
+<div class="cons">
+<p>Proponents of change argue that a wider line can make
+code more readable. The 80-column limit is an hidebound
+throwback to 1960s mainframes;  modern equipment has wide screens that
+can easily show longer lines.</p>
+</div>
+
+<div class="decision">
+<p> 80 characters is the maximum.</p>
+
+<p class="exception">If a comment line contains an example
+command or a literal URL longer than 80 characters, that
+line may be longer than 80 characters for ease of cut and
+paste.</p>
+
+<p class="exception">A raw-string literal may have content
+that exceeds 80 characters.  Except for test code, such literals
+should appear near top of a file.</p>
+
+<p class="exception">An <code>#include</code> statement with a
+long path may exceed 80 columns.</p>
+
+<p class="exception">You needn't be concerned about
+<a href="#The__define_Guard">header guards</a> that exceed
+the maximum length. </p>
+</div>
+
+</div>
+
+<h3 id="Non-ASCII_Characters">Non-ASCII Characters</h3>
+
+<div class="summary">
+<p>Non-ASCII characters should be rare, and must use UTF-8
+formatting.</p>
+</div>
+
+<div class="stylebody">
+
+<p>You shouldn't hard-code user-facing text in source,
+even English, so use of non-ASCII characters should be
+rare. However, in certain cases it is appropriate to
+include such words in your code. For example, if your
+code parses data files from foreign sources, it may be
+appropriate to hard-code the non-ASCII string(s) used in
+those data files as delimiters. More commonly, unittest
+code (which does not  need to be localized) might
+contain non-ASCII strings. In such cases, you should use
+UTF-8, since that is  an encoding
+understood by most tools able to handle more than just
+ASCII.</p>
+
+<p>Hex encoding is also OK, and encouraged where it
+enhances readability &#8212; for example,
+<code>"\xEF\xBB\xBF"</code>, or, even more simply,
+<code>u8"\uFEFF"</code>, is the Unicode zero-width
+no-break space character, which would be invisible if
+included in the source as straight UTF-8.</p>
+
+<p>Use the <code>u8</code> prefix
+to guarantee that a string literal containing
+<code>\uXXXX</code> escape sequences is encoded as UTF-8.
+Do not use it for strings containing non-ASCII characters
+encoded as UTF-8, because that will produce incorrect
+output if the compiler does not interpret the source file
+as UTF-8. </p>
+
+<p>You shouldn't use the C++11 <code>char16_t</code> and
+<code>char32_t</code> character types, since they're for
+non-UTF-8 text. For similar reasons you also shouldn't
+use <code>wchar_t</code> (unless you're writing code that
+interacts with the Windows API, which uses
+<code>wchar_t</code> extensively).</p>
+
+</div>
+
+<h3 id="Spaces_vs._Tabs">Spaces vs. Tabs</h3>
+
+<div class="summary">
+<p>Use only spaces, and indent 2 spaces at a time.</p>
+</div>
+
+<div class="stylebody">
+
+<p>We use spaces for indentation. Do not use tabs in your
+code. You should set your editor to emit spaces when you
+hit the tab key.</p>
+
+</div>
+
+<h3 id="Function_Declarations_and_Definitions">Function Declarations and Definitions</h3>
+
+<div class="summary">
+<p>Return type on the same line as function name, parameters
+on the same line if they fit. Wrap parameter lists which do
+not fit on a single line as you would wrap arguments in a
+function call.</p>
+</div>
+
+<div class="stylebody">
+
+<p>Functions look like this:</p>
+
+
+<pre>ReturnType ClassName::FunctionName(Type par_name1, Type par_name2) {
+  DoSomething();
+  ...
+}
+</pre>
+
+<p>If you have too much text to fit on one line:</p>
+
+<pre>ReturnType ClassName::ReallyLongFunctionName(Type par_name1, Type par_name2,
+                                             Type par_name3) {
+  DoSomething();
+  ...
+}
+</pre>
+
+<p>or if you cannot fit even the first parameter:</p>
+
+<pre>ReturnType LongClassName::ReallyReallyReallyLongFunctionName(
+    Type par_name1,  // 4 space indent
+    Type par_name2,
+    Type par_name3) {
+  DoSomething();  // 2 space indent
+  ...
+}
+</pre>
+
+<p>Some points to note:</p>
+
+<ul>
+  <li>If you cannot fit the return type and the function
+  name on a single line, break between them.</li>
+
+  <li>If you break after the return type of a function
+  declaration or definition, do not indent.</li>
+
+  <li>The open parenthesis is always on the same line as
+  the function name.</li>
+
+  <li>There is never a space between the function name
+  and the open parenthesis.</li>
+
+  <li>There is never a space between the parentheses and
+  the parameters.</li>
+
+  <li>The open curly brace is always at the end of the
+  same line as the last parameter.</li>
+
+  <li>The close curly brace is either on the last line by
+  itself or (if other style rules permit) on the same
+  line as the open curly brace.</li>
+
+  <li>There should be a space between the close
+  parenthesis and the open curly brace.</li>
+
+  <li>All parameters should be named, with identical
+  names in the declaration and implementation.</li>
+
+  <li>All parameters should be aligned if possible.</li>
+
+  <li>Default indentation is 2 spaces.</li>
+
+  <li>Wrapped parameters have a 4 space indent.</li>
+</ul>
+
+<p>If some parameters are unused, comment out the
+variable name in the function definition:</p>
+
+<pre>// Always have named parameters in interfaces.
+class Shape {
+ public:
+  virtual void Rotate(double radians) = 0;
+};
+
+// Always have named parameters in the declaration.
+class Circle : public Shape {
+ public:
+  virtual void Rotate(double radians);
+};
+
+// Comment out unused named parameters in definitions.
+void Circle::Rotate(double /*radians*/) {}
+</pre>
+
+<pre class="badcode">// Bad - if someone wants to implement later, it's not clear what the
+// variable means.
+void Circle::Rotate(double) {}
+</pre>
+
+</div>
+
+<h3 id="Formatting_Lambda_Expressions">Lambda Expressions</h3>
+
+<div class="summary">
+<p>Format parameters and bodies as for any other function, and capture
+lists like other comma-separated lists.</p>
+</div>
+
+<div class="stylebody">
+<p>For by-reference captures, do not leave a space between the
+ampersand (&amp;) and the variable name.</p>
+<pre>int x = 0;
+auto add_to_x = [&amp;x](int n) { x += n; };
+</pre>
+<p>Short lambdas may be written inline as function arguments.</p>
+<pre>std::set&lt;int&gt; blacklist = {7, 8, 9};
+std::vector&lt;int&gt; digits = {3, 9, 1, 8, 4, 7, 1};
+digits.erase(std::remove_if(digits.begin(), digits.end(), [&amp;blacklist](int i) {
+               return blacklist.find(i) != blacklist.end();
+             }),
+             digits.end());
+</pre>
+
+</div>
+
+<h3 id="Function_Calls">Function Calls</h3>
+
+<div class="summary">
+<p>Either write the call all on a single line, wrap the
+arguments at the parenthesis, or start the arguments on a new
+line indented by four spaces and continue at that 4 space
+indent. In the absence of other considerations, use the
+minimum number of lines, including placing multiple arguments
+on each line where appropriate.</p>
+</div>
+
+<div class="stylebody">
+
+<p>Function calls have the following format:</p>
+<pre>bool retval = DoSomething(argument1, argument2, argument3);
+</pre>
+
+<p>If the arguments do not all fit on one line, they
+should be broken up onto multiple lines, with each
+subsequent line aligned with the first argument. Do not
+add spaces after the open paren or before the close
+paren:</p>
+<pre>bool retval = DoSomething(averyveryveryverylongargument1,
+                          argument2, argument3);
+</pre>
+
+<p>Arguments may optionally all be placed on subsequent
+lines with a four space indent:</p>
+<pre>if (...) {
+  ...
+  ...
+  if (...) {
+    DoSomething(
+        argument1, argument2,  // 4 space indent
+        argument3, argument4);
+  }
+</pre>
+
+<p>Put multiple arguments on a single line to reduce the
+number of lines necessary for calling a function unless
+there is a specific readability problem. Some find that
+formatting with strictly one argument on each line is
+more readable and simplifies editing of the arguments.
+However, we prioritize for the reader over the ease of
+editing arguments, and most readability problems are
+better addressed with the following techniques.</p>
+
+<p>If having multiple arguments in a single line decreases
+readability due to the complexity or confusing nature of the
+expressions that make up some arguments, try creating
+variables that capture those arguments in a descriptive name:</p>
+<pre>int my_heuristic = scores[x] * y + bases[x];
+bool retval = DoSomething(my_heuristic, x, y, z);
+</pre>
+
+<p>Or put the confusing argument on its own line with
+an explanatory comment:</p>
+<pre>bool retval = DoSomething(scores[x] * y + bases[x],  // Score heuristic.
+                          x, y, z);
+</pre>
+
+<p>If there is still a case where one argument is
+significantly more readable on its own line, then put it on
+its own line. The decision should be specific to the argument
+which is made more readable rather than a general policy.</p>
+
+<p>Sometimes arguments form a structure that is important
+for readability. In those cases, feel free to format the
+arguments according to that structure:</p>
+<pre>// Transform the widget by a 3x3 matrix.
+my_widget.Transform(x1, x2, x3,
+                    y1, y2, y3,
+                    z1, z2, z3);
+</pre>
+
+</div>
+
+<h3 id="Braced_Initializer_List_Format">Braced Initializer List Format</h3>
+
+<div class="summary">
+<p>Format a <a href="#Braced_Initializer_List">braced initializer list</a>
+exactly like you would format a function call in its place.</p>
+</div>
+
+<div class="stylebody">
+
+<p>If the braced list follows a name (e.g. a type or
+variable name), format as if the <code>{}</code> were the
+parentheses of a function call with that name. If there
+is no name, assume a zero-length name.</p>
+
+<pre>// Examples of braced init list on a single line.
+return {foo, bar};
+functioncall({foo, bar});
+pair&lt;int, int&gt; p{foo, bar};
+
+// When you have to wrap.
+SomeFunction(
+    {"assume a zero-length name before {"},
+    some_other_function_parameter);
+SomeType variable{
+    some, other, values,
+    {"assume a zero-length name before {"},
+    SomeOtherType{
+        "Very long string requiring the surrounding breaks.",
+        some, other values},
+    SomeOtherType{"Slightly shorter string",
+                  some, other, values}};
+SomeType variable{
+    "This is too long to fit all in one line"};
+MyType m = {  // Here, you could also break before {.
+    superlongvariablename1,
+    superlongvariablename2,
+    {short, interior, list},
+    {interiorwrappinglist,
+     interiorwrappinglist2}};
+</pre>
+
+</div>
+
+<h3 id="Conditionals">Conditionals</h3>
+
+<div class="summary">
+<p>Prefer no spaces inside parentheses. The <code>if</code>
+and <code>else</code> keywords belong on separate lines.</p>
+</div>
+
+<div class="stylebody">
+
+<p>There are two acceptable formats for a basic
+conditional statement. One includes spaces between the
+parentheses and the condition, and one does not.</p>
+
+<p>The most common form is without spaces. Either is
+fine, but <em>be consistent</em>. If you are modifying a
+file, use the format that is already present. If you are
+writing new code, use the format that the other files in
+that directory or project use. If in doubt and you have
+no personal preference, do not add the spaces.</p>
+
+<pre>if (condition) {  // no spaces inside parentheses
+  ...  // 2 space indent.
+} else if (...) {  // The else goes on the same line as the closing brace.
+  ...
+} else {
+  ...
+}
+</pre>
+
+<p>If you prefer you may add spaces inside the
+parentheses:</p>
+
+<pre>if ( condition ) {  // spaces inside parentheses - rare
+  ...  // 2 space indent.
+} else {  // The else goes on the same line as the closing brace.
+  ...
+}
+</pre>
+
+<p>Note that in all cases you must have a space between
+the <code>if</code> and the open parenthesis. You must
+also have a space between the close parenthesis and the
+curly brace, if you're using one.</p>
+
+<pre class="badcode">if(condition) {   // Bad - space missing after IF.
+if (condition){   // Bad - space missing before {.
+if(condition){    // Doubly bad.
+</pre>
+
+<pre>if (condition) {  // Good - proper space after IF and before {.
+</pre>
+
+<p>Short conditional statements may be written on one
+line if this enhances readability. You may use this only
+when the line is brief and the statement does not use the
+<code>else</code> clause.</p>
+
+<pre>if (x == kFoo) return new Foo();
+if (x == kBar) return new Bar();
+</pre>
+
+<p>This is not allowed when the if statement has an
+<code>else</code>:</p>
+
+<pre class="badcode">// Not allowed - IF statement on one line when there is an ELSE clause
+if (x) DoThis();
+else DoThat();
+</pre>
+
+<p>In general, curly braces are not required for
+single-line statements, but they are allowed if you like
+them; conditional or loop statements with complex
+conditions or statements may be more readable with curly
+braces. Some
+projects require that an
+<code>if</code> must always always have an accompanying
+brace.</p>
+
+<pre>if (condition)
+  DoSomething();  // 2 space indent.
+
+if (condition) {
+  DoSomething();  // 2 space indent.
+}
+</pre>
+
+<p>However, if one part of an
+<code>if</code>-<code>else</code> statement uses curly
+braces, the other part must too:</p>
+
+<pre class="badcode">// Not allowed - curly on IF but not ELSE
+if (condition) {
+  foo;
+} else
+  bar;
+
+// Not allowed - curly on ELSE but not IF
+if (condition)
+  foo;
+else {
+  bar;
+}
+</pre>
+
+<pre>// Curly braces around both IF and ELSE required because
+// one of the clauses used braces.
+if (condition) {
+  foo;
+} else {
+  bar;
+}
+</pre>
+
+</div>
+
+<h3 id="Loops_and_Switch_Statements">Loops and Switch Statements</h3>
+
+<div class="summary">
+<p>Switch statements may use braces for blocks. Annotate
+non-trivial fall-through between cases.
+Braces are optional for single-statement loops.
+Empty loop bodies should use <code>{}</code> or <code>continue</code>.</p>
+</div>
+
+<div class="stylebody">
+
+<p><code>case</code> blocks in <code>switch</code>
+statements can have curly braces or not, depending on
+your preference. If you do include curly braces they
+should be placed as shown below.</p>
+
+<p>If not conditional on an enumerated value, switch
+statements should always have a <code>default</code> case
+(in the case of an enumerated value, the compiler will
+warn you if any values are not handled). If the default
+case should never execute, simply
+<code>assert</code>:</p>
+
+
+
+<div>
+<pre>switch (var) {
+  case 0: {  // 2 space indent
+    ...      // 4 space indent
+    break;
+  }
+  case 1: {
+    ...
+    break;
+  }
+  default: {
+    assert(false);
+  }
+}
+</pre>
+</div>
+
+
+
+
+
+<p> Braces are optional for single-statement loops.</p>
+
+<pre>for (int i = 0; i &lt; kSomeNumber; ++i)
+  printf("I love you\n");
+
+for (int i = 0; i &lt; kSomeNumber; ++i) {
+  printf("I take it back\n");
+}
+</pre>
+
+
+<p>Empty loop bodies should use <code>{}</code> or
+<code>continue</code>, but not a single semicolon.</p>
+
+<pre>while (condition) {
+  // Repeat test until it returns false.
+}
+for (int i = 0; i &lt; kSomeNumber; ++i) {}  // Good - empty body.
+while (condition) continue;  // Good - continue indicates no logic.
+</pre>
+
+<pre class="badcode">while (condition);  // Bad - looks like part of do/while loop.
+</pre>
+
+</div>
+
+<h3 id="Pointer_and_Reference_Expressions">Pointer and Reference Expressions</h3>
+
+<div class="summary">
+<p>No spaces around period or arrow. Pointer operators do not
+have trailing spaces.</p>
+</div>
+
+<div class="stylebody">
+
+<p>The following are examples of correctly-formatted
+pointer and reference expressions:</p>
+
+<pre>x = *p;
+p = &amp;x;
+x = r.y;
+x = r-&gt;y;
+</pre>
+
+<p>Note that:</p>
+
+<ul>
+  <li>There are no spaces around the period or arrow when
+  accessing a member.</li>
+
+   <li>Pointer operators have no space after the
+   <code>*</code> or <code>&amp;</code>.</li>
+</ul>
+
+<p>When declaring a pointer variable or argument, you may
+place the asterisk adjacent to either the type or to the
+variable name:</p>
+
+<pre>// These are fine, space preceding.
+char *c;
+const string &amp;str;
+
+// These are fine, space following.
+char* c;    // but remember to do "char* c, *d, *e, ...;"!
+const string&amp; str;
+</pre>
+
+<pre class="badcode">char * c;  // Bad - spaces on both sides of *
+const string &amp; str;  // Bad - spaces on both sides of &amp;
+</pre>
+
+<p>You should do this consistently within a single
+file,
+so, when modifying an existing file, use the style in
+that file.</p>
+
+</div>
+
+<h3 id="Boolean_Expressions">Boolean Expressions</h3>
+
+<div class="summary">
+<p>When you have a boolean expression that is longer than the
+<a href="#Line_Length">standard line length</a>, be
+consistent in how you break up the lines.</p>
+</div>
+
+<div class="stylebody">
+
+<p>In this example, the logical AND operator is always at
+the end of the lines:</p>
+
+<pre>if (this_one_thing &gt; this_other_thing &amp;&amp;
+    a_third_thing == a_fourth_thing &amp;&amp;
+    yet_another &amp;&amp; last_one) {
+  ...
+}
+</pre>
+
+<p>Note that when the code wraps in this example, both of
+the <code>&amp;&amp;</code> logical AND operators are at
+the end of the line. This is more common in Google code,
+though wrapping all operators at the beginning of the
+line is also allowed. Feel free to insert extra
+parentheses judiciously because they can be very helpful
+in increasing readability when used
+appropriately. Also note that you should always use
+the punctuation operators, such as
+<code>&amp;&amp;</code> and <code>~</code>, rather than
+the word operators, such as <code>and</code> and
+<code>compl</code>.</p>
+
+</div>
+
+<h3 id="Return_Values">Return Values</h3>
+
+<div class="summary">
+<p>Do not needlessly surround the <code>return</code>
+expression with parentheses.</p>
+</div>
+
+<div class="stylebody">
+
+<p>Use parentheses in <code>return expr;</code> only
+where you would use them in <code>x = expr;</code>.</p>
+
+<pre>return result;                  // No parentheses in the simple case.
+// Parentheses OK to make a complex expression more readable.
+return (some_long_condition &amp;&amp;
+        another_condition);
+</pre>
+
+<pre class="badcode">return (value);                // You wouldn't write var = (value);
+return(result);                // return is not a function!
+</pre>
+
+</div>
+
+
+
+<h3 id="Variable_and_Array_Initialization">Variable and Array Initialization</h3>
+
+<div class="summary">
+<p>Your choice of <code>=</code>, <code>()</code>, or
+<code>{}</code>.</p>
+</div>
+
+<div class="stylebody">
+
+<p>You may choose between <code>=</code>,
+<code>()</code>, and <code>{}</code>; the following are
+all correct:</p>
+
+<pre>int x = 3;
+int x(3);
+int x{3};
+string name = "Some Name";
+string name("Some Name");
+string name{"Some Name"};
+</pre>
+
+<p>Be careful when using a braced initialization list <code>{...}</code>
+on a type with an <code>std::initializer_list</code> constructor.
+A nonempty <i>braced-init-list</i> prefers the
+<code>std::initializer_list</code> constructor whenever
+possible. Note that empty braces <code>{}</code> are special, and
+will call a default constructor if available. To force the
+non-<code>std::initializer_list</code> constructor, use parentheses
+instead of braces.</p>
+
+<pre>vector&lt;int&gt; v(100, 1);  // A vector of 100 1s.
+vector&lt;int&gt; v{100, 1};  // A vector of 100, 1.
+</pre>
+
+<p>Also, the brace form prevents narrowing of integral
+types. This can prevent some types of programming
+errors.</p>
+
+<pre>int pi(3.14);  // OK -- pi == 3.
+int pi{3.14};  // Compile error: narrowing conversion.
+</pre>
+
+</div>
+
+<h3 id="Preprocessor_Directives">Preprocessor Directives</h3>
+
+<div class="summary">
+<p>The hash mark that starts a preprocessor directive should
+always be at the beginning of the line.</p>
+</div>
+
+<div class="stylebody">
+
+<p>Even when preprocessor directives are within the body
+of indented code, the directives should start at the
+beginning of the line.</p>
+
+<pre>// Good - directives at beginning of line
+  if (lopsided_score) {
+#if DISASTER_PENDING      // Correct -- Starts at beginning of line
+    DropEverything();
+# if NOTIFY               // OK but not required -- Spaces after #
+    NotifyClient();
+# endif
+#endif
+    BackToNormal();
+  }
+</pre>
+
+<pre class="badcode">// Bad - indented directives
+  if (lopsided_score) {
+    #if DISASTER_PENDING  // Wrong!  The "#if" should be at beginning of line
+    DropEverything();
+    #endif                // Wrong!  Do not indent "#endif"
+    BackToNormal();
+  }
+</pre>
+
+</div>
+
+<h3 id="Class_Format">Class Format</h3>
+
+<div class="summary">
+<p>Sections in <code>public</code>, <code>protected</code> and
+<code>private</code> order, each indented one space.</p>
+</div>
+
+<div class="stylebody">
+
+<p>The basic format for a class declaration (lacking the
+comments, see <a href="#Class_Comments">Class
+Comments</a> for a discussion of what comments are
+needed) is:</p>
+
+<pre>class MyClass : public OtherClass {
+ public:      // Note the 1 space indent!
+  MyClass();  // Regular 2 space indent.
+  explicit MyClass(int var);
+  ~MyClass() {}
+
+  void SomeFunction();
+  void SomeFunctionThatDoesNothing() {
+  }
+
+  void set_some_var(int var) { some_var_ = var; }
+  int some_var() const { return some_var_; }
+
+ private:
+  bool SomeInternalFunction();
+
+  int some_var_;
+  int some_other_var_;
+};
+</pre>
+
+<p>Things to note:</p>
+
+<ul>
+  <li>Any base class name should be on the same line as
+  the subclass name, subject to the 80-column limit.</li>
+
+  <li>The <code>public:</code>, <code>protected:</code>,
+  and <code>private:</code> keywords should be indented
+  one space.</li>
+
+  <li>Except for the first instance, these keywords
+  should be preceded by a blank line. This rule is
+  optional in small classes.</li>
+
+  <li>Do not leave a blank line after these
+  keywords.</li>
+
+  <li>The <code>public</code> section should be first,
+  followed by the <code>protected</code> and finally the
+  <code>private</code> section.</li>
+
+  <li>See <a href="#Declaration_Order">Declaration
+  Order</a> for rules on ordering declarations within
+  each of these sections.</li>
+</ul>
+
+</div>
+
+<h3 id="Constructor_Initializer_Lists">Constructor Initializer Lists</h3>
+
+<div class="summary">
+<p>Constructor initializer lists can be all on one line or
+with subsequent lines indented four spaces.</p>
+</div>
+
+<div class="stylebody">
+
+<p>There are two acceptable formats for initializer
+lists:</p>
+
+<pre>// When it all fits on one line:
+MyClass::MyClass(int var) : some_var_(var), some_other_var_(var + 1) {}
+</pre>
+
+<p>or</p>
+
+<pre>// When it requires multiple lines, indent 4 spaces, putting the colon on
+// the first initializer line:
+MyClass::MyClass(int var)
+    : some_var_(var),             // 4 space indent
+      some_other_var_(var + 1) {  // lined up
+  ...
+  DoSomething();
+  ...
+}
+</pre>
+
+</div>
+
+<h3 id="Namespace_Formatting">Namespace Formatting</h3>
+
+<div class="summary">
+<p>The contents of namespaces are not indented.</p>
+</div>
+
+<div class="stylebody">
+
+<p><a href="#Namespaces">Namespaces</a> do not add an
+extra level of indentation. For example, use:</p>
+
+<pre>namespace {
+
+void foo() {  // Correct.  No extra indentation within namespace.
+  ...
+}
+
+}  // namespace
+</pre>
+
+<p>Do not indent within a namespace:</p>
+
+<pre class="badcode">namespace {
+
+  // Wrong.  Indented when it should not be.
+  void foo() {
+    ...
+  }
+
+}  // namespace
+</pre>
+
+<p>When declaring nested namespaces, put each namespace
+on its own line.</p>
+
+<pre>namespace foo {
+namespace bar {
+</pre>
+
+</div>
+
+<h3 id="Horizontal_Whitespace">Horizontal Whitespace</h3>
+
+<div class="summary">
+<p>Use of horizontal whitespace depends on location. Never put
+trailing whitespace at the end of a line.</p>
+</div>
+
+<div class="stylebody">
+
+<h4 class="stylepoint_subsection">General</h4>
+
+<pre>void f(bool b) {  // Open braces should always have a space before them.
+  ...
+int i = 0;  // Semicolons usually have no space before them.
+// Spaces inside braces for braced-init-list are optional.  If you use them,
+// put them on both sides!
+int x[] = { 0 };
+int x[] = {0};
+
+// Spaces around the colon in inheritance and initializer lists.
+class Foo : public Bar {
+ public:
+  // For inline function implementations, put spaces between the braces
+  // and the implementation itself.
+  Foo(int b) : Bar(), baz_(b) {}  // No spaces inside empty braces.
+  void Reset() { baz_ = 0; }  // Spaces separating braces from implementation.
+  ...
+</pre>
+
+<p>Adding trailing whitespace can cause extra work for
+others editing the same file, when they merge, as can
+removing existing trailing whitespace. So: Don't
+introduce trailing whitespace. Remove it if you're
+already changing that line, or do it in a separate
+clean-up
+operation (preferably when no-one
+else is working on the file).</p>
+
+<h4 class="stylepoint_subsection">Loops and Conditionals</h4>
+
+<pre>if (b) {          // Space after the keyword in conditions and loops.
+} else {          // Spaces around else.
+}
+while (test) {}   // There is usually no space inside parentheses.
+switch (i) {
+for (int i = 0; i &lt; 5; ++i) {
+// Loops and conditions may have spaces inside parentheses, but this
+// is rare.  Be consistent.
+switch ( i ) {
+if ( test ) {
+for ( int i = 0; i &lt; 5; ++i ) {
+// For loops always have a space after the semicolon.  They may have a space
+// before the semicolon, but this is rare.
+for ( ; i &lt; 5 ; ++i) {
+  ...
+
+// Range-based for loops always have a space before and after the colon.
+for (auto x : counts) {
+  ...
+}
+switch (i) {
+  case 1:         // No space before colon in a switch case.
+    ...
+  case 2: break;  // Use a space after a colon if there's code after it.
+</pre>
+
+<h4 class="stylepoint_subsection">Operators</h4>
+
+<pre>// Assignment operators always have spaces around them.
+x = 0;
+
+// Other binary operators usually have spaces around them, but it's
+// OK to remove spaces around factors.  Parentheses should have no
+// internal padding.
+v = w * x + y / z;
+v = w*x + y/z;
+v = w * (x + z);
+
+// No spaces separating unary operators and their arguments.
+x = -5;
+++x;
+if (x &amp;&amp; !y)
+  ...
+</pre>
+
+<h4 class="stylepoint_subsection">Templates and Casts</h4>
+
+<pre>// No spaces inside the angle brackets (&lt; and &gt;), before
+// &lt;, or between &gt;( in a cast
+vector&lt;string&gt; x;
+y = static_cast&lt;char*&gt;(x);
+
+// Spaces between type and pointer are OK, but be consistent.
+vector&lt;char *&gt; x;
+set&lt;list&lt;string&gt;&gt; x;        // Permitted in C++11 code.
+set&lt;list&lt;string&gt; &gt; x;       // C++03 required a space in &gt; &gt;.
+
+// You may optionally use symmetric spacing in &lt; &lt;.
+set&lt; list&lt;string&gt; &gt; x;
+</pre>
+
+</div>
+
+<h3 id="Vertical_Whitespace">Vertical Whitespace</h3>
+
+<div class="summary">
+<p>Minimize use of vertical whitespace.</p>
+</div>
+
+<div class="stylebody">
+
+<p>This is more a principle than a rule: don't use blank
+lines when you don't have to. In particular, don't put
+more than one or two blank lines between functions,
+resist starting functions with a blank line, don't end
+functions with a blank line, and be discriminating with
+your use of blank lines inside functions.</p>
+
+<p>The basic principle is: The more code that fits on one
+screen, the easier it is to follow and understand the
+control flow of the program. Of course, readability can
+suffer from code being too dense as well as too spread
+out, so use your judgement. But in general, minimize use
+of vertical whitespace.</p>
+
+<p>Some rules of thumb to help when blank lines may be
+useful:</p>
+
+<ul>
+  <li>Blank lines at the beginning or end of a function
+  very rarely help readability.</li>
+
+  <li>Blank lines inside a chain of if-else blocks may
+  well help readability.</li>
+</ul>
+
+</div>
+
+<h2 id="Exceptions_to_the_Rules">Exceptions to the Rules</h2>
+
+<p>The coding conventions described above are mandatory.
+However, like all good rules, these sometimes have exceptions,
+which we discuss here.</p>
+
+
+
+<div>
+<h3 id="Existing_Non-conformant_Code">Existing Non-conformant Code</h3>
+
+<div class="summary">
+<p>You may diverge from the rules when dealing with code that
+does not conform to this style guide.</p>
+</div>
+
+<div class="stylebody">
+
+<p>If you find yourself modifying code that was written
+to specifications other than those presented by this
+guide, you may have to diverge from these rules in order
+to stay consistent with the local conventions in that
+code. If you are in doubt about how to do this, ask the
+original author or the person currently responsible for
+the code. Remember that <em>consistency</em> includes
+local consistency, too.</p>
+
+</div>
+</div>
+
+
+<h2 class="ignoreLink">Parting Words</h2>
+
+<p>Use common sense and <em>BE CONSISTENT</em>.</p>
+
+<p>If you are editing code, take a few minutes to look at the
+code around you and determine its style. If they use spaces
+around their <code>if</code> clauses, you should, too. If their
+comments have little boxes of stars around them, make your
+comments have little boxes of stars around them too.</p>
+
+<p>The point of having style guidelines is to have a common
+vocabulary of coding so people can concentrate on what you are
+saying, rather than on how you are saying it. We present global
+style rules here so people know the vocabulary. But local style
+is also important. If code you add to a file looks drastically
+different from the existing code around it, the discontinuity
+throws readers out of their rhythm when they go to read it. Try
+to avoid this.</p>
+
+
+
+<p>OK, enough writing about writing code; the code itself is much
+more interesting. Have fun!</p>
+
+<hr>
+
+<p style="text-align:right; font-style:italic;">Revision 4.45</p>
+
+</div>
+</body></html>
diff --git a/styleguide/eclipse-cpp-google-style.xml b/styleguide/eclipse-cpp-google-style.xml
new file mode 100644
index 0000000..aa05a81
--- /dev/null
+++ b/styleguide/eclipse-cpp-google-style.xml
@@ -0,0 +1,167 @@
+<?xml version="1.0" encoding="UTF-8" standalone="no"?>
+<profiles version="1">
+<profile kind="CodeFormatterProfile" name="Google C++" version="1">
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_paren_in_method_declaration" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_paren_in_for" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_new_line_in_empty_block" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.lineSplit" value="80"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_member_access" value="16"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_comma_in_base_types" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.keep_else_statement_on_same_line" value="false"/>
+<setting id="org.eclipse.cdt.core.formatter.indent_switchstatements_compare_to_switch" value="true"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_constructor_initializer_list" value="83"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_brace_in_array_initializer" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_comma_in_method_declaration_parameters" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_paren_in_if" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_paren_in_parenthesized_expression" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_paren_in_exception_specification" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_comma_in_base_types" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.indent_body_declarations_compare_to_access_specifier" value="true"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_paren_in_exception_specification" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_comma_in_template_arguments" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_brace_in_block" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_paren_in_method_declaration" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.use_tabs_only_for_leading_indentations" value="false"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_colon_in_labeled_statement" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_colon_in_case" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.comment.min_distance_between_code_and_line_comment" value="2"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_comma_in_array_initializer" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_comma_in_enum_declarations" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_expressions_in_array_initializer" value="16"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_comma_in_declarator_list" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_bracket" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_paren_in_for" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_prefix_operator" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.tabulation.size" value="2"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_new_line_before_else_in_if_statement" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_enumerator_list" value="51"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_paren_in_parenthesized_expression" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_between_empty_parens_in_method_declaration" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_paren_in_switch" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_declarator_list" value="16"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_paren_in_parenthesized_expression" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.indent_empty_lines" value="false"/>
+<setting id="org.eclipse.cdt.core.formatter.indent_switchstatements_compare_to_cases" value="true"/>
+<setting id="org.eclipse.cdt.core.formatter.keep_empty_array_initializer_on_one_line" value="false"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_brace_in_method_declaration" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.put_empty_statement_on_new_line" value="true"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_brace_in_switch" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_paren_in_cast" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_between_empty_braces_in_array_initializer" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.brace_position_for_method_declaration" value="end_of_line"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_paren_in_while" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_question_in_conditional" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_semicolon" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_closing_angle_bracket_in_template_arguments" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_colon_in_base_clause" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.indent_breaks_compare_to_cases" value="true"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_unary_operator" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.join_wrapped_lines" value="true"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_comma_in_declarator_list" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_arguments_in_method_invocation" value="18"/>
+<setting id="org.eclipse.cdt.core.formatter.comment.never_indent_line_comments_on_first_column" value="true"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_paren_in_while" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_between_empty_brackets" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_bracket" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_parameters_in_method_declaration" value="18"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_new_line_before_closing_brace_in_array_initializer" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.number_of_empty_lines_to_preserve" value="1"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_paren_in_method_invocation" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_brace_in_array_initializer" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_semicolon_in_for" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_colon_in_conditional" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.brace_position_for_block" value="end_of_line"/>
+<setting id="org.eclipse.cdt.core.formatter.comment.preserve_white_space_between_code_and_line_comments" value="true"/>
+<setting id="org.eclipse.cdt.core.formatter.brace_position_for_type_declaration" value="end_of_line"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_assignment_operator" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_angle_bracket_in_template_arguments" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_comma_in_expression_list" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_angle_bracket_in_template_parameters" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.continuation_indentation" value="2"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_expression_list" value="0"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_paren_in_method_declaration" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_comma_in_template_parameters" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_colon_in_default" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_binary_operator" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_conditional_expression" value="34"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_between_empty_parens_in_method_invocation" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_comma_in_array_initializer" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_paren_in_if" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.format_guardian_clause_on_one_line" value="false"/>
+<setting id="org.eclipse.cdt.core.formatter.indent_access_specifier_extra_spaces" value="1"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_paren_in_cast" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.indent_access_specifier_compare_to_type_header" value="false"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_brace_in_type_declaration" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.continuation_indentation_for_array_initializer" value="2"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_colon_in_labeled_statement" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_comma_in_method_declaration_parameters" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_semicolon_in_for" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_paren_in_method_invocation" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.indent_body_declarations_compare_to_namespace_header" value="false"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_compact_if" value="0"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_assignment_operator" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_closing_brace_in_block" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_brace_in_array_initializer" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_new_line_at_end_of_file_if_missing" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_assignment" value="16"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_conditional_expression_chain" value="18"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_comma_in_template_parameters" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_comma_in_expression_list" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_question_in_conditional" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_paren_in_exception_specification" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_binary_operator" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_new_line_before_identifier_in_function_declaration" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_base_clause_in_type_declaration" value="16"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_comma_in_method_declaration_throws" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_between_empty_parens_in_exception_specification" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_comma_in_method_invocation_arguments" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.indent_declaration_compare_to_template_header" value="false"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_unary_operator" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_paren_in_switch" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.indent_statements_compare_to_body" value="true"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_comma_in_method_declaration_throws" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_binary_expression" value="16"/>
+<setting id="org.eclipse.cdt.core.formatter.indent_statements_compare_to_block" value="true"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_comma_in_template_arguments" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_new_line_before_catch_in_try_statement" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_throws_clause_in_method_declaration" value="16"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_paren_in_method_invocation" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_closing_paren_in_cast" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_paren_in_catch" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_angle_bracket_in_template_parameters" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.tabulation.char" value="space"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_angle_bracket_in_template_parameters" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_new_line_before_colon_in_constructor_initializer_list" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_paren_in_while" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_comma_in_method_invocation_arguments" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.brace_position_for_block_in_case" value="end_of_line"/>
+<setting id="org.eclipse.cdt.core.formatter.compact_else_if" value="true"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_postfix_operator" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_new_line_after_template_declaration" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_colon_in_base_clause" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_paren_in_catch" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.keep_then_statement_on_same_line" value="false"/>
+<setting id="org.eclipse.cdt.core.formatter.brace_position_for_switch" value="end_of_line"/>
+<setting id="org.eclipse.cdt.core.formatter.alignment_for_overloaded_left_shift_chain" value="18"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_paren_in_if" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_paren_in_switch" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.keep_imple_if_on_one_line" value="false"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_new_line_after_opening_brace_in_array_initializer" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.indentation.size" value="2"/>
+<setting id="org.eclipse.cdt.core.formatter.brace_position_for_namespace_declaration" value="end_of_line"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_colon_in_conditional" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_comma_in_enum_declarations" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_prefix_operator" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_angle_bracket_in_template_arguments" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.brace_position_for_array_initializer" value="end_of_line"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_colon_in_case" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_paren_in_catch" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_brace_in_namespace_declaration" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_postfix_operator" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_closing_bracket" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_new_line_before_while_in_do_statement" value="do not insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_before_opening_paren_in_for" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_closing_angle_bracket_in_template_parameters" value="insert"/>
+<setting id="org.eclipse.cdt.core.formatter.insert_space_after_opening_angle_bracket_in_template_arguments" value="do not insert"/>
+</profile>
+</profiles>
diff --git a/styleguide/eclipse-java-google-style.xml b/styleguide/eclipse-java-google-style.xml
new file mode 100644
index 0000000..b3177d3
--- /dev/null
+++ b/styleguide/eclipse-java-google-style.xml
@@ -0,0 +1,337 @@
+<?xml version="1.0" encoding="UTF-8" standalone="no"?>
+<profiles version="12">
+<profile kind="CodeFormatterProfile" name="GoogleStyle" version="12">
+<setting id="org.eclipse.jdt.core.formatter.comment.insert_new_line_before_root_tags" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.disabling_tag" value="@formatter:off"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_annotation" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_type_parameters" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_brace_in_type_declaration" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_type_arguments" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.brace_position_for_anonymous_type_declaration" value="end_of_line"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_colon_in_case" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_brace_in_array_initializer" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.new_lines_at_block_boundaries" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_cascading_method_invocation_with_arguments.count_dependent" value="16|-1|16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_in_empty_annotation_declaration" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_annotation" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.blank_lines_before_field" value="0"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_while" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.use_on_off_tags" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.wrap_prefer_two_fragments" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_between_empty_parens_in_annotation_type_member_declaration" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_before_else_in_if_statement" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_prefix_operator" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.keep_else_statement_on_same_line" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_ellipsis" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.insert_new_line_for_parameter" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.wrap_comment_inline_tags" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_brace_in_annotation_type_declaration" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.indent_breaks_compare_to_cases" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_at_in_annotation" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_local_variable_declaration" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_multiple_fields" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_annotations_on_parameter" value="1040"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_expressions_in_array_initializer" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_annotations_on_type.count_dependent" value="1585|-1|1585"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_conditional_expression" value="80"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_for" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_multiple_fields.count_dependent" value="16|-1|16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_binary_operator" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_question_in_wildcard" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.brace_position_for_array_initializer" value="end_of_line"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_between_empty_parens_in_enum_constant" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_before_finally_in_try_statement" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_after_annotation_on_local_variable" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_before_catch_in_try_statement" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_while" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.blank_lines_after_package" value="1"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_arguments_in_qualified_allocation_expression.count_dependent" value="16|4|80"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_throws_clause_in_method_declaration.count_dependent" value="16|4|48"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_type_parameters" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.continuation_indentation" value="2"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_superinterfaces_in_enum_declaration.count_dependent" value="16|4|49"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_postfix_operator" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_arguments_in_method_invocation" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_angle_bracket_in_type_arguments" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_superinterfaces" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.blank_lines_before_new_chunk" value="1"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_binary_operator" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.blank_lines_before_package" value="0"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_cascading_method_invocation_with_arguments" value="16"/>
+<setting id="org.eclipse.jdt.core.compiler.source" value="1.8"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_throws_clause_in_constructor_declaration.count_dependent" value="16|4|48"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_enum_constant_arguments" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_constructor_declaration" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.format_line_comments" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_closing_angle_bracket_in_type_arguments" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_enum_declarations" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.join_wrapped_lines" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_brace_in_block" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_arguments_in_explicit_constructor_call" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.wrap_non_simple_local_variable_annotation" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_method_invocation_arguments" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.align_type_members_on_columns" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.blank_lines_before_member_type" value="0"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_enum_constant" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_enum_constants.count_dependent" value="16|5|48"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_for" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_brace_in_method_declaration" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_selector_in_method_invocation" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_switch" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_unary_operator" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_colon_in_case" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.indent_parameter_description" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_method_declaration" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_switch" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_brace_in_enum_declaration" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_angle_bracket_in_type_parameters" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.clear_blank_lines_in_block_comment" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_in_empty_type_declaration" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.lineSplit" value="80"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_if" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_selector_in_method_invocation.count_dependent" value="16|4|48"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_between_brackets_in_array_type_reference" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_parenthesized_expression" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_explicitconstructorcall_arguments" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_brace_in_constructor_declaration" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.blank_lines_before_first_class_body_declaration" value="0"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_after_annotation_on_method" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.indentation.size" value="4"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_between_empty_parens_in_method_declaration" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.enabling_tag" value="@formatter:on"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_enum_constant" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_annotations_on_package" value="1585"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_superclass_in_type_declaration" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_assignment" value="16"/>
+<setting id="org.eclipse.jdt.core.compiler.problem.assertIdentifier" value="error"/>
+<setting id="org.eclipse.jdt.core.formatter.tabulation.char" value="space"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_semicolon_in_try_resources" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_constructor_declaration_parameters" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_prefix_operator" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.indent_statements_compare_to_body" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.blank_lines_before_method" value="1"/>
+<setting id="org.eclipse.jdt.core.formatter.wrap_outer_expressions_when_nested" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.wrap_non_simple_type_annotation" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.format_guardian_clause_on_one_line" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_colon_in_for" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_field_declaration" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_cast" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_parameters_in_constructor_declaration" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_colon_in_labeled_statement" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.brace_position_for_annotation_type_declaration" value="end_of_line"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_in_empty_method_body" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_method_declaration" value="0"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_try" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_method_invocation" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_bracket_in_array_allocation_expression" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_brace_in_enum_constant" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_annotation" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_at_in_annotation_type_declaration" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_method_declaration_throws" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_if" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.brace_position_for_switch" value="end_of_line"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_method_declaration_throws" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_parenthesized_expression_in_return" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_annotation" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_question_in_conditional" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_question_in_wildcard" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_try" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_bracket_in_array_allocation_expression" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.preserve_white_space_between_code_and_line_comments" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_parenthesized_expression_in_throw" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_type_arguments" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.compiler.problem.enumIdentifier" value="error"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_generic_type_arguments" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.indent_switchstatements_compare_to_switch" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.comment_new_line_at_start_of_html_paragraph" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_ellipsis" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.brace_position_for_block" value="end_of_line"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comment_prefix" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_for_inits" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.brace_position_for_method_declaration" value="end_of_line"/>
+<setting id="org.eclipse.jdt.core.formatter.compact_else_if" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.wrap_non_simple_parameter_annotation" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.wrap_before_or_operator_multicatch" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_array_initializer" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_for_increments" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_annotations_on_method" value="1585"/>
+<setting id="org.eclipse.jdt.core.formatter.format_line_comment_starting_on_first_column" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_bracket_in_array_reference" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_after_annotation_on_field" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.indent_root_tags" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.brace_position_for_enum_constant" value="end_of_line"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_enum_declarations" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_union_type_in_multicatch" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_explicitconstructorcall_arguments" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_brace_in_switch" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_method_declaration_parameters" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_superinterfaces" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_allocation_expression" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.tabulation.size" value="2"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_bracket_in_array_type_reference" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_after_opening_brace_in_array_initializer" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_closing_brace_in_block" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_bracket_in_array_reference" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_in_empty_enum_constant" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_angle_bracket_in_type_arguments" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_constructor_declaration" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_constructor_declaration_throws" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_if" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_arguments_in_method_invocation.count_dependent" value="16|5|80"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.clear_blank_lines_in_javadoc_comment" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_annotations_on_parameter.count_dependent" value="1040|-1|1040"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_throws_clause_in_constructor_declaration" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_assignment_operator" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_assignment_operator" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_annotations_on_package.count_dependent" value="1585|-1|1585"/>
+<setting id="org.eclipse.jdt.core.formatter.indent_empty_lines" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_synchronized" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_closing_paren_in_cast" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_method_declaration_parameters" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.force_if_else_statement_brace" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.brace_position_for_block_in_case" value="end_of_line"/>
+<setting id="org.eclipse.jdt.core.formatter.number_of_empty_lines_to_preserve" value="3"/>
+<setting id="org.eclipse.jdt.core.formatter.wrap_non_simple_package_annotation" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_method_declaration" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_catch" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_constructor_declaration" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_method_invocation" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_bracket_in_array_reference" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_arguments_in_qualified_allocation_expression" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_arguments_in_annotation.count_dependent" value="16|-1|16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_and_in_type_parameter" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_annotations_on_type" value="1585"/>
+<setting id="org.eclipse.jdt.core.compiler.compliance" value="1.8"/>
+<setting id="org.eclipse.jdt.core.formatter.continuation_indentation_for_array_initializer" value="2"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_between_empty_brackets_in_array_allocation_expression" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_at_in_annotation_type_declaration" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_arguments_in_allocation_expression" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_cast" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_unary_operator" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_new_anonymous_class" value="20"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_angle_bracket_in_parameterized_type_reference" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_annotations_on_local_variable.count_dependent" value="1585|-1|1585"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_brace_in_anonymous_type_declaration" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.keep_empty_array_initializer_on_one_line" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_in_empty_enum_declaration" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_annotations_on_field.count_dependent" value="1585|-1|1585"/>
+<setting id="org.eclipse.jdt.core.formatter.keep_imple_if_on_one_line" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_constructor_declaration_parameters" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_closing_angle_bracket_in_type_parameters" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_colon_in_labeled_statement" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_at_end_of_file_if_missing" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_colon_in_for" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_parameterized_type_reference" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_parameters_in_constructor_declaration.count_dependent" value="16|5|80"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_superinterfaces_in_type_declaration" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.brace_position_for_enum_declaration" value="end_of_line"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_binary_expression" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_while" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_after_annotation_on_type" value="insert"/>
+<setting id="org.eclipse.jdt.core.compiler.codegen.inlineJsrBytecode" value="enabled"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_try" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.put_empty_statement_on_new_line" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_after_label" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_after_annotation_on_parameter" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_angle_bracket_in_type_parameters" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_between_empty_parens_in_method_invocation" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.format_javadoc_comments" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_arguments_in_enum_constant" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_before_while_in_do_statement" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_arguments_in_enum_constant.count_dependent" value="16|-1|16"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.line_length" value="100"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_after_annotation_on_package" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.blank_lines_between_import_groups" value="1"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_enum_constant_arguments" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_semicolon" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.brace_position_for_constructor_declaration" value="end_of_line"/>
+<setting id="org.eclipse.jdt.core.formatter.number_of_blank_lines_at_beginning_of_method_body" value="0"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_colon_in_conditional" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.indent_body_declarations_compare_to_type_header" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_annotation_type_member_declaration" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.wrap_before_binary_operator" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.blank_lines_between_type_declarations" value="2"/>
+<setting id="org.eclipse.jdt.core.formatter.indent_body_declarations_compare_to_enum_declaration_header" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_synchronized" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_superinterfaces_in_enum_declaration" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.indent_statements_compare_to_block" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.join_lines_in_comments" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_question_in_conditional" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_multiple_field_declarations" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_compact_if" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_for_inits" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.indent_switchstatements_compare_to_cases" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_array_initializer" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_colon_in_default" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_and_in_type_parameter" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_between_empty_parens_in_constructor_declaration" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.blank_lines_before_imports" value="0"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_colon_in_assert" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_annotations_on_field" value="1585"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.format_html" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_throws_clause_in_method_declaration" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_angle_bracket_in_type_parameters" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_bracket_in_array_allocation_expression" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_in_empty_anonymous_type_declaration" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_colon_in_conditional" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_angle_bracket_in_parameterized_type_reference" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_for" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_expressions_in_array_initializer.count_dependent" value="16|5|80"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_postfix_operator" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.format_source_code" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_synchronized" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_allocation_expression" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_constructor_declaration_throws" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_parameters_in_method_declaration" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_brace_in_array_initializer" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.compiler.codegen.targetPlatform" value="1.8"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_resources_in_try" value="80"/>
+<setting id="org.eclipse.jdt.core.formatter.use_tabs_only_for_leading_indentations" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_arguments_in_annotation" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.format_header" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.format_block_comments" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_enum_constant" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_enum_constants" value="0"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_parenthesized_expression" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.indent_body_declarations_compare_to_annotation_declaration_header" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_new_line_in_empty_block" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_parenthesized_expression" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_catch" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_multiple_local_declarations" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_superinterfaces_in_type_declaration.count_dependent" value="16|4|48"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_switch" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_comma_in_for_increments" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_annotations_on_method.count_dependent" value="1585|-1|1585"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_method_invocation" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_colon_in_assert" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.brace_position_for_type_declaration" value="end_of_line"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_brace_in_array_initializer" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_between_empty_braces_in_array_initializer" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_binary_expression.count_dependent" value="16|-1|16"/>
+<setting id="org.eclipse.jdt.core.formatter.wrap_non_simple_member_annotation" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_annotations_on_local_variable" value="1585"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_opening_paren_in_method_declaration" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_semicolon_in_for" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_arguments_in_explicit_constructor_call.count_dependent" value="16|5|80"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_paren_in_catch" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_angle_bracket_in_parameterized_type_reference" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_multiple_field_declarations" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_closing_paren_in_annotation" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_generic_type_arguments.count_dependent" value="16|-1|16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_parameterized_type_reference" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_arguments_in_allocation_expression.count_dependent" value="16|5|80"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_method_invocation_arguments" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_parameters_in_method_declaration.count_dependent" value="16|5|80"/>
+<setting id="org.eclipse.jdt.core.formatter.comment.new_lines_at_javadoc_boundaries" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.blank_lines_after_imports" value="1"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_comma_in_multiple_local_declarations" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.indent_body_declarations_compare_to_enum_constant_header" value="true"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_after_semicolon_in_for" value="insert"/>
+<setting id="org.eclipse.jdt.core.formatter.never_indent_line_comments_on_first_column" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_semicolon_in_try_resources" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.alignment_for_for_statement" value="16"/>
+<setting id="org.eclipse.jdt.core.formatter.insert_space_before_opening_angle_bracket_in_type_arguments" value="do not insert"/>
+<setting id="org.eclipse.jdt.core.formatter.never_indent_block_comments_on_first_column" value="false"/>
+<setting id="org.eclipse.jdt.core.formatter.keep_then_statement_on_same_line" value="false"/>
+</profile>
+</profiles>
diff --git a/styleguide/include/link.png b/styleguide/include/link.png
new file mode 100644
index 0000000..75d5c7b
--- /dev/null
+++ b/styleguide/include/link.png
Binary files differ
diff --git a/styleguide/include/styleguide.css b/styleguide/include/styleguide.css
new file mode 100644
index 0000000..ef62024
--- /dev/null
+++ b/styleguide/include/styleguide.css
@@ -0,0 +1,261 @@
+/* General CSS */
+
+body {
+  background-color: #fff;
+  color: #333;
+  font-family: sans-serif;
+  font-size: 10pt;
+  margin-right: 100px;
+  margin-left: 100px;
+}
+
+h1 {
+  text-align: center;
+  font-size: 18pt;
+}
+
+h1, h2, h3, h4, h5, h6 {
+  color: #06c;
+  margin-top: 2em;
+  margin-bottom: 1em;
+  padding: 25px;
+  font-weight:bold;
+}
+
+h2,
+h3,
+h4,
+h5,
+h6 {
+  margin-top:1.5em;
+  margin-bottom:.75em;
+}
+
+h1 {font-size:200%;}
+h2 {font-size:167%;}
+h3 {font-size:133%;}
+h4 {font-size:120%;}
+h5 {font-size:110%;}
+
+
+table {
+  border: 1px solid #bbb;
+  border-spacing: 0;
+  border-collapse: collapse;
+  margin: 0 0 1.5em;
+  vertical-align: middle;
+  width: 100%
+}
+
+td, th {
+  border: 1px solid #ccc;
+  padding: 2px 12px;
+  font-size: 10pt;
+}
+
+code, samp, var {
+  background-color:#FAFAFA;
+  white-space: nowrap
+}
+
+pre {
+  padding:6px 10px;
+  background-color:#FAFAFA;
+  border:1px solid #bbb;
+  overflow:auto;
+}
+
+pre.prettyprint {
+  padding:6px 10px !important;
+  border:1px solid #bbb !important;
+}
+
+code.bad, code.badcode {
+  color: magenta;
+}
+
+pre.bad, pre.badcode {
+  background-color:#ffe6d8;
+  border-top:1px inset #a03;
+  border-left:1px inset #a03;
+}
+
+hr {
+  margin-top: 3.5em;
+  border-width: 1px;
+  color: #fff;
+}
+
+/* TOC CSS */
+
+table.columns {
+  border: none;
+}
+
+td.two_columns {
+  -webkit-column-count: 2;
+  column-count: 2;
+}
+
+.toc_category {
+  font-size: 10pt;
+  padding-top: 1em;
+  padding-bottom: 1em;
+  border-left-width: 2px;
+  border-right-width: 2px;
+  border-color: grey;
+}
+
+.toc_stylepoint {
+  font-size: 10pt;
+  padding-top: 1em;
+  padding-bottom: 1em;
+}
+
+li.toc_entry {
+  padding-right: 1em;
+  display: inline;
+  list-style-type: none;
+}
+
+/*
+ * This space is required to trigger the linewrap on the links
+ * at href boundaries
+ */
+li.toc_entry::after {
+    content: " ";
+  }
+
+li.toc_entry a {
+  white-space: nowrap;
+}
+
+/* Horizontal TOC */
+.toc td, .toc th {
+  border-width: 1px 5px;
+  overflow: hidden;
+}
+
+/* Vertical TOC */
+
+.toc td.two_columns {
+  border-width: 0px;
+}
+
+/* Special Sections */
+
+address {
+  text-align: right;
+}
+
+.revision {
+  text-align: right;
+}
+
+.headerbox {
+  margin-left: 50%;
+  font-size: 75%;
+}
+
+.legend {
+  padding-top: 1em;
+  margin-left: 50%;
+  font-size: 10pt;
+}
+
+.link_button {
+  float: left;
+  display: none;
+  background-color: #f8f8ff;
+  border-color: #f0f0ff;
+  border-style: solid;
+  border-width: 1px;
+  font-size: 75%;
+  margin-top: 0;
+  margin-left: -50px;
+  padding: 24px;
+  border-radius: 3px;
+  -webkit-border-radius: 3px;
+  -moz-border-radius: 3px;
+}
+
+.ignoreLink {
+  padding: 0px;
+}
+
+.divider{
+    width:5px;
+    height:auto;
+    display:inline-block;
+}
+
+/* Style Guide semantic CSS */
+
+.summary {
+  margin-top: 1em;
+  margin-bottom: 1em;
+}
+
+.stylebody {
+  margin-top: 1em;
+  margin-bottom: 1em;
+}
+
+.stylepoint_section {
+  display: block;
+  margin-bottom: 1em;
+  font-family: sans-serif;
+  font-weight: bold;
+}
+
+.stylepoint_subsection {
+  display: block;
+  margin-bottom: 1em;
+}
+
+.stylepoint_subsubsection {
+  display: block;
+  margin-bottom: 1em;
+}
+
+.definition:before {
+  content: "Definition: ";
+  font-weight: bold;
+  display: block;
+  margin-bottom: 1em;
+}
+
+.pros:before {
+  content: "Pros: ";
+  font-weight: bold;
+  display: block;
+  margin-bottom: 1em;
+}
+
+.cons:before {
+  content: "Cons: ";
+  font-weight: bold;
+  display: block;
+  margin-bottom: 1em;
+}
+
+.decision:before {
+  content: "Decision: ";
+  font-weight: bold;
+  display: block;
+  margin-bottom: 1em;
+}
+
+.exception:before {
+  content: "Exception: ";
+  font-weight: bold;
+  display: block;
+  margin-bottom: 1em;
+}
+
+.note:before {
+  content: "Note: ";
+  font-weight: bold;
+  display: block;
+  margin-bottom: 1em;
+}
diff --git a/styleguide/include/styleguide.js b/styleguide/include/styleguide.js
new file mode 100644
index 0000000..accb779
--- /dev/null
+++ b/styleguide/include/styleguide.js
@@ -0,0 +1,289 @@
+TocTypeEnum = {
+  VERTICAL: 1,
+  HORIZONTAL: 2
+};
+
+function CreateTOC(tocElement) {
+
+  // Find the toc element DIV. We'll place our TOC there.
+  var toc = document.getElementById(tocElement);
+
+  var tocTypeClass = toc.className;
+  var tocType;
+
+  switch (tocTypeClass) {
+      case 'horizontal_toc':
+        tocType = TocTypeEnum.HORIZONTAL;
+        break;
+      case 'vertical_toc':
+        tocType = TocTypeEnum.VERTICAL;
+        break;
+      default:
+        tocType = TocTypeEnum.VERTICAL;
+        break;
+  }
+
+  // If toc_levels is defined, set headingLevels to it.
+  // Otherwise, use default value of "h2,h3"
+  var headingLevels;
+  if (typeof toc_levels === 'undefined') {
+    headingLevels = 'h2,h3';
+  } else {
+
+  }
+
+  // Collect all section heading elements in an array
+  var headings = document.querySelectorAll(headingLevels);
+
+  // Add TOC title elements
+  var tocHeadingDiv = document.createElement('div');
+  toc.appendChild(tocHeadingDiv);
+  tocHeadingDiv.className = 'toc_title';
+  var tocHeading = document.createElement('h3');
+  toc.appendChild(tocHeading);
+  tocHeading.className = 'ignoreLink';
+  tocHeading.id = 'toc';
+  var tocText = document.createTextNode('Table of Contents');
+  tocHeading.appendChild(tocText);
+
+  // Add table and tbody
+  var tocTable = document.createElement('table');
+  if (tocType == TocTypeEnum.VERTICAL) {
+    tocTable.className = 'columns';
+  }
+  toc.appendChild(tocTable);
+
+  var tbody_element = document.createElement('tbody');
+  tbody_element.setAttribute('valign', 'top');
+  tbody_element.className = 'toc';
+  tocTable.appendChild(tbody_element);
+
+  // Get the highest level heading
+  var firstHeading = headings[0];
+  var masterLevel = parseInt(headingLevels.charAt(1));
+
+  // Get the lowest heading level
+  var lowestLevel = parseInt(headingLevels.charAt(headingLevels - 1));
+
+  switch (tocType) {
+    case TocTypeEnum.HORIZONTAL:
+        CreateHorizontalTOC(headings, masterLevel, lowestLevel, tbody_element);
+        break;
+    case TocTypeEnum.VERTICAL:
+        CreateVerticalTOC(headings, masterLevel, lowestLevel, tbody_element);
+        break;
+    default:
+   }
+}
+
+function CreateHorizontalTOC(
+             headings, masterLevel, lowestLevel, tbody_element) {
+
+  // Initialize the header counter
+  var h = 0;
+  var ignoreChildren = false;
+
+  while (h < headings.length) {
+    // Get current heading
+    var heading = headings[h];
+
+    // Get the current heading level
+    var level = parseInt(heading.tagName.charAt(1));
+
+    if (isNaN(level) || level < 1 || level > lowestLevel) continue;
+
+    // If level is a masterLevel, make it a TOC parent category
+    if ((level == masterLevel) && (!hasClass(heading, 'ignoreLink'))) {
+      toc_current_row = AddTOCMaster(tbody_element, heading);
+      ignoreChildren = false;
+    }
+
+    if ((level == masterLevel) && (hasClass(heading, 'ignoreLink'))) {
+      ignoreChildren = true;
+    }
+
+    if ((level != masterLevel) && (!ignoreChildren)) {
+      AddTOCElements(toc_current_row, heading);
+    }
+
+    // Advance the header counter
+    h++;
+  }
+}
+
+// Adds a master Table of Content heading
+function AddTOCMaster(tocTable, heading) {
+
+  // Add the table row scaffolding
+  var toc_tr = document.createElement('tr');
+  tocTable.appendChild(toc_tr);
+  toc_tr.setAttribute('valign', 'top');
+  var toc_tr_td = document.createElement('td');
+  toc_tr.appendChild(toc_tr_td);
+  var toc_category = document.createElement('div');
+  toc_tr_td.appendChild(toc_category);
+  toc_category.className = 'toc_category';
+
+  // Create the link to this header
+  var link = document.createElement('a');
+  link.href = '#' + heading.id;       // Create the anchor link
+  link.textContent = heading.textContent; // Link text is same as heading
+  toc_category.appendChild(link);
+
+  // Add the container table cell for its children
+  var toc_td = document.createElement('td');
+  toc_tr.appendChild(toc_td);
+  var toc_td_div = document.createElement('div');
+  toc_td_div.className = 'toc_stylepoint';
+  toc_td.appendChild(toc_td_div);
+
+  return (toc_td_div);
+}
+
+// Adds Table of Contents element to a master heading as children
+function AddTOCElements(toc_div, heading) {
+
+  if (heading.offsetParent === null) {
+    // The element is currently hidden, so don't create a TOC entry
+  } else {
+    // Create the list item element
+    var toc_list_element = document.createElement('li');
+    toc_list_element.className = 'toc_entry';
+    toc_div.appendChild(toc_list_element);
+
+    // Create the link to this header
+    var link = document.createElement('a');
+    link.href = '#' + heading.id;       // Create the anchor link
+    link.textContent = heading.textContent; // Link text is same as heading
+    toc_list_element.appendChild(link);
+  }
+}
+
+function CreateVerticalTOC(headings, masterLevel, lowestLevel, tbody_element) {
+
+  // Create the Column scaffolding
+  var toc_tr = document.createElement('tr');
+  tbody_element.appendChild(toc_tr);
+  var toc_tr_td = document.createElement('td');
+  toc_tr_td.className = 'two_columns';
+  toc_tr.appendChild(toc_tr_td);
+
+
+  // Initialize the header counter and the current row
+  var h = 0;
+  var toc_current_col = null;
+  var ignoreChildren = false;
+
+  while (h < headings.length) {
+    // Get current heading
+    var heading = headings[h];
+
+    // Get the current heading level
+    var level = parseInt(heading.tagName.charAt(1));
+
+    if (isNaN(level) || level < 1 || level > lowestLevel) continue;
+
+    // If level is a masterLevel, make it a TOC parent category
+    if ((level == masterLevel) && (!hasClass(heading, 'ignoreLink'))) {
+      if (heading.offsetParent === null) {
+        // The element is currently hidden, so don't create a TOC entry
+      } else {
+        var td_dl = document.createElement('dl');
+        toc_tr_td.appendChild(td_dl);
+        var td_dt = document.createElement('dt');
+        td_dl.appendChild(td_dt);
+        toc_current_col = td_dl;
+
+        // Create the link to this header
+        var link = document.createElement('a');
+        link.href = '#' + heading.id;       // Create the anchor link
+        link.textContent = heading.textContent; // Link text is same as heading
+        td_dt.appendChild(link);
+        ignoreChildren = false;
+      }
+    }
+
+    // If level is a masterLevel but it's specified to ignore links, skip it
+    // and its children.
+    if ((level == masterLevel) && (hasClass(heading, 'ignoreLink'))) {
+      ignoreChildren = true;
+    }
+
+    if ((level != masterLevel) && (!ignoreChildren)) {
+      if (heading.offsetParent === null) {
+        // The element is currently hidden, so don't create a TOC entry
+      } else {
+        var td_dd = document.createElement('dd');
+        toc_current_col.appendChild(td_dd);
+        // Create the link to this header
+        var link = document.createElement('a');
+        link.href = '#' + heading.id;       // Create the anchor link
+        link.textContent = heading.textContent; // Link text is same as heading
+        td_dd.appendChild(link);
+      }
+    }
+
+    // Advance the header counter
+    h++;
+  }
+}
+
+/*
+ * Utility function for finding elements with a given
+ * class.
+ */
+function hasClass(element, cls) {
+    return (' ' + element.className + ' ').indexOf(' ' + cls + ' ') > -1;
+}
+
+/*
+ * Linkify all h2 through h4 headers, except for those marked
+ * "ignoreLink"
+ */
+
+// Add the link image to the element.
+function LinkifyHeader(header, fileName, sizePixels) {
+  var link = document.createElement('a');
+  link.href = '#' + header.id;
+  link.alt = 'link to ' + header.id;
+  link.innerHTML =
+      '<img src="include/' + fileName + '"' +
+      ' width=' + sizePixels +
+      ' height=' + sizePixels +
+      ' style="float:left;position:relative;bottom:5px;">';
+  header.appendChild(link);
+}
+
+// Find all elements of the given tag and linkify if
+// they don't have 'ignoreLink' in their class.
+function LinkifyHeadersForTag(tagName) {
+  var headers = document.getElementsByTagName(tagName);
+  var header;
+  for (var j = 0; j != headers.length; j++) {
+    header = headers[j];
+    if (!hasClass(header, 'ignoreLink') && ('id' in header)) {
+      if (header.id != '') {
+        LinkifyHeader(header, 'link.png', 21);
+        header.style.left = '-46px';
+        header.style.position = 'relative';
+      }
+    }
+  }
+}
+
+// Linkify all h2, h3, and h4s. h1s are titles.
+function LinkifyHeaders() {
+  LinkifyHeadersForTag('h2');
+  LinkifyHeadersForTag('h3');
+  LinkifyHeadersForTag('h4');
+}
+
+/*
+ * Initialize the style guide by showing all internal
+ * elements and then linkifying the headers.
+ */
+
+function initStyleGuide() {
+  LinkifyHeaders();
+  CreateTOC('tocDiv');
+}
diff --git a/styleguide/javaguide.css b/styleguide/javaguide.css
new file mode 100644
index 0000000..c42ba83
--- /dev/null
+++ b/styleguide/javaguide.css
@@ -0,0 +1,515 @@
+table {
+  border-collapse: collapse;
+}
+
+td, th {
+  border: 1px solid #ccc;
+  padding: 2px 12px;
+  font-size: 10pt;
+}
+
+code, samp, var {
+  color: #060;
+}
+
+pre {
+  font-size: 10pt;
+  display: block;
+  color: #060;
+  background-color: #e8fff6;
+  border-color: #f0fff0;
+  border-style: solid;
+  border-top-width: 1px;
+  border-bottom-width: 1px;
+  border-right-width: 1px;
+  border-left-width: 5px;
+  padding-left: 12px;
+  padding-right: 12px;
+  padding-top: 4px;
+  padding-bottom: 4px;
+}
+
+pre.badcode {
+  color: #c00;
+  background-color: #ffe6d8;
+  border-color: #fff0f0;
+}
+
+hr {
+  margin-top: 3.5em;
+  border-width: 1px;
+  color: #fff;
+}
+
+html {
+  margin-top:2em;
+  margin-left:10%;
+  margin-right:10%;
+  padding:0;
+}
+
+.bp-reset-element,
+body,
+h1,
+h2,
+h3,
+h4,
+h5,
+h6,
+article,
+aside,
+details,
+figcaption,
+figure,
+footer,
+header,
+hgroup,
+menu,
+nav,
+section,
+summary,
+blockquote,
+q,
+th,
+td,
+caption,
+table,
+div,
+span,
+object,
+iframe,
+p,
+pre,
+a,
+abbr,
+acronym,
+address,
+code,
+del,
+dfn,
+em,
+img,
+dl,
+dt,
+dd,
+ol,
+ul,
+li,
+fieldset,
+form,
+label,
+legend,
+caption,
+tbody,
+tfoot,
+thead,
+tr {
+  margin:0;
+  padding:0;
+  border:0;
+  font-weight:inherit;
+  font-style:inherit;
+  font-size:100%;
+  font-family:inherit;
+  vertical-align:baseline;
+}
+
+body {
+  font-family:'Arial', sans-serif;
+  font-size:81.25%;
+  color:#222;
+  background-color:#fff;
+  line-height:1.67;
+  overflow: auto;
+}
+
+.change {
+  text-align: right;
+  margin-bottom:1em;
+}
+
+em {
+  font-style: italic
+}
+
+h1,
+h2,
+h3,
+h4,
+h5,
+h6 {
+  font-weight:bold;
+}
+
+h1 {
+  margin-bottom:.50em;
+  text-align: center
+}
+
+h2,
+h3,
+h4,
+h5,
+h6 {
+  margin-top:1.5em;
+  margin-bottom:.75em;
+}
+
+h1 {font-size:200%;}
+h2 {font-size:167%;}
+h3 {font-size:133%;}
+h4 {font-size:120%;}
+h5 {font-size:110%;}
+
+p {
+  margin:0 0 1.5em;
+}
+
+a[href=''] {
+  cursor:default;
+}
+
+h1 img,
+h2 img,
+h3 img,
+h4 img,
+h5 img,
+h6 img {
+  margin:0;
+}
+
+a img {
+  border:none;
+}
+
+pre {
+  margin:1.5em 0;
+  white-space:pre;
+}
+
+pre,
+code,
+kbd,
+tt {
+  font:1em 'Droid Sans Mono', monospace;
+  line-height:1.5;
+}
+
+dl {
+  margin:0 0 1.5em 0;
+}
+
+dl dt {
+  font-weight:bold;
+}
+
+dd {
+  margin-left:1.5em;
+}
+
+dd.toc3 {
+  margin-left:3em;
+}
+
+hr {
+  height:0;
+  border:0;
+  border-top:1px solid #ccc;
+  background-color:#ccc;
+}
+
+table {
+  border:1px solid #bbb;
+  border-spacing:0;
+  border-collapse:collapse;
+  margin:0 0 1.5em;
+  vertical-align:middle;
+  width:100%;
+}
+
+table.unlined,
+table.unlined th,
+table.unlined tr,
+table.unlined td {
+  border:0;
+}
+
+th,
+td,
+caption {
+  float:none !important;
+  text-align:left;
+  font-weight:normal;
+  vertical-align:middle;
+  padding:4px;
+}
+
+caption {
+  padding:0;
+}
+
+td {
+  border:1px solid #bbb;
+  vertical-align:top;
+}
+
+th {
+  border:0;
+  border-bottom:1px solid black;
+  font-weight:bold;
+  background:rgb(229, 236, 249);
+}
+
+table th code {
+  background-color:inherit;
+  color:inherit;
+}
+
+table tfoot th {
+  border:1px solid #bbb;
+}
+
+tfoot {
+  font-style:italic;
+}
+
+caption {
+  background:#eee;
+}
+
+table[border='0'] {
+  border:none;
+}
+
+table[border='0']>tbody>tr>td,
+table[border='0']>tr>td {
+  border:none;
+}
+
+tr.alt td,
+td.alt {
+  background-color:#efefef;
+}
+
+table.striped tr:nth-child(even) td,
+table tr.even td {
+  background:#efefef;
+}
+
+table.columns {
+  border:none;
+}
+
+table.columns>tbody>tr>td,
+table.columns>tr>td {
+  border:none;
+  padding:0 3em 0 0;
+}
+
+table.columns>tbody>tr>td:last-child,
+table.columns>tr>td:last-child {
+  border:none;
+  padding:0;
+}
+
+ul,
+ol {
+  margin:0 1.5em 1.5em 0;
+  padding-left:2em;
+}
+
+li ul,
+li ol {
+  margin:0;
+}
+
+ul {
+  list-style-type:disc;
+}
+
+ol {
+  list-style-type:decimal;
+}
+
+ul {
+  list-style-type:disc;
+}
+
+ul ul {
+  list-style-type:circle;
+}
+
+ul ul ul {
+  list-style-type:square;
+}
+
+ul.disc {
+  list-style-type:disc;
+}
+
+ul.circle {
+  list-style-type:circle;
+}
+
+ul.square {
+  list-style-type:square;
+}
+
+ol {
+  list-style-type:decimal;
+}
+
+ol ol {
+  list-style-type:lower-alpha;
+}
+
+ol ol ol {
+  list-style-type:lower-roman;
+}
+
+ol ul {
+  list-style-type:circle;
+}
+
+ol.decimal {
+  list-style-type:decimal;
+}
+
+ol.upper-alpha {
+  list-style-type:upper-alpha;
+}
+
+ol.lower-alpha {
+  list-style-type:lower-alpha;
+}
+
+ol.upper-roman {
+  list-style-type:upper-roman;
+}
+
+ol.lower-roman {
+  list-style-type:lower-roman;
+}
+
+ol.nolist,
+ul.nolist {
+  padding-left:0;
+  list-style-image:none;
+  list-style-type:none;
+  margin-left:0;
+}
+
+.center {
+  text-align:center;
+}
+
+code,
+kbd,
+pre {
+  color:#009900;
+}
+
+kbd {
+  font-weight: bold;
+}
+
+table.striped code {
+  background-color:inherit;
+}
+
+pre {
+  padding:6px 10px;
+  background-color:#FAFAFA;
+  border:1px solid #bbb;
+  overflow:auto;
+}
+
+pre.prettyprint {
+  padding:6px 10px !important;
+  border:1px solid #bbb !important;
+}
+
+code.bad, code.badcode {
+  color: magenta;
+}
+pre.bad, pre.badcode {
+  background-color:#ffe6d8;
+  border-top:1px inset #a03;
+  border-left:1px inset #a03;
+}
+
+.tip {
+  background-color:#fffbd9;
+  padding:6px 8px 6px 10px;
+  border-left:6px solid #ffef70;
+}
+
+.note {
+  background-color:#e5ecf9;
+  padding:6px 8px 6px 10px;
+  border-left:6px solid #36c;
+}
+
+@media print {
+
+  .str {
+    color:#060;
+  }
+
+  .kwd {
+    color:#006;
+    font-weight:bold;
+  }
+
+  .com {
+    color:#600;
+    font-style:italic;
+  }
+
+  .typ {
+    color:#404;
+    font-weight:bold;
+  }
+
+  .lit {
+    color:#044;
+  }
+
+  .pun,
+  .opn,
+  .clo {
+    color:#440;
+  }
+
+  .pln {
+    color:#000;
+  }
+
+  .tag {
+    color:#006;
+    font-weight:bold;
+  }
+
+  .atn {
+    color:#404;
+  }
+
+  .atv {
+    color:#060;
+  }
+
+  h1 {
+    font-style:italic;
+  }
+}
+
+ol.linenums {
+  margin-top:0;
+  margin-bottom:0;
+}
+
+code {
+  background-color:#FAFAFA;
+  padding: 0.25em 0.5em;
+  white-space: nowrap
+}
diff --git a/styleguide/javaguide.html b/styleguide/javaguide.html
new file mode 100644
index 0000000..da34b85
--- /dev/null
+++ b/styleguide/javaguide.html
@@ -0,0 +1,806 @@
+<html lang="en">
+<head>
+  <meta http-equiv="content-type" content="text/html; charset=UTF-8" />
+  <link rel="stylesheet" type="text/css" href="javaguide.css"/>
+  <script src="https://google-code-prettify.googlecode.com/svn/loader/run_prettify.js"
+          type="text/javascript"></script>
+  <link href="http://www.google.com/favicon.ico"
+        type="image/x-icon" rel="shortcut icon" />
+  <title>WPILib Java Style</title>
+</head>
+<body>
+<h1>WPILib Java Style (Based on the
+ <a href=http://google-styleguide.googlecode.com/svn/trunk/javaguide.html>Google Java Style Guide</a>)</h1>
+  <div class="change">Last changed: June 19, 2015</div>
+<table border="0">
+<tr>
+<td>
+<dl>
+<br>
+<dt class="toc1">
+<a href="#s1-introduction">1 Introduction</a>
+</dt>
+<dd>
+<a href="#s1.1-terminology">1.1 Terminology notes</a>
+</dd>
+<dd>
+<a href="#s1.2-guide-notes">1.2 Guide notes</a>
+</dd>
+<br>
+<dt class="toc1">
+<a href="#s2-source-file-basics">2 Source file basics</a>
+</dt>
+<dd>
+<a href="#s2.1-file-name">2.1 File name</a>
+</dd>
+<dd>
+<a href="#s2.2-file-encoding">2.2 File encoding: UTF-8</a>
+</dd>
+<dd>
+<a href="#s2.3-special-characters">2.3 Special characters</a>
+</dd>
+<dd class="toc3">
+<a href="#s2.3.1-whitespace-characters">2.3.1 Whitespace characters</a>
+</dd>
+<dd class="toc3">
+<a href="#s2.3.2-special-escape-sequences">2.3.2 Special escape sequences</a>
+</dd>
+<dd class="toc3">
+<a href="#s2.3.3-non-ascii-characters">2.3.3 Non-ASCII characters</a>
+</dd>
+<br>
+<dt class="toc1">
+<a href="#s3-source-file-structure">3 Source file structure</a>
+</dt>
+<dd>
+<a href="#s3.1-copyright-statement">3.1 License or copyright information, if present</a>
+</dd>
+<dd>
+<a href="#s3.2-package-statement">3.2 Package statement</a>
+</dd>
+<dd>
+<a href="#s3.3-import-statements">3.3 Import statements</a>
+</dd>
+<dd class="toc3">
+<a href="#s3.3.1-wildcard-imports">3.3.1 No wildcard imports</a>
+</dd>
+<dd class="toc3">
+<a href="#s3.3.2-import-line-wrapping">3.3.2 No line-wrapping</a>
+</dd>
+<dd class="toc3">
+<a href="#s3.3.3-import-ordering-and-spacing">3.3.3 Ordering and spacing</a>
+</dd>
+<dd>
+<a href="#s3.4-class-declaration">3.4 Class declaration</a>
+</dd>
+<dd class="toc3">
+<a href="#s3.4.1-one-top-level-class">3.4.1 Exactly one top-level class declaration</a>
+</dd>
+<dd class="toc3">
+<a href="#s3.4.2-class-member-ordering">3.4.2 Class member ordering</a>
+</dd>
+</dl>
+</td><td>
+<dl>
+<br>
+<dt class="toc1">
+<a href="#s4-formatting">4 Formatting</a>
+</dt>
+<dd>
+<a href="#s4.1-braces">4.1 Braces</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.1.1-braces-always-used">4.1.1 Braces are used where optional</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.1.2-blocks-k-r-style">4.1.2 Nonempty blocks: K &amp; R style</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.1.3-braces-empty-blocks">4.1.3 Empty blocks: may be concise</a>
+</dd>
+<dd>
+<a href="#s4.2-block-indentation">4.2 Block indentation: +2 spaces</a>
+</dd>
+<dd>
+<a href="#s4.3-one-statement-per-line">4.3 One statement per line</a>
+</dd>
+<dd>
+<a href="#s4.4-column-limit">4.4 Column limit: 80 or 100</a>
+</dd>
+<dd>
+<a href="#s4.5-line-wrapping">4.5 Line-wrapping</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.5.1-line-wrapping-where-to-break">4.5.1 Where to break</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.5.2-line-wrapping-indent">4.5.2 Indent continuation lines at least +4 spaces</a>
+</dd>
+<dd>
+<a href="#s4.6-whitespace">4.6 Whitespace</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.6.1-vertical-whitespace">4.6.1 Vertical Whitespace</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.6.2-horizontal-whitespace">4.6.2 Horizontal whitespace</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.6.3-horizontal-alignment">4.6.3 Horizontal alignment: never required</a>
+</dd>
+<dd>
+<a href="#s4.7-grouping-parentheses">4.7 Grouping parentheses: recommended</a>
+</dd>
+<dd>
+<a href="#s4.8-specific-constructs">4.8 Specific constructs</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.8.1-enum-classes">4.8.1 Enum classes</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.8.2-variable-declarations">4.8.2 Variable declarations</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.8.3-arrays">4.8.3 Arrays</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.8.4-switch">4.8.4 Switch statements</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.8.5-annotations">4.8.5 Annotations</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.8.6-comments">4.8.6 Comments</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.8.7-modifiers">4.8.7 Modifiers</a>
+</dd>
+<dd class="toc3">
+<a href="#s4.8.8-numeric-literals">4.8.8 Numeric Literals</a>
+</dd>
+</dl>
+</td><td>
+<dl>
+<br>
+<dt class="toc1">
+<a href="#s5-naming">5 Naming</a>
+</dt>
+<dd>
+<a href="#s5.1-identifier-names">5.1 Rules common to all identifiers</a>
+</dd>
+<dd>
+<a href="#s5.2-specific-identifier-names">5.2 Rules by identifier type</a>
+</dd>
+<dd class="toc3">
+<a href="#s5.2.1-package-names">5.2.1 Package names</a>
+</dd>
+<dd class="toc3">
+<a href="#s5.2.2-class-names">5.2.2 Class names</a>
+</dd>
+<dd class="toc3">
+<a href="#s5.2.3-method-names">5.2.3 Method names</a>
+</dd>
+<dd class="toc3">
+<a href="#s5.2.4-constant-names">5.2.4 Constant names</a>
+</dd>
+<dd class="toc3">
+<a href="#s5.2.5-non-constant-field-names">5.2.5 Non-constant field names</a>
+</dd>
+<dd class="toc3">
+<a href="#s5.2.6-parameter-names">5.2.6 Parameter names</a>
+</dd>
+<dd class="toc3">
+<a href="#s5.2.7-local-variable-names">5.2.7 Local variable names</a>
+</dd>
+<dd class="toc3">
+<a href="#s5.2.8-type-variable-names">5.2.8 Type variable names</a>
+</dd>
+<dd>
+<a href="#s5.3-camel-case">5.3 Camel case: defined</a>
+</dd>
+<br>
+<dt class="toc1">
+<a href="#s6-programming-practices">6 Programming Practices</a>
+</dt>
+<dd>
+<a href="#s6.1-override-annotation">6.1 @Override: always used</a>
+</dd>
+<dd>
+<a href="#s6.2-caught-exceptions">6.2 Caught exceptions: not ignored</a>
+</dd>
+<dd>
+<a href="#s6.3-static-members">6.3 Static members: qualified using class</a>
+</dd>
+<dd>
+<a href="#s6.4-finalizers">6.4 Finalizers: not used</a>
+</dd>
+<br>
+<dt class="toc1">
+<a href="#s7-javadoc">7 Javadoc</a>
+</dt>
+<dd>
+<a href="#s7.1-javadoc-formatting">7.1 Formatting</a>
+</dd>
+<dd class="toc3">
+<a href="#s7.1.1-javadoc-multi-line">7.1.1 General form</a>
+</dd>
+<dd class="toc3">
+<a href="#s7.1.2-javadoc-paragraphs">7.1.2 Paragraphs</a>
+</dd>
+<dd class="toc3">
+<a href="#s7.1.3-javadoc-at-clauses">7.1.3 At-clauses</a>
+</dd>
+<dd>
+<a href="#s7.2-summary-fragment">7.2 The summary fragment</a>
+</dd>
+<dd>
+<a href="#s7.3-javadoc-where-required">7.3 Where Javadoc is used</a>
+</dd>
+<dd class="toc3">
+<a href="#s7.3.1-javadoc-exception-self-explanatory">7.3.1 Exception: self-explanatory methods</a>
+</dd>
+<dd class="toc3">
+<a href="#s7.3.2-javadoc-exception-overrides">7.3.2 Exception: overrides</a>
+</dd>
+</dl>
+</td>
+</tr>
+</table>
+<div><a name="s1-introduction"/>
+    <h2>1 Introduction&nbsp;<a href="#s1-introduction"><img height="21" width="21" src="javaguidelink.png"/></a></h2>
+
+<p><strong>This guide is a work in progress.</strong>
+We are currently working on getting this guide updated to
+a point where it is useful for WPILib developers to use.</p>
+
+    <p>This document serves as the style guide for WPILib. It is <em>heavily</em>
+ based on the Google Java Style Guide and copies pretty much word-for-word
+ the formatting/style components of the guide while cutting a couple
+ of the programming practices. As this guide evolves, we will likely
+ introduce more suggested/mandated programming practices specific
+ to WPILib.</p>
+    <p>It is encouraged that anyone working on the Java WPILib also
+ read the corresponding C++ guide, as we generally try to develop
+ the C++ and Java components of the library in parallel and many
+ programming practices true in one language will be true in the other
+ (although this is not universally true).</p>
+</p><a name="s1.1-terminology"/>
+    <h3>1.1 Terminology notes&nbsp;<a href="#s1.1-terminology"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>In this document, unless otherwise clarified:</p><ol><li>The term <em>class</em> is used inclusively to mean an "ordinary" class, enum class,
+  interface or annotation type (<code class="prettyprint lang-java">@interface</code>).</li><li>The term <em>comment</em> always refers to <em>implementation</em> comments. We do not
+  use the phrase "documentation comments", instead using the common term "Javadoc."</li></ol><p>Other "terminology notes" will appear occasionally throughout the document.</p><a name="s1.2-guide-notes"/>
+    <h3>1.2 Guide notes&nbsp;<a href="#s1.2-guide-notes"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>Example code in this document is <strong>non-normative</strong>. That is, while the examples
+are in Google Style, they may not illustrate the <em>only</em> stylish way to represent the
+code. Optional formatting choices made in examples should not be enforced as rules.</p><a name="s2-source-file-basics"/>
+    <h2>2 Source file basics&nbsp;<a href="#s2-source-file-basics"><img height="21" width="21" src="javaguidelink.png"/></a></h2>
+    <a name="s2.1-file-name"/>
+    <h3>2.1 File name&nbsp;<a href="#s2.1-file-name"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>The source file name consists of the case-sensitive name of the top-level class it contains,
+plus the <code>.java</code> extension.</p><a name="s2.2-file-encoding"/>
+    <h3>2.2 File encoding: UTF-8&nbsp;<a href="#s2.2-file-encoding"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>Source files are encoded in <strong>UTF-8</strong>.</p><a name="s2.3-special-characters"/>
+    <h3>2.3 Special characters&nbsp;<a href="#s2.3-special-characters"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <a name="s2.3.1-whitespace-characters"/>
+    <h4>2.3.1 Whitespace characters&nbsp;<a href="#s2.3.1-whitespace-characters"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Aside from the line terminator sequence, the <strong>ASCII horizontal space
+character</strong> (<strong>0x20</strong>) is the only whitespace character that appears
+anywhere in a source file. This implies that:</p><ol><li>All other whitespace characters in string and character literals are escaped.</li><li>Tab characters are <strong>not</strong> used for indentation.</li></ol><a name="s2.3.2-special-escape-sequences"/>
+    <h4>2.3.2 Special escape sequences&nbsp;<a href="#s2.3.2-special-escape-sequences"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>For any character that has a special escape sequence
+(<code class="prettyprint lang-java">\b</code>,
+<code class="prettyprint lang-java">\t</code>,
+<code class="prettyprint lang-java">\n</code>,
+<code class="prettyprint lang-java">\f</code>,
+<code class="prettyprint lang-java">\r</code>,
+<code class="prettyprint lang-java">\"</code>,
+<code class="prettyprint lang-java">\'</code> and
+<code class="prettyprint lang-java">\\</code>), that sequence
+is used rather than the corresponding octal
+(e.g. <code class="badcode">\012</code>) or Unicode
+(e.g. <code class="badcode">\u000a</code>) escape.</p><a name="s2.3.3-non-ascii-characters"/>
+    <h4>2.3.3 Non-ASCII characters&nbsp;<a href="#s2.3.3-non-ascii-characters"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>For the remaining non-ASCII characters, either the actual Unicode character
+(e.g. <code class="prettyprint lang-java">∞</code>) or the equivalent Unicode escape
+(e.g. <code class="prettyprint lang-java">\u221e</code>) is used, depending only on which
+makes the code <strong>easier to read and understand</strong>.</p><p class="tip"><strong>Tip:</strong> In the Unicode escape case, and occasionally even when actual
+Unicode characters are used, an explanatory comment can be very helpful.</p><p>Examples:</p><table><tr><th>Example</th><th>Discussion</th></tr><tr><td><code class="prettyprint lang-java">String unitAbbrev = "μs";</code></td><td>Best: perfectly clear even without a comment.</td></tr><tr><td><code class="prettyprint lang-java">String unitAbbrev = "\u03bcs"; // "μs"</code></td><td>Allowed, but there's no reason to do this.</td></tr><tr><td><code class="prettyprint lang-java">String unitAbbrev = "\u03bcs";
+      // Greek letter mu, "s"</code></td><td>Allowed, but awkward and prone to mistakes.</td></tr><tr><td><code class="badcode">String unitAbbrev = "\u03bcs";</code></td><td>Poor: the reader has no idea what this is.</td></tr><tr><td><code class="prettyprint lang-java">return '\ufeff' + content;
+       // byte order mark</code></td><td>Good: use escapes for non-printable characters, and comment if necessary.</td></tr></table><p class="tip"><strong>Tip:</strong> Never make your code less readable simply out of fear that
+some programs might not handle non-ASCII characters properly. If that should happen, those
+programs are <strong>broken</strong> and they must be <strong>fixed</strong>.</p><a name="filestructure"/><a name="s3-source-file-structure"/>
+    <h2>3 Source file structure&nbsp;<a href="#s3-source-file-structure"><img height="21" width="21" src="javaguidelink.png"/></a></h2>
+    <div><p>A source file consists of, <strong>in order</strong>:</p><ol><li>License or copyright information, if present</li><li>Package statement</li><li>Import statements</li><li>Exactly one top-level class</li></ol></div><p><strong>Exactly one blank line</strong> separates each section that is present.</p><a name="s3.1-copyright-statement"/>
+    <h3>3.1 License or copyright information, if present&nbsp;<a href="#s3.1-copyright-statement"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>If license or copyright information belongs in a file, it belongs here.</p><a name="s3.2-package-statement"/>
+    <h3>3.2 Package statement&nbsp;<a href="#s3.2-package-statement"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>The package statement is <strong>not line-wrapped</strong>. The column limit (Section 4.4,
+<a href="#s4.4-column-limit">Column limit: 80</a>) does not apply to package statements.</p><a name="imports"/><a name="s3.3-import-statements"/>
+    <h3>3.3 Import statements&nbsp;<a href="#s3.3-import-statements"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <a name="s3.3.1-wildcard-imports"/>
+    <h4>3.3.1 No wildcard imports&nbsp;<a href="#s3.3.1-wildcard-imports"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p><strong>Wildcard imports</strong>, static or otherwise, <strong>are not used</strong>.</p><a name="s3.3.2-import-line-wrapping"/>
+    <h4>3.3.2 No line-wrapping&nbsp;<a href="#s3.3.2-import-line-wrapping"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Import statements are <strong>not line-wrapped</strong>. The column limit (Section 4.4,
+<a href="#s4.4-column-limit">Column limit: 80</a>) does not apply to import
+statements.</p><a name="s3.3.3-import-ordering-and-spacing"/>
+    <h4>3.3.3 Ordering and spacing&nbsp;<a href="#s3.3.3-import-ordering-and-spacing"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Import statements are divided into the following groups, in this order, with each group
+separated by a single blank line:</p><ol><li>All static imports in a single group</li><li><code>com.google</code> imports
+  (only if this source file is in the <code>com.google</code> package
+  space)</li><li>Third-party imports, one group per top-level package, in ASCII sort order
+  <ul><li>for example: <code>android</code>, <code>com</code>, <code>junit</code>, <code>org</code>,
+    <code>sun</code></li></ul></li><li><code>java</code> imports</li><li><code>javax</code> imports</li></ol><p>Within a group there are no blank lines, and the imported names appear in ASCII sort
+order. (<strong>Note:</strong> this is not the same as the import <em>statements</em> being in
+ASCII sort order; the presence of semicolons warps the result.)</p><a name="s3.4-class-declaration"/>
+    <h3>3.4 Class declaration&nbsp;<a href="#s3.4-class-declaration"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <a name="oneclassperfile"/><a name="s3.4.1-one-top-level-class"/>
+    <h4>3.4.1 Exactly one top-level class declaration&nbsp;<a href="#s3.4.1-one-top-level-class"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Each top-level class resides in a source file of its own.</p><a name="s3.4.2-class-member-ordering"/>
+    <h4>3.4.2 Class member ordering&nbsp;<a href="#s3.4.2-class-member-ordering"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>The ordering of the members of a class can have a great effect on learnability, but there is
+no single correct recipe for how to do it. Different classes may order their members
+differently.</p><p>What is important is that each class order its members in <strong><em>some</em> logical
+order</strong>, which its maintainer could explain if asked. For example, new methods are not
+just habitually added to the end of the class, as that would yield "chronological by date
+added" ordering, which is not a logical ordering.</p><a name="overloads"/><a name="s3.4.2.1-overloads-never-split"/>
+    <h5>3.4.2.1 Overloads: never split&nbsp;<a href="#s3.4.2.1-overloads-never-split"><img height="21" width="21" src="javaguidelink.png"/></a></h5>
+    <p>When a class has multiple constructors, or multiple methods with the same name, these appear
+sequentially, with no intervening members.</p><a name="s4-formatting"/>
+    <h2>4 Formatting&nbsp;<a href="#s4-formatting"><img height="21" width="21" src="javaguidelink.png"/></a></h2>
+    <p class="terminology"><strong>Terminology Note:</strong> <em>block-like construct</em> refers to
+the body of a class, method or constructor. Note that, by Section 4.8.3.1 on
+<a href="#s4.8.3.1-array-initializers">array initializers</a>, any array initializer
+<em>may</em> optionally be treated as if it were a block-like construct.</p><a name="braces"/><a name="s4.1-braces"/>
+    <h3>4.1 Braces&nbsp;<a href="#s4.1-braces"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <a name="s4.1.1-braces-always-used"/>
+    <h4>4.1.1 Braces are used where optional&nbsp;<a href="#s4.1.1-braces-always-used"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Braces are used with
+<code class="prettyprint lang-java">if</code>,
+<code class="prettyprint lang-java">else</code>,
+<code class="prettyprint lang-java">for</code>,
+<code class="prettyprint lang-java">do</code> and
+<code class="prettyprint lang-java">while</code> statements, even when the
+body is empty or contains only a single statement.</p><a name="s4.1.2-blocks-k-r-style"/>
+    <h4>4.1.2 Nonempty blocks: K &amp; R style&nbsp;<a href="#s4.1.2-blocks-k-r-style"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Braces follow the Kernighan and Ritchie style
+("<a href="http://www.codinghorror.com/blog/2012/07/new-programming-jargon.html">Egyptian brackets</a>")
+for <em>nonempty</em> blocks and block-like constructs:</p><ul><li>No line break before the opening brace.</li><li>Line break after the opening brace.</li><li>Line break before the closing brace.</li><li>Line break after the closing brace <em>if</em> that brace terminates a statement or the body
+  of a method, constructor or <em>named</em> class. For example, there is <em>no</em> line break
+  after the brace if it is followed by <code class="prettyprint lang-java">else</code> or a
+  comma.</li></ul><p>Example:</p><pre class="prettyprint lang-java">
+return new MyClass() {
+  @Override public void method() {
+    if (condition()) {
+      try {
+        something();
+      } catch (ProblemException e) {
+        recover();
+      }
+    }
+  }
+};
+</pre><p>A few exceptions for enum classes are given in Section 4.8.1,
+<a href="#s4.8.1-enum-classes">Enum classes</a>.</p><a name="emptyblocks"/><a name="s4.1.3-braces-empty-blocks"/>
+    <h4>4.1.3 Empty blocks: may be concise&nbsp;<a href="#s4.1.3-braces-empty-blocks"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>An empty block or block-like construct <em>may</em> be closed immediately after it is
+opened, with no characters or line break in between
+(<code class="prettyprint lang-java">{}</code>), <strong>unless</strong> it is part of a
+<em>multi-block statement</em> (one that directly contains multiple blocks:
+<code class="prettyprint lang-java">if/else-if/else</code> or
+<code class="prettyprint lang-java">try/catch/finally</code>).</p><p>Example:</p><pre class="prettyprint lang-java">
+  void doNothing() {}
+</pre><a name="s4.2-block-indentation"/>
+    <h3>4.2 Block indentation: +2 spaces&nbsp;<a href="#s4.2-block-indentation"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>Each time a new block or block-like construct is opened, the indent increases by two
+spaces. When the block ends, the indent returns to the previous indent level. The indent level
+applies to both code and comments throughout the block. (See the example in Section 4.1.2,
+<a href="#s4.1.2-blocks-k-r-style">Nonempty blocks: K &amp; R Style</a>.)</p><a name="s4.3-one-statement-per-line"/>
+    <h3>4.3 One statement per line&nbsp;<a href="#s4.3-one-statement-per-line"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>Each statement is followed by a line-break.</p><a name="columnlimit"/><a name="s4.4-column-limit"/>
+    <h3>4.4 Column limit: 80&nbsp;<a href="#s4.4-column-limit"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>
+  Projects should have a column limit of 80 characters.
+
+Except as noted below, any line that would exceed this limit must be line-wrapped, as explained in
+Section 4.5, <a href="#s4.5-line-wrapping">Line-wrapping</a>.
+</p><p><strong>Exceptions:</strong></p><ol><li>Lines where obeying the column limit is not possible (for example, a long URL in Javadoc,
+  or a long JSNI method reference).</li><li><code class="prettyprint lang-java">package</code> and
+  <code class="prettyprint lang-java">import</code> statements (see Sections
+  3.2 <a href="#s3.2-package-statement">Package statement</a> and
+  3.3 <a href="#s3.3-import-statements">Import statements</a>).</li><li>Command lines in a comment that may be cut-and-pasted into a shell.</li></ol><a name="s4.5-line-wrapping"/>
+    <h3>4.5 Line-wrapping&nbsp;<a href="#s4.5-line-wrapping"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p class="terminology"><strong>Terminology Note:</strong> When code that might otherwise legally
+occupy a single line is divided into multiple lines, typically to avoid overflowing the column
+limit, this activity is called
+<em>line-wrapping</em>.</p><p>There is no comprehensive, deterministic formula showing <em>exactly</em> how to line-wrap in
+every situation. Very often there are several valid ways to line-wrap the same piece of code.</p><p class="tip"><strong>Tip:</strong> Extracting a method or local variable may solve the problem
+without the need to line-wrap.</p><a name="s4.5.1-line-wrapping-where-to-break"/>
+    <h4>4.5.1 Where to break&nbsp;<a href="#s4.5.1-line-wrapping-where-to-break"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>The prime directive of line-wrapping is: prefer to break at a
+<strong>higher syntactic level</strong>. Also:</p><ol><li>When a line is broken at a <em>non-assignment</em> operator the break comes <em>before</em>
+  the symbol. (Note that this is not the same practice used in Google style for other languages,
+  such as C++ and JavaScript.)
+    <ul><li>This also applies to the following "operator-like" symbols: the dot separator
+      (<code class="prettyprint lang-java">.</code>), the ampersand in type bounds
+      (<code class="prettyprint lang-java">&lt;T extends Foo &amp; Bar&gt;</code>), and the pipe in
+      catch blocks
+      (<code class="prettyprint lang-java">catch (FooException | BarException e)</code>).</li></ul></li><li>When a line is broken at an <em>assignment</em> operator the break typically comes
+  <em>after</em> the symbol, but either way is acceptable.
+    <ul><li>This also applies to the "assignment-operator-like" colon in an enhanced
+      <code class="prettyprint lang-java">for</code> ("foreach") statement.</li></ul></li><li>A method or constructor name stays attached to the open parenthesis
+  (<code class="prettyprint lang-java">(</code>) that follows it.</li><li>A comma (<code class="prettyprint lang-java">,</code>) stays attached to the token that
+  precedes it.</li></ol><a name="indentation"/><a name="s4.5.2-line-wrapping-indent"/>
+    <h4>4.5.2 Indent continuation lines at least +4 spaces&nbsp;<a href="#s4.5.2-line-wrapping-indent"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>When line-wrapping, each line after the first (each <em>continuation line</em>) is indented
+at least +4 from the original line.</p><p>When there are multiple continuation lines, indentation may be varied beyond +4 as
+desired. In general, two continuation lines use the same indentation level if and only if they
+begin with syntactically parallel elements.</p><p>Section 4.6.3 on <a href="#s4.6.3-horizontal-alignment">Horizontal alignment</a> addresses
+the discouraged practice of using a variable number of spaces to align certain tokens with
+previous lines.</p><a name="s4.6-whitespace"/>
+    <h3>4.6 Whitespace&nbsp;<a href="#s4.6-whitespace"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <a name="s4.6.1-vertical-whitespace"/>
+    <h4>4.6.1 Vertical Whitespace&nbsp;<a href="#s4.6.1-vertical-whitespace"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>A single blank line appears:</p><ol><li><em>Between</em> consecutive members (or initializers) of a class: fields, constructors,
+  methods, nested classes, static initializers, instance initializers.
+  <ul><li><span class="exception"><strong>Exception:</strong> A blank line between two consecutive
+    fields (having no other code between them) is optional. Such blank lines are used as needed to
+    create <em>logical groupings</em> of fields.</span></li></ul></li><li>Within method bodies, as needed to create <em>logical groupings</em> of statements.</li><li><em>Optionally</em> before the first member or after the last member of the class (neither
+  encouraged nor discouraged).</li><li>As required by other sections of this document (such as Section 3.3,
+  <a href="#s3.3-import-statements">Import statements</a>).</li></ol><p><em>Multiple</em> consecutive blank lines are permitted, but never required (or encouraged).</p><a name="s4.6.2-horizontal-whitespace"/>
+    <h4>4.6.2 Horizontal whitespace&nbsp;<a href="#s4.6.2-horizontal-whitespace"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Beyond where required by the language or other style rules, and apart from literals, comments and
+Javadoc, a single ASCII space also appears in the following places <strong>only</strong>.</p><ol><li>Separating any reserved word, such as
+  <code class="prettyprint lang-java">if</code>,
+  <code class="prettyprint lang-java">for</code> or
+  <code class="prettyprint lang-java">catch</code>, from an open parenthesis
+  (<code class="prettyprint lang-java">(</code>)
+  that follows it on that line</li><li>Separating any reserved word, such as
+  <code class="prettyprint lang-java">else</code> or
+  <code class="prettyprint lang-java">catch</code>, from a closing curly brace
+  (<code class="prettyprint lang-java">}</code>) that precedes it on that line</li><li>Before any open curly brace
+  (<code class="prettyprint lang-java">{</code>), with two exceptions:
+  <ul><li><code class="prettyprint lang-java">@SomeAnnotation({a, b})</code> (no space is used)</li><li><code class="prettyprint lang-java">String[][] x = {{"foo"}};</code> (no space is required
+    between <code class="prettyprint lang-java">{{</code>, by item 8 below)</li></ul></li><li>On both sides of any binary or ternary operator. This also applies to the following
+  "operator-like" symbols:
+  <ul><li>the ampersand in a conjunctive type bound:
+    <code class="prettyprint lang-java">&lt;T extends Foo &amp; Bar&gt;</code></li><li>the pipe for a catch block that handles multiple exceptions:
+    <code class="prettyprint lang-java">catch (FooException | BarException e)</code></li><li>the colon (<code class="prettyprint lang-java">:</code>) in an enhanced
+    <code class="prettyprint lang-java">for</code> ("foreach") statement</li></ul></li><li>After <code class="prettyprint lang-java">,:;</code> or the closing parenthesis
+  (<code class="prettyprint lang-java">)</code>) of a cast</li><li>On both sides of the double slash (<code class="prettyprint lang-java">//</code>) that
+  begins an end-of-line comment. Here, multiple spaces are allowed, but not required.</li><li>Between the type and variable of a declaration:
+  <code class="prettyprint lang-java">List&lt;String&gt; list</code></li><li><em>Optional</em> just inside both braces of an array initializer
+  <ul><li><code class="prettyprint lang-java">new int[] {5, 6}</code> and
+    <code class="prettyprint lang-java">new int[] { 5, 6 }</code> are both valid</li></ul></li></ol><p class="note"><strong>Note:</strong> This rule never requires or forbids additional space at the
+start or end of a line, only <em>interior</em> space.</p><a name="s4.6.3-horizontal-alignment"/>
+    <h4>4.6.3 Horizontal alignment: never required&nbsp;<a href="#s4.6.3-horizontal-alignment"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p class="terminology"><strong>Terminology Note:</strong> <em>Horizontal alignment</em> is the
+practice of adding a variable number of additional spaces in your code with the goal of making
+certain tokens appear directly below certain other tokens on previous lines.</p><p>This practice is permitted, but is <strong>never required</strong> by Google Style. It is not
+even required to <em>maintain</em> horizontal alignment in places where it was already used.</p><p>Here is an example without alignment, then using alignment:</p><pre class="prettyprint lang-java">
+private int x; // this is fine
+private Color color; // this too
+
+private int   x;      // permitted, but future edits
+private Color color;  // may leave it unaligned
+</pre><p class="tip"><strong>Tip:</strong> Alignment can aid readability, but it creates problems for
+future maintenance.  Consider a future change that needs to touch just one line. This change may
+leave the formerly-pleasing formatting mangled, and that is <strong>allowed</strong>. More often
+it prompts the coder (perhaps you) to adjust whitespace on nearby lines as well, possibly
+triggering a cascading series of reformattings. That one-line change now has a "blast radius."
+This can at worst result in pointless busywork, but at best it still corrupts version history
+information, slows down reviewers and exacerbates merge conflicts.</p><a name="parentheses"/><a name="s4.7-grouping-parentheses"/>
+    <h3>4.7 Grouping parentheses: recommended&nbsp;<a href="#s4.7-grouping-parentheses"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>Optional grouping parentheses are omitted only when author and reviewer agree that there is no
+reasonable chance the code will be misinterpreted without them, nor would they have made the code
+easier to read. It is <em>not</em> reasonable to assume that every reader has the entire Java
+operator precedence table memorized.</p><a name="s4.8-specific-constructs"/>
+    <h3>4.8 Specific constructs&nbsp;<a href="#s4.8-specific-constructs"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <a name="s4.8.1-enum-classes"/>
+    <h4>4.8.1 Enum classes&nbsp;<a href="#s4.8.1-enum-classes"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>After each comma that follows an enum constant, a line-break is optional.</p><p>An enum class with no methods and no documentation on its constants may optionally be formatted
+as if it were an array initializer (see Section 4.8.3.1 on
+<a href="#s4.8.3.1-array-initializers">array initializers</a>).</p><pre class="prettyprint lang-java">
+private enum Suit { CLUBS, HEARTS, SPADES, DIAMONDS }
+</pre><p>Since enum classes <em>are classes</em>, all other rules for formatting classes apply.</p><a name="localvariables"/><a name="s4.8.2-variable-declarations"/>
+    <h4>4.8.2 Variable declarations&nbsp;<a href="#s4.8.2-variable-declarations"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <a name="s4.8.2.1-variables-per-declaration"/>
+    <h5>4.8.2.1 One variable per declaration&nbsp;<a href="#s4.8.2.1-variables-per-declaration"><img height="21" width="21" src="javaguidelink.png"/></a></h5>
+    <p>Every variable declaration (field or local) declares only one variable: declarations such as
+<code class="badcode">int a, b;</code> are not used.</p><a name="s4.8.2.2-variables-limited-scope"/>
+    <h5>4.8.2.2 Declared when needed, initialized as soon as
+possible&nbsp;<a href="#s4.8.2.2-variables-limited-scope"><img height="21" width="21" src="javaguidelink.png"/></a></h5>
+    <p>Local variables are <strong>not</strong> habitually declared at the start of their containing
+block or block-like construct. Instead, local variables are declared close to the point they are
+first used (within reason), to minimize their scope. Local variable declarations typically have
+initializers, or are initialized immediately after declaration.</p><a name="s4.8.3-arrays"/>
+    <h4>4.8.3 Arrays&nbsp;<a href="#s4.8.3-arrays"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <a name="s4.8.3.1-array-initializers"/>
+    <h5>4.8.3.1 Array initializers: can be "block-like"&nbsp;<a href="#s4.8.3.1-array-initializers"><img height="21" width="21" src="javaguidelink.png"/></a></h5>
+    <p>Any array initializer may <em>optionally</em> be formatted as if it were a "block-like
+construct." For example, the following are all valid (<strong>not</strong> an exhaustive
+list):</p><pre class="prettyprint lang-java">
+new int[] {           new int[] {
+  0, 1, 2, 3            0,
+}                       1,
+                        2,
+new int[] {             3,
+  0, 1,               }
+  2, 3
+}                     new int[]
+                          {0, 1, 2, 3}
+</pre><a name="s4.8.3.2-array-declarations"/>
+    <h5>4.8.3.2 No C-style array declarations&nbsp;<a href="#s4.8.3.2-array-declarations"><img height="21" width="21" src="javaguidelink.png"/></a></h5>
+    <p>The square brackets form a part of the <em>type</em>, not the variable:
+<code class="prettyprint lang-java">String[] args</code>, not
+<code class="badcode">String args[]</code>.</p><a name="s4.8.4-switch"/>
+    <h4>4.8.4 Switch statements&nbsp;<a href="#s4.8.4-switch"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p class="terminology"><strong>Terminology Note:</strong> Inside the braces of a
+<em>switch block</em> are one or more <em>statement groups</em>. Each statement group consists of
+one or more <em>switch labels</em> (either <code class="prettyprint lang-java">case FOO:</code> or
+<code class="prettyprint lang-java">default:</code>), followed by one or more statements.</p><a name="s4.8.4.1-switch-indentation"/>
+    <h5>4.8.4.1 Indentation&nbsp;<a href="#s4.8.4.1-switch-indentation"><img height="21" width="21" src="javaguidelink.png"/></a></h5>
+    <p>As with any other block, the contents of a switch block are indented +2.</p><p>After a switch label, a newline appears, and the indentation level is increased +2, exactly as
+if a block were being opened. The following switch label returns to the previous indentation
+level, as if a block had been closed.</p><a name="fallthrough"/><a name="s4.8.4.2-switch-fall-through"/>
+    <h5>4.8.4.2 Fall-through: commented&nbsp;<a href="#s4.8.4.2-switch-fall-through"><img height="21" width="21" src="javaguidelink.png"/></a></h5>
+    <p>Within a switch block, each statement group either terminates abruptly (with a
+<code class="prettyprint lang-java">break</code>,
+<code class="prettyprint lang-java">continue</code>,
+<code class="prettyprint lang-java">return</code> or thrown exception), or is marked with a comment
+to indicate that execution will or <em>might</em> continue into the next statement group. Any
+comment that communicates the idea of fall-through is sufficient (typically
+<code class="prettyprint lang-java">// fall through</code>). This special comment is not required in
+the last statement group of the switch block. Example:</p><pre class="prettyprint lang-java">
+switch (input) {
+  case 1:
+  case 2:
+    prepareOneOrTwo();
+    // fall through
+  case 3:
+    handleOneTwoOrThree();
+    break;
+  default:
+    handleLargeNumber(input);
+}
+</pre><a name="s4.8.4.3-switch-default"/>
+    <h5>4.8.4.3 The default case is present&nbsp;<a href="#s4.8.4.3-switch-default"><img height="21" width="21" src="javaguidelink.png"/></a></h5>
+    <p>Each switch statement includes a <code class="prettyprint lang-java">default</code> statement
+group, even if it contains no code.</p><a name="annotations"/><a name="s4.8.5-annotations"/>
+    <h4>4.8.5 Annotations&nbsp;<a href="#s4.8.5-annotations"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Annotations applying to a class, method or constructor appear immediately after the
+documentation block, and each annotation is listed on a line of its own (that is, one annotation
+per line). These line breaks do not constitute line-wrapping (Section
+4.5, <a href="#s4.5-line-wrapping">Line-wrapping</a>), so the indentation level is not
+increased. Example:</p><pre class="prettyprint lang-java">
+@Override
+@Nullable
+public String getNameIfPresent() { ... }
+</pre><p class="exception"><strong>Exception:</strong> A <em>single</em> parameterless annotation
+<em>may</em> instead appear together with the first line of the signature, for example:</p><pre class="prettyprint lang-java">
+@Override public int hashCode() { ... }
+</pre><p>Annotations applying to a field also appear immediately after the documentation block, but in
+this case, <em>multiple</em> annotations (possibly parameterized) may be listed on the same line;
+for example:</p><pre class="prettyprint lang-java">
+@Partial @Mock DataLoader loader;
+</pre><p>There are no specific rules for formatting parameter and local variable annotations.</p><a name="comments"/><a name="s4.8.6-comments"/>
+    <h4>4.8.6 Comments&nbsp;<a href="#s4.8.6-comments"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <a name="s4.8.6.1-block-comment-style"/>
+    <h5>4.8.6.1 Block comment style&nbsp;<a href="#s4.8.6.1-block-comment-style"><img height="21" width="21" src="javaguidelink.png"/></a></h5>
+    <p>Block comments are indented at the same level as the surrounding code. They may be in
+<code class="prettyprint lang-java">/* ... */</code> style or
+<code class="prettyprint lang-java">// ...</code> style. For multi-line
+<code class="prettyprint lang-java">/* ... */</code> comments, subsequent lines must start with
+<code>*</code> aligned with the <code>*</code> on the previous line.</p><pre class="prettyprint lang-java">
+/*
+ * This is          // And so           /* Or you can
+ * okay.            // is this.          * even do this. */
+ */
+</pre><p>Comments are not enclosed in boxes drawn with asterisks or other characters.</p><p class="tip"><strong>Tip:</strong> When writing multi-line comments, use the
+<code class="prettyprint lang-java">/* ... */</code> style if you want automatic code formatters to
+re-wrap the lines when necessary (paragraph-style). Most formatters don't re-wrap lines in
+<code class="prettyprint lang-java">// ...</code> style comment blocks.</p><a name="modifiers"/><a name="s4.8.7-modifiers"/>
+    <h4>4.8.7 Modifiers&nbsp;<a href="#s4.8.7-modifiers"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Class and member modifiers, when present, appear in the order
+recommended by the Java Language Specification:
+</p><pre>
+public protected private abstract static final transient volatile synchronized native strictfp
+</pre><a name="s4.8.8-numeric-literals"/>
+    <h4>4.8.8 Numeric Literals&nbsp;<a href="#s4.8.8-numeric-literals"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p><code>long</code>-valued integer literals use an uppercase <code>L</code> suffix, never
+lowercase (to avoid confusion with the digit <code>1</code>). For example, <code>3000000000L</code>
+rather than <code class="badcode">3000000000l</code>.</p><a name="naming"/><a name="s5-naming"/>
+    <h2>5 Naming&nbsp;<a href="#s5-naming"><img height="21" width="21" src="javaguidelink.png"/></a></h2>
+    <a name="s5.1-identifier-names"/>
+    <h3>5.1 Rules common to all identifiers&nbsp;<a href="#s5.1-identifier-names"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>Identifiers use only ASCII letters and digits, and in two cases noted below, underscores. Thus
+each valid identifier name is matched by the regular expression <code>\w+</code> .</p><p> In Google Style special prefixes or
+suffixes, like those seen in the examples <code class="badcode">name_</code>,
+<code class="badcode">mName</code>, <code class="badcode">s_name</code> and
+<code class="badcode">kName</code>, are <strong>not</strong> used.
+For WPILib, we do make one exception to this rule for non-constant field name.</p><a name="s5.2-specific-identifier-names"/>
+    <h3>5.2 Rules by identifier type&nbsp;<a href="#s5.2-specific-identifier-names"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <a name="s5.2.1-package-names"/>
+    <h4>5.2.1 Package names&nbsp;<a href="#s5.2.1-package-names"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Package names are all lowercase, with consecutive words simply concatenated together (no
+underscores). For example, <code>com.example.deepspace</code>, not
+<code class="badcode">com.example.deepSpace</code> or
+<code class="badcode">com.example.deep_space</code>.</p><a name="s5.2.2-class-names"/>
+    <h4>5.2.2 Class names&nbsp;<a href="#s5.2.2-class-names"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Class names are written in <a href="#s5.3-camel-case">UpperCamelCase</a>.</p><p>Class names are typically nouns or noun phrases. For example,
+<code class="prettyprint lang-java">Character</code> or
+<code class="prettyprint lang-java">ImmutableList</code>. Interface names may also be nouns or
+noun phrases (for example, <code class="prettyprint lang-java">List</code>), but may sometimes be
+adjectives or adjective phrases instead (for example,
+<code class="prettyprint lang-java">Readable</code>).</p><p>There are no specific rules or even well-established conventions for naming annotation types.</p><p><em>Test</em> classes are named starting with the name of the class they are testing, and ending
+with <code class="prettyprint lang-java">Test</code>. For example,
+<code class="prettyprint lang-java">HashTest</code> or
+<code class="prettyprint lang-java">HashIntegrationTest</code>.</p><a name="s5.2.3-method-names"/>
+    <h4>5.2.3 Method names&nbsp;<a href="#s5.2.3-method-names"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Method names are written in <a href="#s5.3-camel-case">lowerCamelCase</a>.</p><p>Method names are typically verbs or verb phrases. For example,
+<code class="prettyprint lang-java">sendMessage</code> or
+<code class="prettyprint lang-java">stop</code>.</p><p>Underscores may appear in JUnit <em>test</em> method names to separate logical components of the
+name. One typical pattern is <code>test<i>&lt;MethodUnderTest&gt;</i>_<i>&lt;state&gt;</i></code>,
+for example <code class="prettyprint lang-java">testPop_emptyStack</code>. There is no One Correct
+Way to name test methods.</p><a name="constants"/><a name="s5.2.4-constant-names"/>
+    <h4>5.2.4 Constant names&nbsp;<a href="#s5.2.4-constant-names"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Constant names use <code class="prettyprint lang-java">CONSTANT_CASE</code>: all uppercase
+letters, with words separated by underscores. But what <em>is</em> a constant, exactly?</p><p>Every constant is a static final field, but not all static final fields are constants. Before
+choosing constant case, consider whether the field really <em>feels like</em> a constant. For
+example, if any of that instance's observable state can change, it is almost certainly not a
+constant. Merely <em>intending</em> to never mutate the object is generally not
+enough. Examples:</p><pre class="prettyprint lang-java">
+// Constants
+static final int NUMBER = 5;
+static final ImmutableList&lt;String&gt; NAMES = ImmutableList.of("Ed", "Ann");
+static final Joiner COMMA_JOINER = Joiner.on(',');  // because Joiner is immutable
+static final SomeMutableType[] EMPTY_ARRAY = {};
+enum SomeEnum { ENUM_CONSTANT }
+
+// Not constants
+static String nonFinal = "non-final";
+final String nonStatic = "non-static";
+static final Set&lt;String&gt; mutableCollection = new HashSet&lt;String&gt;();
+static final ImmutableSet&lt;SomeMutableType&gt; mutableElements = ImmutableSet.of(mutable);
+static final Logger logger = Logger.getLogger(MyClass.getName());
+static final String[] nonEmptyArray = {"these", "can", "change"};
+</pre><p>These names are typically nouns or noun phrases.</p><a name="s5.2.5-non-constant-field-names"/>
+    <h4>5.2.5 Non-constant field names&nbsp;<a href="#s5.2.5-non-constant-field-names"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Non-constant field names (static or otherwise) are written
+in <a href="#s5.3-camel-case">lowerCamelCase</a> with a preceding <code class="prettyprint lang-java">m_</code>.</p>
+<p>These names are typically nouns or noun phrases.  For example,
+<code class="prettyprint lang-java">m_computedValues</code> or
+<code class="prettyprint lang-java">m_index</code>.</p><a name="s5.2.6-parameter-names"/>
+    <h4>5.2.6 Parameter names&nbsp;<a href="#s5.2.6-parameter-names"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Parameter names are written in <a href="#s5.3-camel-case">lowerCamelCase</a>.</p><p>One-character parameter names should be avoided.</p><a name="s5.2.7-local-variable-names"/>
+    <h4>5.2.7 Local variable names&nbsp;<a href="#s5.2.7-local-variable-names"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Local variable names are written in <a href="#s5.3-camel-case">lowerCamelCase</a>, and can be
+abbreviated more liberally than other types of names.</p><p>However, one-character names should be avoided, except for temporary and looping variables.</p><p>Even when final and immutable, local variables are not considered to be constants, and should not
+be styled as constants.</p><a name="s5.2.8-type-variable-names"/>
+    <h4>5.2.8 Type variable names&nbsp;<a href="#s5.2.8-type-variable-names"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Each type variable is named in one of two styles:</p><ul><li>A single capital letter, optionally followed by a single numeral (such as
+  <code class="prettyprint lang-java">E</code>, <code class="prettyprint lang-java">T</code>,
+  <code class="prettyprint lang-java">X</code>, <code class="prettyprint lang-java">T2</code>)
+  </li><li>A name in the form used for classes (see Section 5.2.2,
+  <a href="#s5.2.2-class-names">Class names</a>), followed by the capital letter
+  <code class="prettyprint lang-java">T</code> (examples:
+  <code class="prettyprint lang-java">RequestT</code>,
+  <code class="prettyprint lang-java">FooBarT</code>).</li></ul><a name="acronyms"/><a name="camelcase"/><a name="s5.3-camel-case"/>
+    <h3>5.3 Camel case: defined&nbsp;<a href="#s5.3-camel-case"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>Sometimes there is more than one reasonable way to convert an English phrase into camel case,
+such as when acronyms or unusual constructs like "IPv6" or "iOS" are present. To improve
+predictability, Google Style specifies the following (nearly) deterministic scheme.</p><p>Beginning with the prose form of the name:</p><ol><li>Convert the phrase to plain ASCII and remove any apostrophes. For example, "Müller's
+  algorithm" might become "Muellers algorithm".</li><li>Divide this result into words, splitting on spaces and any remaining punctuation (typically
+  hyphens).
+
+  <ul><li><em>Recommended:</em> if any word already has a conventional camel-case appearance in common
+    usage, split this into its constituent parts (e.g., "AdWords" becomes "ad words"). Note
+    that a word such as "iOS" is not really in camel case <em>per se</em>; it defies <em>any</em>
+    convention, so this recommendation does not apply.</li></ul></li><li>Now lowercase <em>everything</em> (including acronyms), then uppercase only the first
+  character of:
+  <ul><li>... each word, to yield <em>upper camel case</em>, or</li><li>... each word except the first, to yield <em>lower camel case</em></li></ul></li><li>Finally, join all the words into a single identifier.</li></ol><p>Note that the casing of the original words is almost entirely disregarded. Examples:</p><table><tr><th>Prose form</th><th>Correct</th><th>Incorrect</th></tr><tr><td>"XML HTTP request"</td><td><code class="prettyprint lang-java">XmlHttpRequest</code></td><td><code class="badcode">XMLHTTPRequest</code></td></tr><tr><td>"new customer ID"</td><td><code class="prettyprint lang-java">newCustomerId</code></td><td><code class="badcode">newCustomerID</code></td></tr><tr><td>"inner stopwatch"</td><td><code class="prettyprint lang-java">innerStopwatch</code></td><td><code class="badcode">innerStopWatch</code></td></tr><tr><td>"supports IPv6 on iOS?"</td><td><code class="prettyprint lang-java">supportsIpv6OnIos</code></td><td><code class="badcode">supportsIPv6OnIOS</code></td></tr><tr><td>"YouTube importer"</td><td><code class="prettyprint lang-java">YouTubeImporter</code><br/><code class="prettyprint lang-java">YoutubeImporter</code>*</td><td/></tr></table><p>*Acceptable, but not recommended.</p><p class="note"><strong>Note:</strong> Some words are ambiguously hyphenated in the English
+language: for example "nonempty" and "non-empty" are both correct, so the method names
+<code class="prettyprint lang-java">checkNonempty</code> and
+<code class="prettyprint lang-java">checkNonEmpty</code> are likewise both correct.</p><a name="s6-programming-practices"/>
+    <h2>6 Programming Practices&nbsp;<a href="#s6-programming-practices"><img height="21" width="21" src="javaguidelink.png"/></a></h2>
+    <a name="s6.1-override-annotation"/>
+    <h3>6.1 @Override: always used&nbsp;<a href="#s6.1-override-annotation"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>A method is marked with the <code class="prettyprint lang-java">@Override</code> annotation
+whenever it is legal.  This includes a class method overriding a superclass method, a class method
+implementing an interface method, and an interface method respecifying a superinterface
+method.</p><p class="exception"><strong>Exception:</strong><code class="prettyprint lang-java">@Override</code> may be omitted when the parent method is
+<code class="prettyprint lang-java">@Deprecated</code>.</p><a name="caughtexceptions"/><a name="s6.2-caught-exceptions"/>
+    <h3>6.2 Caught exceptions: not ignored&nbsp;<a href="#s6.2-caught-exceptions"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>Except as noted below, it is very rarely correct to do nothing in response to a caught
+exception. (Typical responses are to log it, or if it is considered "impossible", rethrow it as an
+<code class="prettyprint lang-java">AssertionError</code>.)</p><p>When it truly is appropriate to take no action whatsoever in a catch block, the reason this is
+justified is explained in a comment.</p><pre class="prettyprint lang-java">
+try {
+  int i = Integer.parseInt(response);
+  return handleNumericResponse(i);
+} catch (NumberFormatException ok) {
+  // it's not numeric; that's fine, just continue
+}
+return handleTextResponse(response);
+</pre><p class="exception"><strong>Exception:</strong> In tests, a caught exception may be ignored
+without comment <em>if</em> it is named <code class="prettyprint lang-java">expected</code>. The
+following is a very common idiom for ensuring that the method under test <em>does</em> throw an
+exception of the expected type, so a comment is unnecessary here.</p><pre class="prettyprint lang-java">
+try {
+  emptyStack.pop();
+  fail();
+} catch (NoSuchElementException expected) {
+}
+</pre><a name="s6.3-static-members"/>
+    <h3>6.3 Static members: qualified using class&nbsp;<a href="#s6.3-static-members"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>When a reference to a static class member must be qualified, it is qualified with that class's
+name, not with a reference or expression of that class's type.</p><pre class="prettyprint lang-java">
+Foo aFoo = ...;
+Foo.aStaticMethod(); // good
+<span class="badcode">aFoo.aStaticMethod();</span> // bad
+<span class="badcode">somethingThatYieldsAFoo().aStaticMethod();</span> // very bad
+</pre><a name="finalizers"/><a name="s6.4-finalizers"/>
+    <h3>6.4 Finalizers: not used&nbsp;<a href="#s6.4-finalizers"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>It is <strong>extremely rare</strong> to override <code class="prettyprint lang-java">Object.finalize</code>.</p><p class="tip"><strong>Tip:</strong> Don't do it. If you absolutely must, first read and understand
+<a href="http://books.google.com/books?isbn=8131726592"><em>Effective Java</em></a>
+Item 7, "Avoid Finalizers," very carefully, and <em>then</em> don't do it.</p><a name="javadoc"/><a name="s7-javadoc"/>
+    <h2>7 Javadoc&nbsp;<a href="#s7-javadoc"><img height="21" width="21" src="javaguidelink.png"/></a></h2>
+    <a name="s7.1-javadoc-formatting"/>
+    <h3>7.1 Formatting&nbsp;<a href="#s7.1-javadoc-formatting"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <a name="s7.1.1-javadoc-multi-line"/>
+    <h4>7.1.1 General form&nbsp;<a href="#s7.1.1-javadoc-multi-line"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>The <em>basic</em> formatting of Javadoc blocks is as seen in this example:</p><pre class="prettyprint lang-java">
+/**
+ * Multiple lines of Javadoc text are written here,
+ * wrapped normally...
+ */
+public int method(String p1) { ... }
+</pre><p>... or in this single-line example:</p><pre class="prettyprint lang-java">
+/** An especially short bit of Javadoc. */
+</pre><p>The basic form is always acceptable. The single-line form may be substituted when there are no
+at-clauses present, and the entirety of the Javadoc block (including comment markers) can fit on a
+single line.</p><a name="s7.1.2-javadoc-paragraphs"/>
+    <h4>7.1.2 Paragraphs&nbsp;<a href="#s7.1.2-javadoc-paragraphs"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>One blank line—that is, a line containing only the aligned leading asterisk
+(<code>*</code>)—appears between paragraphs, and before the group of "at-clauses" if
+present. Each paragraph but the first has <code>&lt;p&gt;</code> immediately before the first word,
+with no space after.</p><a name="s7.1.3-javadoc-at-clauses"/>
+    <h4>7.1.3 At-clauses&nbsp;<a href="#s7.1.3-javadoc-at-clauses"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Any of the standard "at-clauses" that are used appear in the order <code>@param</code>,
+<code>@return</code>, <code>@throws</code>, <code>@deprecated</code>, and these four types never
+appear with an empty description. When an at-clause doesn't fit on a single line, continuation lines
+are indented four (or more) spaces from the position of the <code>@</code>.
+</p><a name="s7.2-summary-fragment"/>
+    <h3>7.2 The summary fragment&nbsp;<a href="#s7.2-summary-fragment"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>The Javadoc for each class and member begins with a brief <strong>summary fragment</strong>. This
+fragment is very important: it is the only part of the text that appears in certain contexts such as
+class and method indexes.</p><p>This is a fragment—a noun phrase or verb phrase, not a complete sentence. It does
+<strong>not</strong> begin with <code class="badcode">A {@code Foo} is a...</code>, or
+<code class="badcode">This method returns...</code>, nor does it form a complete imperative sentence
+like <code class="badcode">Save the record.</code>. However, the fragment is capitalized and
+punctuated as if it were a complete sentence.</p><p class="tip"><strong>Tip:</strong> A common mistake is to write simple Javadoc in the form
+<code class="badcode">/** @return the customer ID */</code>. This is incorrect, and should be
+changed to <code class="prettyprint lang-java">/** Returns the customer ID. */</code>.</p><a name="s7.3.3-javadoc-optional"/><a name="s7.3-javadoc-where-required"/>
+    <h3>7.3 Where Javadoc is used&nbsp;<a href="#s7.3-javadoc-where-required"><img height="21" width="21" src="javaguidelink.png"/></a></h3>
+    <p>At the <em>minimum</em>, Javadoc is present for every
+<code class="prettyprint lang-java">public</code> class, and every
+<code class="prettyprint lang-java">public</code> or
+<code class="prettyprint lang-java">protected</code> member of such a class, with a few exceptions
+noted below.</p><p>Other classes and members still have Javadoc <em>as needed</em>.  Whenever an implementation
+comment would be used to define the overall purpose or behavior of a class, method or field, that
+comment is written as Javadoc instead. (It's more uniform, and more tool-friendly.)</p><a name="s7.3.1-javadoc-exception-self-explanatory"/>
+    <h4>7.3.1 Exception: self-explanatory methods&nbsp;<a href="#s7.3.1-javadoc-exception-self-explanatory"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Javadoc is optional for "simple, obvious" methods like
+<code class="prettyprint lang-java">getFoo</code>, in cases where there <em>really and truly</em> is
+nothing else worthwhile to say but "Returns the foo".</p><p class="note"><strong>Important:</strong> it is not appropriate to cite this exception to justify
+omitting relevant information that a typical reader might need to know. For example, for a method
+named <code class="prettyprint lang-java">getCanonicalName</code>, don't omit its documentation
+(with the rationale that it would say only
+<code class="badcode">/** Returns the canonical name. */</code>) if a typical reader may have no idea
+what the term "canonical name" means!</p><a name="s7.3.2-javadoc-exception-overrides"/>
+    <h4>7.3.2 Exception: overrides&nbsp;<a href="#s7.3.2-javadoc-exception-overrides"><img height="21" width="21" src="javaguidelink.png"/></a></h4>
+    <p>Javadoc is not always present on a method that overrides a supertype method.
+</p></div>  <hr/>
+  <div class="change">Last changed: March 21, 2014</div>
+</body>
+</html>
diff --git a/styleguide/javaguidelink.png b/styleguide/javaguidelink.png
new file mode 100644
index 0000000..75d5c7b
--- /dev/null
+++ b/styleguide/javaguidelink.png
Binary files differ
diff --git a/styleguide/styleguide.css b/styleguide/styleguide.css
new file mode 100644
index 0000000..adba8f3
--- /dev/null
+++ b/styleguide/styleguide.css
@@ -0,0 +1,147 @@
+body {
+  background-color: #fff;
+  color: #333;
+  font-family: sans-serif;
+  font-size: 10pt;
+  margin-right: 100px;
+  margin-left: 100px;
+}
+
+h1, h2, h3, h4, h5, h6, .toc_title {
+  color: #06c;
+  margin-top: 2em;
+  margin-bottom: 1em;
+}
+
+h1 {
+  text-align: center;
+  font-size: 18pt;
+}
+
+h2, .toc_title {
+  font-weight: bold;
+  font-size: 12pt;
+  margin-left: -40px;
+}
+
+h3, h4, h5, h6 {
+  font-size: 10pt;
+  margin-left: -20px;
+}
+
+.toc_category, .toc_stylepoint {
+  font-size: 10pt;
+  padding-top: .3em;
+  padding-bottom: .3em;
+}
+
+table {
+  border-collapse: collapse;
+}
+
+td, th {
+  border: 1px solid #ccc;
+  padding: 2px 12px;
+  font-size: 10pt;
+}
+
+.toc td, .toc th {
+  border-width: 1px 5px;
+}
+
+code, samp, var {
+  color: #060;
+}
+
+pre {
+  font-size: 10pt;
+  display: block;
+  color: #060;
+  background-color: #f8fff8;
+  border-color: #f0fff0;
+  border-style: solid;
+  border-top-width: 1px;
+  border-bottom-width: 1px;
+  border-right-width: 1px;
+  border-left-width: 5px;
+  padding-left: 12px;
+  padding-right: 12px;
+  padding-top: 4px;
+  padding-bottom: 4px;
+}
+
+pre.badcode {
+  color: #c00;
+  background-color: #fff8f8;
+  border-color: #fff0f0;
+}
+
+.showhide_button {
+  float: left;
+  cursor: pointer;
+  border-width: 1px;
+  border-style: solid;
+  border-color: #ddd #aaa #aaa #ddd;
+  padding: 0 3px 1px;
+  margin: 0 4px 8px 0;
+  border-radius: 3px;
+  -webkit-border-radius: 3px;
+  -moz-border-radius: 3px;
+}
+
+.link_button {
+  float: left;
+  display: none;
+  background-color: #f8f8ff;
+  border-color: #f0f0ff;
+  border-style: solid;
+  border-width: 1px;
+  font-size: 75%;
+  margin-top: 0;
+  margin-left: -50px;
+  padding: 4px;
+  border-radius: 3px;
+  -webkit-border-radius: 3px;
+  -moz-border-radius: 3px;
+}
+
+address {
+  text-align: right;
+}
+
+hr {
+  margin-top: 3.5em;
+  border-width: 1px;
+  color: #fff;
+}
+
+.stylepoint_section {
+  display: block;
+  margin-bottom: 1em;
+  color: #5588ff;
+  font-family: sans-serif;
+  font-size: 90%;
+  font-weight: bold;
+  margin-left: -2%;
+}
+
+.stylepoint_subsection {
+  color: #667799;
+  font-family: sans-serif;
+  font-size: 90%;
+  font-weight: bold;
+  margin-left: -1%;
+}
+
+.stylepoint_subsubsection {
+  color: #667799;
+  font-family: sans-serif;
+  font-size: 80%;
+  font-weight: bold;
+  margin-left: 0;
+}
+
+.revision {
+  text-align: right;
+}
+
diff --git a/styleguide/styleguide.xsl b/styleguide/styleguide.xsl
new file mode 100644
index 0000000..09a9b95
--- /dev/null
+++ b/styleguide/styleguide.xsl
@@ -0,0 +1,924 @@
+<xsl:stylesheet version="1.0"
+xmlns:xsl="http://www.w3.org/1999/XSL/Transform"
+xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
+xmlns:dc="http://purl.org/dc/elements/1.1/"
+xmlns:dcq="http://purl.org/dc/qualifiers/1.0/"
+xmlns:fo="http://www.w3.org/1999/XSL/Format"
+xmlns:fn="http://www.w3.org/2005/xpath-functions">
+  <xsl:output method="html"/>
+  <!-- Set to 1 to show explanations by default.  Set to 0 to hide them -->
+  <xsl:variable name="show_explanation_default" select="0" />
+  <!-- The characters within the Webdings font that show the triangles -->
+  <xsl:variable name="show_button_text" select="'&#x25B6;'" />
+  <xsl:variable name="hide_button_text" select="'&#x25BD;'" />
+  <!-- The suffix for names -->
+  <xsl:variable name="button_suffix" select="'__button'"/>
+  <xsl:variable name="body_suffix" select="'__body'"/>
+  <!-- For easy reference, the name of the button -->
+  <xsl:variable name="show_hide_all_button" select="'show_hide_all_button'"/>
+
+  <!-- The top-level element -->
+  <xsl:template match="GUIDE">
+      <HTML>
+          <HEAD>
+              <TITLE><xsl:value-of select="@title"/></TITLE>
+              <META http-equiv="Content-Type" content="text/html; charset=utf-8"/>
+              <LINK HREF="http://www.google.com/favicon.ico" type="image/x-icon"
+                    rel="shortcut icon"/>
+              <LINK HREF="styleguide.css"
+                    type="text/css" rel="stylesheet"/>
+
+              <SCRIPT language="javascript" type="text/javascript">
+
+                function GetElementsByName(name) {
+                  // Workaround a bug on old versions of opera.
+                  if (document.getElementsByName) {
+                    return document.getElementsByName(name);
+                  } else {
+                    return [document.getElementById(name)];
+                  }
+                }
+
+                /**
+                 * @param {string} namePrefix The prefix of the body name.
+                 * @param {function(boolean): boolean} getVisibility Computes the new
+                 *     visibility state, given the current one.
+                 */
+                function ChangeVisibility(namePrefix, getVisibility) {
+                  var bodyName = namePrefix + '<xsl:value-of select="$body_suffix"/>';
+                  var buttonName = namePrefix + '<xsl:value-of select="$button_suffix"/>';
+                  var bodyElements = GetElementsByName(bodyName);
+                  var linkElement = GetElementsByName('link-' + buttonName)[0];
+                  if (bodyElements.length != 1) {
+                    throw Error('ShowHideByName() got the wrong number of bodyElements:  ' + 
+                        bodyElements.length);
+                  } else {
+                    var bodyElement = bodyElements[0];
+                    var buttonElement = GetElementsByName(buttonName)[0];
+                    var isVisible = bodyElement.style.display != "none";
+                    if (getVisibility(isVisible)) {
+                      bodyElement.style.display = "inline";
+                      linkElement.style.display = "block";
+                      buttonElement.innerHTML = '<xsl:value-of select="$hide_button_text"/>';
+                    } else {
+                      bodyElement.style.display = "none";
+                      linkElement.style.display = "none";
+                      buttonElement.innerHTML = '<xsl:value-of select="$show_button_text"/>';
+                    }
+                  }
+                }
+
+                function ShowHideByName(namePrefix) {
+                  ChangeVisibility(namePrefix, function(old) { return !old; });
+                }
+
+                function ShowByName(namePrefix) {
+                  ChangeVisibility(namePrefix, function() { return true; });
+                }
+
+                function ShowHideAll() {
+                  var allButton = GetElementsByName("show_hide_all_button")[0];
+                  if (allButton.innerHTML == '<xsl:value-of select="$hide_button_text"/>') {
+                    allButton.innerHTML = '<xsl:value-of select="$show_button_text"/>';
+                    SetHiddenState(document.getElementsByTagName("body")[0].childNodes, "none", '<xsl:value-of select="$show_button_text"/>');
+                  } else {
+                    allButton.innerHTML = '<xsl:value-of select="$hide_button_text"/>';
+                    SetHiddenState(document.getElementsByTagName("body")[0].childNodes, "inline", '<xsl:value-of select="$hide_button_text"/>');
+                  }
+                }
+
+                // Recursively sets state of all children
+                // of a particular node.
+                function SetHiddenState(root, newState, newButton) {
+                  for (var i = 0; i != root.length; i++) {
+                    SetHiddenState(root[i].childNodes, newState, newButton);
+                    if (root[i].className == 'showhide_button')  {
+                      root[i].innerHTML = newButton;
+                    }
+                    if (root[i].className == 'stylepoint_body' ||
+                        root[i].className == 'link_button')  {
+                      root[i].style.display = newState;
+                    }
+                  }
+                }
+
+
+                function EndsWith(str, suffix) {
+                  var l = str.length - suffix.length;
+                  return l >= 0 &amp;&amp; str.indexOf(suffix, l) == l;
+                }
+
+                function RefreshVisibilityFromHashParam() {
+                  var hashRegexp = new RegExp('#([^&amp;#]*)$');
+                  var hashMatch = hashRegexp.exec(window.location.href);
+                  var anchor = hashMatch &amp;&amp; GetElementsByName(hashMatch[1])[0];
+                  var node = anchor;
+                  var suffix = '<xsl:value-of select="$body_suffix"/>';
+                  while (node) {
+                    var id = node.id;
+                    var matched = id &amp;&amp; EndsWith(id, suffix);
+                    if (matched) {
+                      var len = id.length - suffix.length;
+                      ShowByName(id.substring(0, len));
+                      if (anchor.scrollIntoView) {
+                        anchor.scrollIntoView();
+                      }
+
+                      return;
+                    }
+                    node = node.parentNode;
+                  }
+                }
+
+                window.onhashchange = RefreshVisibilityFromHashParam;
+
+                window.onload = function() {
+                  // if the URL contains "?showall=y", expand the details of all children
+                  var showHideAllRegex = new RegExp("[\\?&amp;](showall)=([^&amp;#]*)");
+                  var showHideAllValue = showHideAllRegex.exec(window.location.href);
+                  if (showHideAllValue != null) {
+                    if (showHideAllValue[2] == "y") {
+                      SetHiddenState(document.getElementsByTagName("body")[0].childNodes, 
+                          "inline", '<xsl:value-of select="$hide_button_text"/>');
+                    } else {
+                      SetHiddenState(document.getElementsByTagName("body")[0].childNodes, 
+                          "none", '<xsl:value-of select="$show_button_text"/>');
+                    }
+                  }
+                  var showOneRegex = new RegExp("[\\?&amp;](showone)=([^&amp;#]*)");
+                  var showOneValue = showOneRegex.exec(window.location.href);
+                  if (showOneValue) {
+                    ShowHideByName(showOneValue[2]);
+                  }
+
+
+                  RefreshVisibilityFromHashParam();
+                }
+              </SCRIPT>
+          </HEAD>
+          <BODY>
+            <H1><xsl:value-of select="@title"/></H1>
+              <xsl:apply-templates/>
+          </BODY>
+      </HTML>
+  </xsl:template>
+
+  <xsl:template match="OVERVIEW">
+    <xsl:variable name="button_text">
+      <xsl:choose>
+        <xsl:when test="$show_explanation_default">
+          <xsl:value-of select="$hide_button_text"/>
+        </xsl:when>
+        <xsl:otherwise>
+          <xsl:value-of select="$show_button_text"/>
+        </xsl:otherwise>
+      </xsl:choose>
+    </xsl:variable>
+    <DIV style="margin-left: 50%; font-size: 75%;">
+      <P>
+        Each style point has a summary for which additional information is available
+        by toggling the accompanying arrow button that looks this way:
+        <SPAN class="showhide_button" style="margin-left: 0; float: none">
+          <xsl:value-of select="$show_button_text"/></SPAN>.
+        You may toggle all summaries with the big arrow button:
+      </P>
+      <DIV style=" font-size: larger; margin-left: +2em;">
+        <SPAN class="showhide_button" style="font-size: 180%; float: none">
+          <xsl:attribute name="onclick"><xsl:value-of select="'javascript:ShowHideAll()'"/></xsl:attribute>
+          <xsl:attribute name="name"><xsl:value-of select="$show_hide_all_button"/></xsl:attribute>
+          <xsl:attribute name="id"><xsl:value-of select="$show_hide_all_button"/></xsl:attribute>
+          <xsl:value-of select="$button_text"/>
+        </SPAN>
+        Toggle all summaries
+      </DIV>
+    </DIV>
+    <xsl:call-template name="TOC">
+      <xsl:with-param name="root" select=".."/>
+    </xsl:call-template>
+    <xsl:apply-templates/>
+  </xsl:template>
+
+  <xsl:template match="PARTING_WORDS">
+    <H2>Parting Words</H2>
+    <xsl:apply-templates/>
+  </xsl:template>
+
+  <xsl:template match="CATEGORY">
+    <DIV>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <H2>
+        <xsl:variable name="category_name">
+          <xsl:call-template name="anchorname">
+            <xsl:with-param name="sectionname" select="@title"/>
+          </xsl:call-template>
+        </xsl:variable>
+        <xsl:attribute name="name"><xsl:value-of select="$category_name"/></xsl:attribute>
+        <xsl:attribute name="id"><xsl:value-of select="$category_name"/></xsl:attribute>
+        <xsl:value-of select="@title"/>
+      </H2>
+      <xsl:apply-templates/>
+    </DIV>
+  </xsl:template>
+
+  <xsl:template match="STYLEPOINT">
+    <DIV>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <xsl:variable name="stylepoint_name">
+        <xsl:call-template name="anchorname">
+          <xsl:with-param name="sectionname" select="@title"/>
+        </xsl:call-template>
+      </xsl:variable>
+      <xsl:variable name="button_text">
+        <xsl:choose>
+          <xsl:when test="$show_explanation_default">
+            <xsl:value-of select="$hide_button_text"/>
+          </xsl:when>
+          <xsl:otherwise>
+            <xsl:value-of select="$show_button_text"/>
+          </xsl:otherwise>
+        </xsl:choose>
+      </xsl:variable>
+      <H3>
+        <A>
+          <xsl:attribute name="name"><xsl:value-of select="$stylepoint_name"/></xsl:attribute>
+          <xsl:attribute name="id"><xsl:value-of select="$stylepoint_name"/></xsl:attribute>
+          <xsl:value-of select="@title"/>
+        </A>
+      </H3>
+      <xsl:variable name="buttonName">
+        <xsl:value-of select="$stylepoint_name"/><xsl:value-of select="$button_suffix"/>
+      </xsl:variable>
+      <xsl:variable name="onclick_definition">
+        <xsl:text>javascript:ShowHideByName('</xsl:text>
+        <xsl:value-of select="$stylepoint_name"/>
+        <xsl:text>')</xsl:text>
+      </xsl:variable>
+      <SPAN class="link_button" id="link-{$buttonName}" name="link-{$buttonName}">
+        <A>
+          <xsl:attribute name="href">?showone=<xsl:value-of select="$stylepoint_name"/>#<xsl:value-of select="$stylepoint_name"/></xsl:attribute>
+          link
+        </A>
+      </SPAN>
+      <SPAN class="showhide_button">
+        <xsl:attribute name="onclick"><xsl:value-of select="$onclick_definition"/></xsl:attribute>
+        <xsl:attribute name="name"><xsl:value-of select="$buttonName"/></xsl:attribute>
+        <xsl:attribute name="id"><xsl:value-of select="$buttonName"/></xsl:attribute>
+        <xsl:value-of select="$button_text"/>
+      </SPAN>
+      <xsl:apply-templates>
+        <xsl:with-param name="anchor_prefix" select="$stylepoint_name" />
+      </xsl:apply-templates>
+    </DIV>
+  </xsl:template>
+
+  <xsl:template match="SUMMARY">
+    <xsl:param name="anchor_prefix" />
+    <DIV style="display:inline;">
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <xsl:apply-templates/>
+    </DIV>
+  </xsl:template>
+
+  <xsl:template match="BODY">
+    <xsl:param name="anchor_prefix" />
+    <DIV>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <DIV class="stylepoint_body">
+        <xsl:attribute name="name"><xsl:value-of select="$anchor_prefix"/><xsl:value-of select="$body_suffix"/></xsl:attribute>
+        <xsl:attribute name="id"><xsl:value-of select="$anchor_prefix"/><xsl:value-of select="$body_suffix"/></xsl:attribute>
+        <xsl:attribute name="style">
+          <xsl:choose>
+            <xsl:when test="$show_explanation_default">display: inline</xsl:when>
+            <xsl:otherwise>display: none</xsl:otherwise>
+          </xsl:choose>
+        </xsl:attribute>
+        <xsl:apply-templates/>
+      </DIV>
+    </DIV>
+  </xsl:template>
+
+  <xsl:template match="DEFINITION">
+    <P>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <SPAN class="stylepoint_section">Definition:  </SPAN>
+      <xsl:apply-templates/>
+    </P>
+  </xsl:template>
+
+  <xsl:template match="PROS">
+    <P>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <SPAN class="stylepoint_section">Pros:  </SPAN>
+      <xsl:apply-templates/>
+    </P>
+  </xsl:template>
+
+  <xsl:template match="CONS">
+    <P>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <SPAN class="stylepoint_section">Cons: </SPAN>
+      <xsl:apply-templates/>
+    </P>
+  </xsl:template>
+
+  <xsl:template match="DECISION">
+    <P>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <SPAN class="stylepoint_section">Decision:  </SPAN>
+      <xsl:apply-templates/>
+    </P>
+  </xsl:template>
+
+  <xsl:template match="TODO">
+    <P>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <DIV style="font-size: 150%;">TODO:
+        <xsl:apply-templates/>
+      </DIV>
+    </P>
+  </xsl:template>
+
+  <xsl:template match="SUBSECTION">
+    <P>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <SPAN class="stylepoint_subsection"><xsl:value-of select="@title"/>  </SPAN>
+      <xsl:apply-templates/>
+    </P>
+  </xsl:template>
+
+  <xsl:template match="SUBSUBSECTION">
+    <P>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <SPAN class="stylepoint_subsubsection"><xsl:value-of select="@title"/>  </SPAN>
+      <xsl:apply-templates/>
+    </P>
+  </xsl:template>
+
+  <xsl:template match="CODE_SNIPPET">
+    <DIV>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <PRE><xsl:call-template name="print_without_leading_chars">
+           <xsl:with-param name="text" select="."/>
+           <xsl:with-param name="strip" select="1"/>
+           <xsl:with-param name="is_firstline" select="1"/>
+           <xsl:with-param name="trim_count">
+             <xsl:call-template name="num_leading_spaces">
+               <xsl:with-param name="text" select="."/>
+               <xsl:with-param name="max_so_far" select="1000"/>
+             </xsl:call-template>
+           </xsl:with-param>
+         </xsl:call-template></PRE>
+    </DIV>
+  </xsl:template>
+
+  <xsl:template match="BAD_CODE_SNIPPET">
+    <DIV>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <PRE class="badcode"><xsl:call-template name="print_without_leading_chars">
+           <xsl:with-param name="text" select="."/>
+           <xsl:with-param name="strip" select="1"/>
+           <xsl:with-param name="is_firstline" select="1"/>
+           <xsl:with-param name="trim_count">
+             <xsl:call-template name="num_leading_spaces">
+               <xsl:with-param name="text" select="."/>
+               <xsl:with-param name="max_so_far" select="1000"/>
+             </xsl:call-template>
+           </xsl:with-param>
+         </xsl:call-template></PRE>
+    </DIV>
+  </xsl:template>
+
+  <xsl:template match="PY_CODE_SNIPPET">
+    <DIV>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <PRE><xsl:call-template name="print_python_code">
+             <xsl:with-param name="text" select="."/>
+           </xsl:call-template></PRE>
+    </DIV>
+  </xsl:template>
+
+  <xsl:template match="BAD_PY_CODE_SNIPPET">
+    <DIV>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <PRE class="badcode"><xsl:call-template name="print_python_code">
+                             <xsl:with-param name="text" select="."/>
+                           </xsl:call-template></PRE>
+    </DIV>
+  </xsl:template>
+
+  <xsl:template match="FUNCTION">
+    <xsl:call-template name="print_function_name">
+      <xsl:with-param name="text" select="."/>
+    </xsl:call-template>
+  </xsl:template>
+
+  <xsl:template match="SYNTAX">
+    <I>
+      <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+      <xsl:apply-templates/>
+    </I>
+  </xsl:template>
+
+
+  <!-- This passes through any HTML elements that the
+    XML doc uses for minor formatting -->
+  <xsl:template match="a|address|blockquote|br|center|cite|code|dd|div|dl|dt|em|hr|i|img|li|ol|p|pre|span|table|td|th|tr|ul|var|A|ADDRESS|BLOCKQUOTE|BR|CENTER|CITE|CODE|DD|DIV|DL|DT|EM|HR|I|LI|OL|P|PRE|SPAN|TABLE|TD|TH|TR|UL|VAR">
+      <xsl:element name="{local-name()}">
+          <xsl:copy-of select="@*"/>
+          <xsl:apply-templates/>
+      </xsl:element>
+  </xsl:template>
+
+    <!-- Builds the table of contents -->
+  <xsl:template name="TOC">
+    <xsl:param name="root"/>
+    <DIV class="toc">
+      <DIV class="toc_title">Table of Contents</DIV>
+      <TABLE>
+      <xsl:for-each select="$root/CATEGORY">
+        <TR valign="top">
+          <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+          <TD>
+          <DIV class="toc_category">
+            <A>
+              <xsl:attribute name="href">
+                <xsl:text>#</xsl:text>
+                <xsl:call-template name="anchorname">
+                  <xsl:with-param name="sectionname" select="@title"/>
+                </xsl:call-template>
+              </xsl:attribute>
+              <xsl:value-of select="@title"/>
+            </A>
+          </DIV>
+          </TD><TD>
+            <DIV class="toc_stylepoint">
+              <xsl:for-each select="./STYLEPOINT">
+                <SPAN style="padding-right: 1em; white-space:nowrap;">
+                  <xsl:attribute name="class"><xsl:value-of select="@class"/></xsl:attribute>
+                  <A>
+                    <xsl:attribute name="href">
+                      <xsl:text>#</xsl:text>
+                      <xsl:call-template name="anchorname">
+                        <xsl:with-param name="sectionname" select="@title"/>
+                      </xsl:call-template>
+                    </xsl:attribute>
+                    <xsl:value-of select="@title"/>
+                  </A>
+                </SPAN>
+                <xsl:text> </xsl:text>
+              </xsl:for-each>
+            </DIV>
+          </TD>
+        </TR>
+      </xsl:for-each>
+      </TABLE>
+    </DIV>
+  </xsl:template>
+
+  <xsl:template name="TOC_one_stylepoint">
+    <xsl:param name="stylepoint"/>
+  </xsl:template>
+
+  <!-- Creates a standard anchor given any text.
+       Substitutes underscore for characters unsuitable for URLs  -->
+  <xsl:template name="anchorname">
+    <xsl:param name="sectionname"/>
+    <!-- strange quoting necessary to strip apostrophes -->
+    <xsl:variable name="bad_characters" select="&quot; ()#'&quot;"/>
+    <xsl:value-of select="translate($sectionname,$bad_characters,'_____')"/>
+  </xsl:template>
+
+  <!-- Given text, evaluates to the number of leading spaces. -->
+  <!-- TODO(csilvers): deal well with leading tabs (treat as 8 spaces?) -->
+  <xsl:template name="num_leading_spaces_one_line">
+    <xsl:param name="text"/>
+    <xsl:param name="current_count"/>
+    <xsl:choose>
+      <xsl:when test="starts-with($text, ' ')">
+        <xsl:call-template name="num_leading_spaces_one_line">
+          <xsl:with-param name="text" select="substring($text, 2)"/>
+          <xsl:with-param name="current_count" select="$current_count + 1"/>
+        </xsl:call-template>
+      </xsl:when>
+      <xsl:otherwise>
+        <xsl:value-of select="$current_count"/>
+      </xsl:otherwise>
+    </xsl:choose>
+  </xsl:template>
+
+  <!-- Given a block of text, each line terminated by \n, evaluates to
+       the indentation-level of that text; that is, the largest number
+       n such that every non-blank line starts with at least n spaces. -->
+  <xsl:template name="num_leading_spaces">
+    <xsl:param name="text"/>
+    <xsl:param name="max_so_far"/>
+    <!-- TODO(csilvers): deal with case text doesn't end in a newline -->
+    <xsl:variable name="line" select="substring-before($text, '&#xA;')"/>
+    <xsl:variable name="rest" select="substring-after($text, '&#xA;')"/>
+    <xsl:variable name="num_spaces_this_line">
+      <xsl:choose>
+        <xsl:when test="$line=''">
+           <xsl:value-of select="$max_so_far"/>
+        </xsl:when>
+        <xsl:otherwise>
+          <xsl:call-template name="num_leading_spaces_one_line">
+            <xsl:with-param name="text" select="$line"/>
+            <xsl:with-param name="current_count" select="0"/>
+          </xsl:call-template>
+        </xsl:otherwise>
+      </xsl:choose>
+    </xsl:variable>
+    <xsl:variable name="new_max_so_far">
+       <xsl:choose>
+         <xsl:when test="$num_spaces_this_line &lt; $max_so_far">
+           <xsl:value-of select="$num_spaces_this_line"/>
+         </xsl:when>
+         <xsl:otherwise>
+           <xsl:value-of select="$max_so_far"/>
+         </xsl:otherwise>
+       </xsl:choose>
+    </xsl:variable>
+    <!-- now check if we're on the last line, and if not, recurse -->
+    <xsl:if test="$rest=''">
+      <xsl:value-of select="$new_max_so_far"/>
+    </xsl:if>
+    <xsl:if test="not($rest='')">
+      <xsl:call-template name="num_leading_spaces">
+        <xsl:with-param name="text" select="$rest"/>
+        <xsl:with-param name="max_so_far" select="$new_max_so_far"/>
+      </xsl:call-template>
+    </xsl:if>
+  </xsl:template>
+
+  <!-- Given text, determine the starting position of code.
+       This similar to num_leading_spaces_one_line but treats "Yes:" and "No:" 
+       as spaces. Also, if there is no code on the first line, it searches 
+       subsequent lines until a non-empty line is found.
+       Used to find the start of code in snippets like:
+       Yes: if(foo):
+       No : if(foo):
+       As well as:
+       Yes:
+         if (foo):
+  -->
+  <xsl:template name="code_start_index">
+    <xsl:param name="text"/>
+    <xsl:param name="current_count"/>
+    <xsl:choose>
+      <xsl:when test="starts-with($text, ' ')">
+        <xsl:call-template name="code_start_index">
+          <xsl:with-param name="text" select="substring($text, 2)"/>
+          <xsl:with-param name="current_count" select="$current_count + 1"/>
+        </xsl:call-template>
+      </xsl:when>
+      <xsl:when test="starts-with($text, 'Yes:')">
+        <xsl:call-template name="code_start_index">
+          <xsl:with-param name="text" select="substring($text, 5)"/>
+          <xsl:with-param name="current_count" select="$current_count + 4"/>
+        </xsl:call-template>
+      </xsl:when>
+      <xsl:when test="starts-with($text, 'No:')">
+        <xsl:call-template name="code_start_index">
+          <xsl:with-param name="text" select="substring($text, 4)"/>
+          <xsl:with-param name="current_count" select="$current_count + 3"/>
+        </xsl:call-template>
+      </xsl:when>
+      <!-- This is only reached if the first line is entirely whitespace or 
+           contains nothing but "Yes:" or "No:"-->
+      <xsl:when test="starts-with($text, '&#xA;')">
+        <xsl:call-template name="code_start_index">
+          <xsl:with-param name="text" select="substring($text, 2)"/>
+          <xsl:with-param name="current_count" select="0"/>
+        </xsl:call-template>
+      </xsl:when>
+      <xsl:otherwise>
+        <xsl:value-of select="$current_count"/>
+      </xsl:otherwise>
+    </xsl:choose>
+  </xsl:template>
+
+  <!-- Helper for ends_with_colon. Determine whether the given line is nothing
+       but spaces and python-style comments. -->
+  <xsl:template name="is_blank_or_comment">
+    <xsl:param name="line"/>
+    <xsl:choose>
+      <xsl:when test="$line = ''">
+        <xsl:value-of select="1"/>
+      </xsl:when>
+      <xsl:when test="starts-with($line, '&#xA;')">
+        <xsl:value-of select="1"/>
+      </xsl:when>
+      <xsl:when test="starts-with($line, '#')">
+        <xsl:value-of select="1"/>
+      </xsl:when>
+      <xsl:when test="starts-with($line, ' ')">
+        <xsl:call-template name="is_blank_or_comment">
+          <xsl:with-param name="line" select="substring($line, 2)"/>
+        </xsl:call-template>
+      </xsl:when>
+      <xsl:otherwise>
+        <xsl:value-of select="0"/>
+      </xsl:otherwise>
+    </xsl:choose>
+  </xsl:template>
+
+  <!-- Determine whether the given line ends with a colon. Note that Python
+       style comments are ignored so the following lines return True:
+       - def foo():
+       - def foo():  # Bar
+       - if(foo):
+
+       But some code may confuse this function. For example the following are
+       also consider to "end_with_colon" even though they don't for Python
+       - foo(":  #")
+       - foo() # No need for :
+  -->
+  <xsl:template name="ends_with_colon">
+    <xsl:param name="line"/>
+    <xsl:param name="found_colon"/>
+    <xsl:choose>
+      <xsl:when test="$line = ''">
+        <xsl:value-of select="$found_colon"/>
+      </xsl:when>
+      <xsl:when test="starts-with($line, '&#xA;')">
+        <xsl:value-of select="$found_colon"/>
+      </xsl:when>
+      <xsl:when test="starts-with($line, ' ')">
+        <xsl:call-template name="ends_with_colon">
+          <xsl:with-param name="line" select="substring($line, 2)"/>
+          <xsl:with-param name="found_colon" select="$found_colon"/>
+        </xsl:call-template>
+      </xsl:when>
+      <xsl:when test="starts-with($line, ':')">
+        <xsl:variable name="rest_is_comment">
+          <xsl:call-template name="is_blank_or_comment">
+            <xsl:with-param name="line" select="substring($line, 2)"/>
+          </xsl:call-template>
+        </xsl:variable>
+        <xsl:choose>
+          <xsl:when test="$rest_is_comment = '1'">
+            <xsl:value-of select="1"/>
+          </xsl:when>
+          <xsl:otherwise>
+            <xsl:call-template name="ends_with_colon">
+              <xsl:with-param name="line" select="substring($line, 2)"/>
+              <xsl:with-param name="found_colon" select="0"/>
+            </xsl:call-template>
+          </xsl:otherwise>
+        </xsl:choose>
+      </xsl:when>
+      <xsl:otherwise>
+        <xsl:call-template name="ends_with_colon">
+          <xsl:with-param name="line" select="substring($line, 2)"/>
+          <xsl:with-param name="found_colon" select="0"/>
+        </xsl:call-template>
+      </xsl:otherwise>
+    </xsl:choose>
+  </xsl:template>
+
+  <!-- Prints one line of python code with proper indent and calls itself
+       recursively for the rest of the text.
+       This template uses "a", "b", "c" and "d" to refer to four key column
+       numbers. They are:
+       - a: the indentation common to all lines in a code snippet. This is
+            stripped out to allow for cleaner code in the xml.
+       - b: the indentation of the most out-dented line of code. This is
+            different from "a" when code is labelled with "Yes:" or "No:"
+       - c: the indentation of the current python block, in other words, the
+            indentation of the first line of this block, which is the
+            indentation of the last line we saw that ended with a colon.
+       - d: the "total" indentation of the line, ignorng possible "Yes:" or
+            "No:" text on the line.
+
+       For example, for the last line of the following code snippet, the
+       positions of a, b, c and d are indicated below:
+           Yes: def Foo():
+                  if bar():
+                    a += 1
+                    baz()
+           a    b c d
+
+       The algorithm is:
+       1) Split the text into first line and the rest. Note that the
+          substring-before function is supposed to handle the case where the
+          character is not present in the string but does not so we
+          automatically ignore the last line of the snippet which is always
+          empty (the closing snippet tag). This is consistent with the
+          behavior or print_without_leading_chars.
+       2) If the current is empty (only whitespace), print newline and call
+          itself recursively on the rest of the text with the rest of the
+          parameters unchanged.
+       3) Otherwise, measure "d"
+       4) Measure "c" by taking:
+          - the value of "d" if the previous line ended with a colon or the
+            current line is outdented compare to the previous line
+          - the indent of the previous line otherwise
+       5) Print line[a:c] (Note that we ignore line[0:a])
+       6) Print line[b:c] in an external span (in order to double the block
+          indent in external code).
+       7) Print line[c:<end>] with function names processed to produce both 
+          internal and external names.
+       8) If there are more lines, recurse.
+  -->
+  <xsl:template name="print_python_line_recursively">
+    <xsl:param name="text"/>
+    <xsl:param name="a"/>
+    <xsl:param name="b"/>
+    <xsl:param name="previous_indent"/>
+    <xsl:param name="previous_ends_with_colon"/>
+    <xsl:param name="is_first_line"/>
+    <xsl:variable name="line" select="substring-before($text, '&#xA;')"/>
+    <xsl:variable name="rest" select="substring-after($text, '&#xA;')"/>
+    <xsl:choose>
+      <xsl:when test="substring($line, $b) = '' and not($rest = '')">
+        <xsl:if test="not($is_first_line = '1')">
+          <xsl:text>&#xA;</xsl:text>
+        </xsl:if>
+        <xsl:call-template name="print_python_line_recursively">
+          <xsl:with-param name="text" select="$rest"/>
+          <xsl:with-param name="a" select="$a"/>
+          <xsl:with-param name="b" select="$b"/>
+          <xsl:with-param name="previous_indent" select="$previous_indent"/>
+          <xsl:with-param name="previous_ends_with_colon"
+                          select="$previous_ends_with_colon"/>
+          <xsl:with-param name="is_first_line" select="0"/>
+        </xsl:call-template>
+      </xsl:when>
+      <xsl:otherwise>
+        <xsl:variable name="indent_after_b">
+          <xsl:call-template name="num_leading_spaces_one_line">
+            <xsl:with-param name="text" select="substring($line, $b + 1)"/>
+            <xsl:with-param name="current_count" select="0"/>
+          </xsl:call-template>
+        </xsl:variable>
+        <xsl:variable name="d" select="$b + $indent_after_b"/>
+        <xsl:variable name="c">
+           <xsl:choose>
+             <xsl:when test="$previous_ends_with_colon = '1' or
+                             $previous_indent > $d">
+               <xsl:value-of select="$d"/>
+             </xsl:when>
+             <xsl:otherwise>
+               <xsl:value-of select="$previous_indent"/>
+             </xsl:otherwise>
+           </xsl:choose>
+        </xsl:variable>
+
+        <xsl:value-of select="substring($line, $a + 1, $c - $a)"/>
+        <span class="external">
+           <xsl:value-of select="substring($line, $b + 1, $c - $b)"/>
+        </span>
+        <xsl:call-template name="munge_function_names_in_text">
+          <xsl:with-param name="stripped_line"
+             select="substring($line, $c + 1)"/>
+        </xsl:call-template>
+        <xsl:if test="not(substring($rest, $a) = '')">
+          <xsl:text>&#xA;</xsl:text>
+          <xsl:call-template name="print_python_line_recursively">
+            <xsl:with-param name="text" select="$rest"/>
+            <xsl:with-param name="a" select="$a"/>
+            <xsl:with-param name="b" select="$b"/>
+            <xsl:with-param name="previous_indent" select="$c"/>
+            <xsl:with-param name="previous_ends_with_colon">
+              <xsl:call-template name="ends_with_colon">
+                <xsl:with-param name="line" select="$line"/>
+                <xsl:with-param name="found_colon" select="0"/>
+              </xsl:call-template>
+            </xsl:with-param>
+            <xsl:with-param name="is_first_line" select="0"/>
+          </xsl:call-template>
+        </xsl:if>
+      </xsl:otherwise>
+    </xsl:choose>
+  </xsl:template>
+
+  <!-- Print python code with internal and external styles.
+       In order to conform with PEP-8 externally, we identify 2-space indents
+       and an external-only 4-space indent.
+       Function names that are marked with $$FunctionName/$$ have an external
+       lower_with_underscore version added. -->
+  <xsl:template name="print_python_code">
+    <xsl:param name="text"/>
+
+    <xsl:variable name="a">
+       <xsl:call-template name="num_leading_spaces">
+         <xsl:with-param name="text" select="."/>
+         <xsl:with-param name="max_so_far" select="1000"/>
+       </xsl:call-template>
+    </xsl:variable>
+
+    <xsl:variable name="b">
+      <xsl:call-template name="code_start_index">
+        <xsl:with-param name="text" select="$text"/>
+        <xsl:with-param name="current_count" select="0"/>
+      </xsl:call-template>
+    </xsl:variable>
+
+    <xsl:call-template name="print_python_line_recursively">
+      <xsl:with-param name="text" select="$text"/>
+      <xsl:with-param name="a" select="$a"/>
+      <xsl:with-param name="b" select="$b"/>
+      <xsl:with-param name="previous_indent" select="$b"/>
+      <xsl:with-param name="previous_ends_with_colon" select="0"/>
+      <xsl:with-param name="is_first_line" select="1"/> 
+    </xsl:call-template>
+  </xsl:template>
+
+  <!-- Given a block of text, each line terminated by \n, and a number n,
+       emits the text with the first n characters of each line
+       deleted.  If strip==1, then we omit blank lines at the beginning
+       and end of the text (but not the middle!) -->
+  <!-- TODO(csilvers): deal well with leading tabs (treat as 8 spaces?) -->
+  <xsl:template name="print_without_leading_chars">
+    <xsl:param name="text"/>
+    <xsl:param name="trim_count"/>
+    <xsl:param name="strip"/>
+    <xsl:param name="is_firstline"/>
+    <!-- TODO(csilvers): deal with case text doesn't end in a newline -->
+    <xsl:variable name="line" select="substring-before($text, '&#xA;')"/>
+    <xsl:variable name="rest" select="substring-after($text, '&#xA;')"/>
+    <xsl:variable name="stripped_line" select="substring($line, $trim_count+1)"/>
+    <xsl:choose>
+      <!-- $line (or $rest) is considered empty if we'd trim the entire line -->
+      <xsl:when test="($strip = '1') and ($is_firstline = '1') and
+                      (string-length($line) &lt;= $trim_count)">
+      </xsl:when>
+      <xsl:when test="($strip = '1') and
+                      (string-length($rest) &lt;= $trim_count)">
+        <xsl:value-of select="$stripped_line"/>
+      </xsl:when>
+      <xsl:otherwise>
+        <xsl:value-of select="$stripped_line"/>
+        <xsl:text>&#xA;</xsl:text>
+      </xsl:otherwise>
+    </xsl:choose>
+    <xsl:if test="not($rest='')">
+      <xsl:call-template name="print_without_leading_chars">
+        <xsl:with-param name="text" select="$rest"/>
+        <xsl:with-param name="trim_count" select="$trim_count"/>
+        <xsl:with-param name="strip" select="$strip"/>
+        <xsl:with-param name="is_firstline" select="0"/>
+      </xsl:call-template>
+    </xsl:if>
+  </xsl:template>
+
+  <!-- Given a line of code, find function names that are marked with $$ /$$ and
+       print out the line with the internal and external versions of the
+       function names.-->
+  <xsl:template name="munge_function_names_in_text">
+    <xsl:param name="stripped_line"/>
+    <xsl:choose>
+      <xsl:when test="contains($stripped_line, '$$')">
+        <xsl:value-of select="substring-before($stripped_line, '$$')"/>
+        <xsl:call-template name="print_function_name">
+          <xsl:with-param name="text" select="substring-after(substring-before($stripped_line, '/$$'), '$$')"/>
+        </xsl:call-template>
+        <xsl:call-template name="munge_function_names_in_text">
+          <xsl:with-param name="stripped_line" select="substring-after($stripped_line, '/$$')"/>
+        </xsl:call-template>
+      </xsl:when>
+      <xsl:otherwise>
+        <xsl:value-of select="$stripped_line"/>
+     </xsl:otherwise>
+   </xsl:choose>
+  </xsl:template>
+
+  <!-- Given a function name, print out both the internal and external version
+       of the function name in their respective spans.-->
+  <xsl:template name="print_function_name">
+    <xsl:param name="text"/>
+      <xsl:call-template name="convert_camel_case_to_lowercase_with_under">
+        <xsl:with-param name="text" select="$text"/>
+      </xsl:call-template>
+  </xsl:template>
+
+  <!-- Given a single word of text convert it from CamelCase to
+       lower_with_under.
+       This means replacing each uppercase character with _ followed by the
+       lowercase version except for the first character which is replaced 
+       without adding the _.-->
+  <xsl:template name="convert_camel_case_to_lowercase_with_under">
+    <xsl:param name="text"/>
+    <xsl:param name="is_recursive_call"/>
+    <xsl:variable name="first_char" select="substring($text, 1, 1)"/>
+    <xsl:variable name="rest" select="substring($text, 2)"/>
+    <xsl:choose>
+      <xsl:when test="contains('ABCDEFGHIJKLMNOPQRSTUVWXYZ', $first_char)">
+        <xsl:if test="$is_recursive_call='1'">
+           <xsl:text>_</xsl:text>
+        </xsl:if>
+        <xsl:value-of select="translate($first_char, 'ABCDEFGHIJKLMNOPQRSTUVWXYZ', 'abcdefghijklmnopqrstuvwxyz')"/>
+      </xsl:when>
+      <xsl:otherwise>
+        <xsl:value-of select="$first_char" />
+      </xsl:otherwise>
+    </xsl:choose>
+    <xsl:if test="not($rest='')">
+      <xsl:call-template name="convert_camel_case_to_lowercase_with_under">
+        <xsl:with-param name="text" select="$rest"/>
+        <xsl:with-param name="is_recursive_call" select="1"/>
+      </xsl:call-template>
+    </xsl:if>
+  </xsl:template>
+</xsl:stylesheet>
+
diff --git a/wpilibc/Athena/include/ADXL345_I2C.h b/wpilibc/Athena/include/ADXL345_I2C.h
index e55e007..e0327f7 100644
--- a/wpilibc/Athena/include/ADXL345_I2C.h
+++ b/wpilibc/Athena/include/ADXL345_I2C.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "interfaces/Accelerometer.h"
@@ -51,7 +52,7 @@
   };
 
  public:
-  explicit ADXL345_I2C(Port port, Range range = kRange_2G);
+  explicit ADXL345_I2C(Port port, Range range = kRange_2G, int deviceAddress = kAddress);
   virtual ~ADXL345_I2C() = default;
 
   ADXL345_I2C(const ADXL345_I2C&) = delete;
diff --git a/wpilibc/Athena/include/ADXL345_SPI.h b/wpilibc/Athena/include/ADXL345_SPI.h
index 1310133..ceb28cd 100644
--- a/wpilibc/Athena/include/ADXL345_SPI.h
+++ b/wpilibc/Athena/include/ADXL345_SPI.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "interfaces/Accelerometer.h"
diff --git a/wpilibc/Athena/include/ADXL362.h b/wpilibc/Athena/include/ADXL362.h
index ea47686..d4c2e0b 100644
--- a/wpilibc/Athena/include/ADXL362.h
+++ b/wpilibc/Athena/include/ADXL362.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "interfaces/Accelerometer.h"
diff --git a/wpilibc/Athena/include/ADXRS450_Gyro.h b/wpilibc/Athena/include/ADXRS450_Gyro.h
index 42a7a59..7717f57 100644
--- a/wpilibc/Athena/include/ADXRS450_Gyro.h
+++ b/wpilibc/Athena/include/ADXRS450_Gyro.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2015. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2015-2016. 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 "GyroBase.h"
@@ -35,8 +36,6 @@
   void Reset() override;
   void Calibrate() override;
 
-  std::string GetSmartDashboardType() const override;
-
  private:
   SPI m_spi;
 
diff --git a/wpilibc/Athena/include/AnalogAccelerometer.h b/wpilibc/Athena/include/AnalogAccelerometer.h
index ad6d6dd..86f7019 100644
--- a/wpilibc/Athena/include/AnalogAccelerometer.h
+++ b/wpilibc/Athena/include/AnalogAccelerometer.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "AnalogInput.h"
diff --git a/wpilibc/Athena/include/AnalogGyro.h b/wpilibc/Athena/include/AnalogGyro.h
index 4ce0ccb..acb5b0f 100644
--- a/wpilibc/Athena/include/AnalogGyro.h
+++ b/wpilibc/Athena/include/AnalogGyro.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "GyroBase.h"
@@ -53,8 +54,6 @@
   virtual void InitGyro();
   void Calibrate() override;
 
-  std::string GetSmartDashboardType() const override;
-
  protected:
   std::shared_ptr<AnalogInput> m_analog;
 
diff --git a/wpilibc/Athena/include/AnalogInput.h b/wpilibc/Athena/include/AnalogInput.h
index d47d1f2..6217e2d 100644
--- a/wpilibc/Athena/include/AnalogInput.h
+++ b/wpilibc/Athena/include/AnalogInput.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "HAL/HAL.hpp"
diff --git a/wpilibc/Athena/include/AnalogOutput.h b/wpilibc/Athena/include/AnalogOutput.h
index c30b5c7..d7bd30e 100644
--- a/wpilibc/Athena/include/AnalogOutput.h
+++ b/wpilibc/Athena/include/AnalogOutput.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibc/Athena/include/AnalogPotentiometer.h b/wpilibc/Athena/include/AnalogPotentiometer.h
index 7b7b12a..3c6daa5 100644
--- a/wpilibc/Athena/include/AnalogPotentiometer.h
+++ b/wpilibc/Athena/include/AnalogPotentiometer.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "interfaces/Potentiometer.h"
 #include "LiveWindow/LiveWindowSendable.h"
diff --git a/wpilibc/Athena/include/AnalogTrigger.h b/wpilibc/Athena/include/AnalogTrigger.h
index 7fdd202..811cc07 100644
--- a/wpilibc/Athena/include/AnalogTrigger.h
+++ b/wpilibc/Athena/include/AnalogTrigger.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "HAL/HAL.hpp"
diff --git a/wpilibc/Athena/include/AnalogTriggerOutput.h b/wpilibc/Athena/include/AnalogTriggerOutput.h
index 27ad3b8..976d30c 100644
--- a/wpilibc/Athena/include/AnalogTriggerOutput.h
+++ b/wpilibc/Athena/include/AnalogTriggerOutput.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "DigitalSource.h"
diff --git a/wpilibc/Athena/include/BuiltInAccelerometer.h b/wpilibc/Athena/include/BuiltInAccelerometer.h
index b6b5f8e..d201b61 100644
--- a/wpilibc/Athena/include/BuiltInAccelerometer.h
+++ b/wpilibc/Athena/include/BuiltInAccelerometer.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "interfaces/Accelerometer.h"
diff --git a/wpilibc/Athena/include/CANJaguar.h b/wpilibc/Athena/include/CANJaguar.h
index 5d05d47..c456e2a 100644
--- a/wpilibc/Athena/include/CANJaguar.h
+++ b/wpilibc/Athena/include/CANJaguar.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2009. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2009-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "ErrorBase.h"
@@ -228,6 +230,7 @@
   mutable std::atomic<bool> m_receivedStatusMessage2{false};
 
   bool m_controlEnabled = false;
+  bool m_stopped = false;
 
   void verify();
 
diff --git a/wpilibc/Athena/include/CANSpeedController.h b/wpilibc/Athena/include/CANSpeedController.h
index 73ed379..5d76026 100644
--- a/wpilibc/Athena/include/CANSpeedController.h
+++ b/wpilibc/Athena/include/CANSpeedController.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SpeedController.h"
@@ -20,23 +22,11 @@
     kSpeed = 2,
     kPosition = 3,
     kVoltage = 4,
-    kFollower = 5  // Not supported in Jaguar.
+    kFollower = 5, // Not supported in Jaguar.
+    kMotionProfile = 6, // Not supported in Jaguar.
   };
 
   // Helper function for the ControlMode enum
-  std::string GetModeName(ControlMode mode) {
-    switch(mode) {
-      case kPercentVbus: return "PercentVbus";
-      case kCurrent: return "Current";
-      case kSpeed: return "Speed";
-      case kPosition: return "Position";
-      case kVoltage: return "Voltage";
-      case kFollower: return "Follower";
-      default: return "[unknown control mode]";
-    }
-  }
-
-  // Helper function for the ControlMode enum
   virtual bool IsModePID(ControlMode mode) const = 0;
 
   enum Faults {
@@ -75,6 +65,7 @@
 
   virtual float Get() const = 0;
   virtual void Set(float value, uint8_t syncGroup = 0) = 0;
+  virtual void StopMotor() = 0;
   virtual void Disable() = 0;
   virtual void SetP(double p) = 0;
   virtual void SetI(double i) = 0;
diff --git a/wpilibc/Athena/include/CANTalon.h b/wpilibc/Athena/include/CANTalon.h
index 15ebbe2..8ea9ae1 100644
--- a/wpilibc/Athena/include/CANTalon.h
+++ b/wpilibc/Athena/include/CANTalon.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SafePWM.h"
@@ -42,9 +44,9 @@
    * Depending on the sensor type, Talon can determine if sensor is plugged in ot not.
    */
   enum FeedbackDeviceStatus {
-	FeedbackStatusUnknown = 0, 		//!< Sensor status could not be determined.  Not all sensors can do this.
-	FeedbackStatusPresent = 1, 		//!< Sensor is present and working okay.
-	FeedbackStatusNotPresent = 2, 	//!< Sensor is not present, not plugged in, not powered, etc...
+    FeedbackStatusUnknown = 0,      //!< Sensor status could not be determined.  Not all sensors can do this.
+    FeedbackStatusPresent = 1,      //!< Sensor is present and working okay.
+    FeedbackStatusNotPresent = 2,   //!< Sensor is not present, not plugged in, not powered, etc...
   };
   enum StatusFrameRate {
     StatusFrameRateGeneral = 0,
@@ -53,6 +55,151 @@
     StatusFrameRateAnalogTempVbat = 3,
     StatusFrameRatePulseWidthMeas = 4,
   };
+  /**
+   * Enumerated types for Motion Control Set Values.
+   * When in Motion Profile control mode, these constants are paseed
+   * into set() to manipulate the motion profile executer.
+   * When changing modes, be sure to read the value back using getMotionProfileStatus()
+   * to ensure changes in output take effect before performing buffering actions.
+   * Disable will signal Talon to put motor output into neutral drive.
+   *   Talon will stop processing motion profile points.  This means the buffer is
+   *   effectively disconnected from the executer, allowing the robot to gracefully
+   *   clear and push new traj points.  isUnderrun will get cleared.
+   *   The active trajectory is also cleared.
+   * Enable will signal Talon to pop a trajectory point from it's buffer and process it.
+   *   If the active trajectory is empty, Talon will shift in the next point.
+   *   If the active traj is empty, and so is the buffer, the motor drive is neutral and
+   *   isUnderrun is set.  When active traj times out, and buffer has at least one point,
+   *   Talon shifts in next one, and isUnderrun is cleared.  When active traj times out,
+   *   and buffer is empty, Talon keeps processing active traj and sets IsUnderrun.
+   * Hold will signal Talon keep processing the active trajectory indefinitely.
+   *   If the active traj is cleared, Talon will neutral motor drive.  Otherwise
+   *    Talon will keep processing the active traj but it will not shift in
+   *    points from the buffer.  This means the buffer is  effectively disconnected
+   *    from the executer, allowing the robot to gracefully clear and push
+   *    new traj points.
+   *    isUnderrun is set if active traj is empty, otherwise it is cleared.
+   *    isLast signal is also cleared.
+   *
+   * Typical workflow:
+   *   set(Disable),
+   *   Confirm Disable takes effect,
+   *   clear buffer and push buffer points,
+   *   set(Enable) when enough points have been pushed to ensure no underruns,
+   *   wait for MP to finish or decide abort,
+   *   If MP finished gracefully set(Hold) to hold position servo and disconnect buffer,
+   *   If MP is being aborted set(Disable) to neutral the motor and disconnect buffer,
+   *   Confirm mode takes effect,
+   *   clear buffer and push buffer points, and rinse-repeat.
+   */
+  enum SetValueMotionProfile {
+    SetValueMotionProfileDisable = 0,
+    SetValueMotionProfileEnable = 1,
+    SetValueMotionProfileHold = 2,
+  };
+  /**
+   * Motion Profile Trajectory Point
+   * This is simply a data transer object.
+   */
+  struct TrajectoryPoint {
+    double position; //!< The position to servo to.
+    double velocity; //!< The velocity to feed-forward.
+    /**
+     * Time in milliseconds to process this point.
+     * Value should be between 1ms and 255ms.  If value is zero
+     * then Talon will default to 1ms.  If value exceeds 255ms API will cap it.
+     */
+    unsigned int timeDurMs;
+    /**
+     * Which slot to get PIDF gains.
+     * PID is used for position servo.
+     * F is used as the Kv constant for velocity feed-forward.
+     * Typically this is hardcoded to the a particular slot, but you are free
+     * gain schedule if need be.
+     */
+    unsigned int profileSlotSelect;
+    /**
+     * Set to true to only perform the velocity feed-forward and not perform
+     * position servo.  This is useful when learning how the position servo
+     * changes the motor response.  The same could be accomplish by clearing the
+     * PID gains, however this is synchronous the streaming, and doesn't require restoing
+     * gains when finished.
+     *
+     * Additionaly setting this basically gives you direct control of the motor output
+     * since motor output = targetVelocity X Kv, where Kv is our Fgain.
+     * This means you can also scheduling straight-throttle curves without relying on
+     * a sensor.
+     */
+    bool velocityOnly;
+    /**
+     * Set to true to signal Talon that this is the final point, so do not
+     * attempt to pop another trajectory point from out of the Talon buffer.
+     * Instead continue processing this way point.  Typically the velocity
+     * member variable should be zero so that the motor doesn't spin indefinitely.
+     */
+    bool isLastPoint;
+   /**
+     * Set to true to signal Talon to zero the selected sensor.
+     * When generating MPs, one simple method is to make the first target position zero,
+     * and the final target position the target distance from the current position.
+     * Then when you fire the MP, the current position gets set to zero.
+     * If this is the intent, you can set zeroPos on the first trajectory point.
+     *
+     * Otherwise you can leave this false for all points, and offset the positions
+     * of all trajectory points so they are correct.
+     */
+    bool zeroPos;
+  };
+  /**
+   * Motion Profile Status
+   * This is simply a data transer object.
+   */
+  struct MotionProfileStatus {
+    /**
+     * The available empty slots in the trajectory buffer.
+     *
+     * The robot API holds a "top buffer" of trajectory points, so your applicaion
+     * can dump several points at once.  The API will then stream them into the Talon's
+     * low-level buffer, allowing the Talon to act on them.
+     */
+    unsigned int topBufferRem;
+    /**
+     * The number of points in the top trajectory buffer.
+     */
+    unsigned int topBufferCnt;
+    /**
+     * The number of points in the low level Talon buffer.
+     */
+    unsigned int btmBufferCnt;
+    /**
+     * Set if isUnderrun ever gets set.
+     * Only is cleared by clearMotionProfileHasUnderrun() to ensure
+     * robot logic can react or instrument it.
+     * @see clearMotionProfileHasUnderrun()
+     */
+    bool hasUnderrun;
+    /**
+     * This is set if Talon needs to shift a point from its buffer into
+     * the active trajectory point however the buffer is empty. This gets cleared
+     * automatically when is resolved.
+     */
+    bool isUnderrun;
+    /**
+     * True if the active trajectory point has not empty, false otherwise.
+     * The members in activePoint are only valid if this signal is set.
+     */
+    bool activePointValid;
+    /**
+     * The number of points in the low level Talon buffer.
+     */
+    TrajectoryPoint activePoint;
+    /**
+     * The current output mode of the motion profile executer (disabled, enabled, or hold).
+     * When changing the set() value in MP mode, it's important to check this signal to
+     * confirm the change takes effect before interacting with the top buffer.
+     */
+    SetValueMotionProfile outputEnable;
+  };
   explicit CANTalon(int deviceNumber);
   explicit CANTalon(int deviceNumber, int controlPeriodMs);
   DEFAULT_MOVE_CONSTRUCTOR(CANTalon);
@@ -139,6 +286,9 @@
   virtual void ConfigLimitMode(LimitMode mode) override;
   virtual void ConfigForwardLimit(double forwardLimitPosition) override;
   virtual void ConfigReverseLimit(double reverseLimitPosition) override;
+  void ConfigLimitSwitchOverrides(bool bForwardLimitSwitchEn, bool bReverseLimitSwitchEn);
+  void ConfigForwardSoftLimitEnable(bool bForwardSoftLimitEn);
+  void ConfigReverseSoftLimitEnable(bool bReverseSoftLimitEn);
   /**
    * Change the fwd limit switch setting to normally open or closed.
    * Talon will disable momentarilly if the Talon's current setting
@@ -167,9 +317,9 @@
   /**
    * Enables Talon SRX to automatically zero the Sensor Position whenever an
    * edge is detected on the index signal.
-   * @param enable 		boolean input, pass true to enable feature or false to disable.
-   * @param risingEdge 	boolean input, pass true to clear the position on rising edge,
-   *					pass false to clear the position on falling edge.
+   * @param enable      boolean input, pass true to enable feature or false to disable.
+   * @param risingEdge  boolean input, pass true to clear the position on rising edge,
+   *                    pass false to clear the position on falling edge.
    */
   void EnableZeroSensorPositionOnIndex(bool enable, bool risingEdge);
   void ConfigSetParameter(uint32_t paramEnum, double value);
@@ -193,6 +343,69 @@
   bool IsEnabled() const override;
   double GetSetpoint() const override;
 
+
+  /**
+   * Calling application can opt to speed up the handshaking between the robot API and the Talon to increase the
+   * download rate of the Talon's Motion Profile.  Ideally the period should be no more than half the period
+   * of a trajectory point.
+   */
+  void ChangeMotionControlFramePeriod(int periodMs);
+
+  /**
+   * Clear the buffered motion profile in both Talon RAM (bottom), and in the API (top).
+   * Be sure to check GetMotionProfileStatus() to know when the buffer is actually cleared.
+   */
+  void ClearMotionProfileTrajectories();
+
+  /**
+   * Retrieve just the buffer count for the api-level (top) buffer.
+   * This routine performs no CAN or data structure lookups, so its fast and ideal
+   * if caller needs to quickly poll the progress of trajectory points being emptied
+   * into Talon's RAM. Otherwise just use GetMotionProfileStatus.
+   * @return number of trajectory points in the top buffer.
+   */
+  int GetMotionProfileTopLevelBufferCount();
+
+  /**
+   * Push another trajectory point into the top level buffer (which is emptied into
+   * the Talon's bottom buffer as room allows).
+   * @param trajPt the trajectory point to insert into buffer.
+   * @return true  if trajectory point push ok. CTR_BufferFull if buffer is full
+   * due to kMotionProfileTopBufferCapacity.
+   */
+  bool PushMotionProfileTrajectory(const TrajectoryPoint & trajPt);
+
+  /**
+   * @return true if api-level (top) buffer is full.
+   */
+  bool IsMotionProfileTopLevelBufferFull();
+
+  /**
+   * This must be called periodically to funnel the trajectory points from the API's top level buffer to
+   * the Talon's bottom level buffer.  Recommendation is to call this twice as fast as the executation rate of the motion profile.
+   * So if MP is running with 20ms trajectory points, try calling this routine every 10ms.  All motion profile functions are thread-safe
+   * through the use of a mutex, so there is no harm in having the caller utilize threading.
+   */
+  void ProcessMotionProfileBuffer();
+
+  /**
+   * Retrieve all status information.
+   * Since this all comes from one CAN frame, its ideal to have one routine to retrieve the frame once and decode everything.
+   * @param [out] motionProfileStatus contains all progress information on the currently running MP.
+   */
+  void GetMotionProfileStatus(MotionProfileStatus & motionProfileStatus);
+
+  /**
+   * Clear the hasUnderrun flag in Talon's Motion Profile Executer when MPE is ready for another point,
+   * but the low level buffer is empty.
+   *
+   * Once the Motion Profile Executer sets the hasUnderrun flag, it stays set until
+   * Robot Application clears it with this routine, which ensures Robot Application
+   * gets a chance to instrument or react.  Caller could also check the isUnderrun flag
+   * which automatically clears when fault condition is removed.
+   */
+  void ClearMotionProfileHasUnderrun();
+
   // LiveWindow stuff.
   void ValueChanged(ITable* source, llvm::StringRef key,
                     std::shared_ptr<nt::Value> value, bool isNew) override;
@@ -216,6 +429,7 @@
     kPositionMode = 1,
     kSpeedMode = 2,
     kCurrentMode = 3,
+    kMotionProfileMode = 6,
     kDisabled = 15
   };
 
@@ -226,6 +440,7 @@
                   // actually test this.
 
   bool m_controlEnabled = true;
+  bool m_stopped = false;
   ControlMode m_controlMode = kPercentVbus;
   TalonControlMode m_sendMode;
 
@@ -255,10 +470,10 @@
   static const unsigned int kDelayForSolicitedSignalsUs = 4000;
   /**
    * @param devToLookup FeedbackDevice to lookup the scalar for.  Because Talon
-   * 				allows multiple sensors to be attached simultaneously, caller must
-   *				specify which sensor to lookup.
-   * @return 		The number of native Talon units per rotation of the selected sensor.
-   *				Zero if the necessary sensor information is not available.
+   *                allows multiple sensors to be attached simultaneously, caller must
+   *                specify which sensor to lookup.
+   * @return        The number of native Talon units per rotation of the selected sensor.
+   *                Zero if the necessary sensor information is not available.
    * @see ConfigEncoderCodesPerRev
    * @see ConfigPotentiometerTurns
    */
@@ -271,40 +486,40 @@
    */
   void ApplyControlMode(CANSpeedController::ControlMode mode);
   /**
-   * @param fullRotations 	double precision value representing number of rotations of selected feedback sensor.
-   *							If user has never called the config routine for the selected sensor, then the caller
-   *							is likely passing rotations in engineering units already, in which case it is returned
-   *							as is.
-   *							@see ConfigPotentiometerTurns
-   *							@see ConfigEncoderCodesPerRev
+   * @param fullRotations   double precision value representing number of rotations of selected feedback sensor.
+   *                            If user has never called the config routine for the selected sensor, then the caller
+   *                            is likely passing rotations in engineering units already, in which case it is returned
+   *                            as is.
+   *                            @see ConfigPotentiometerTurns
+   *                            @see ConfigEncoderCodesPerRev
    * @return fullRotations in native engineering units of the Talon SRX firmware.
    */
   int32_t ScaleRotationsToNativeUnits(FeedbackDevice devToLookup, double fullRotations) const;
   /**
-   * @param rpm 	double precision value representing number of rotations per minute of selected feedback sensor.
-   *							If user has never called the config routine for the selected sensor, then the caller
-   *							is likely passing rotations in engineering units already, in which case it is returned
-   *							as is.
-   *							@see ConfigPotentiometerTurns
-   *							@see ConfigEncoderCodesPerRev
+   * @param rpm     double precision value representing number of rotations per minute of selected feedback sensor.
+   *                            If user has never called the config routine for the selected sensor, then the caller
+   *                            is likely passing rotations in engineering units already, in which case it is returned
+   *                            as is.
+   *                            @see ConfigPotentiometerTurns
+   *                            @see ConfigEncoderCodesPerRev
    * @return sensor velocity in native engineering units of the Talon SRX firmware.
    */
   int32_t ScaleVelocityToNativeUnits(FeedbackDevice devToLookup, double rpm) const;
   /**
-   * @param nativePos 	integral position of the feedback sensor in native Talon SRX units.
-   *							If user has never called the config routine for the selected sensor, then the return
-   *							will be in TALON SRX units as well to match the behavior in the 2015 season.
-   *							@see ConfigPotentiometerTurns
-   *							@see ConfigEncoderCodesPerRev
+   * @param nativePos     integral position of the feedback sensor in native Talon SRX units.
+   *                            If user has never called the config routine for the selected sensor, then the return
+   *                            will be in TALON SRX units as well to match the behavior in the 2015 season.
+   *                            @see ConfigPotentiometerTurns
+   *                            @see ConfigEncoderCodesPerRev
    * @return double precision number of rotations, unless config was never performed.
    */
   double ScaleNativeUnitsToRotations(FeedbackDevice devToLookup, int32_t nativePos) const;
   /**
-   * @param nativeVel 	integral velocity of the feedback sensor in native Talon SRX units.
-   *							If user has never called the config routine for the selected sensor, then the return
-   *							will be in TALON SRX units as well to match the behavior in the 2015 season.
-   *							@see ConfigPotentiometerTurns
-   *							@see ConfigEncoderCodesPerRev
+   * @param nativeVel     integral velocity of the feedback sensor in native Talon SRX units.
+   *                            If user has never called the config routine for the selected sensor, then the return
+   *                            will be in TALON SRX units as well to match the behavior in the 2015 season.
+   *                            @see ConfigPotentiometerTurns
+   *                            @see ConfigEncoderCodesPerRev
    * @return double precision of sensor velocity in RPM, unless config was never performed.
    */
   double ScaleNativeUnitsToRpm(FeedbackDevice devToLookup, int32_t nativeVel) const;
diff --git a/wpilibc/Athena/include/CameraServer.h b/wpilibc/Athena/include/CameraServer.h
index 17ece99..bb0c314 100644
--- a/wpilibc/Athena/include/CameraServer.h
+++ b/wpilibc/Athena/include/CameraServer.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 "USBCamera.h"
diff --git a/wpilibc/Athena/include/Compressor.h b/wpilibc/Athena/include/Compressor.h
index d5962c3..0d56ef7 100644
--- a/wpilibc/Athena/include/Compressor.h
+++ b/wpilibc/Athena/include/Compressor.h
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef Compressor_H_
diff --git a/wpilibc/Athena/include/ControllerPower.h b/wpilibc/Athena/include/ControllerPower.h
index 7384e60..18367b5 100644
--- a/wpilibc/Athena/include/ControllerPower.h
+++ b/wpilibc/Athena/include/ControllerPower.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __CONTROLLER_POWER_H__
diff --git a/wpilibc/Athena/include/Counter.h b/wpilibc/Athena/include/Counter.h
index 4066de8..3cb55b5 100644
--- a/wpilibc/Athena/include/Counter.h
+++ b/wpilibc/Athena/include/Counter.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "HAL/HAL.hpp"
diff --git a/wpilibc/Athena/include/CounterBase.h b/wpilibc/Athena/include/CounterBase.h
index 68896a8..633b795 100644
--- a/wpilibc/Athena/include/CounterBase.h
+++ b/wpilibc/Athena/include/CounterBase.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include <stdint.h>
diff --git a/wpilibc/Athena/include/DigitalGlitchFilter.h b/wpilibc/Athena/include/DigitalGlitchFilter.h
index a6f9f90..0f9e676 100644
--- a/wpilibc/Athena/include/DigitalGlitchFilter.h
+++ b/wpilibc/Athena/include/DigitalGlitchFilter.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2015. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2015-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include <array>
diff --git a/wpilibc/Athena/include/DigitalInput.h b/wpilibc/Athena/include/DigitalInput.h
index 79cfcc5..96a70a0 100644
--- a/wpilibc/Athena/include/DigitalInput.h
+++ b/wpilibc/Athena/include/DigitalInput.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "DigitalSource.h"
diff --git a/wpilibc/Athena/include/DigitalOutput.h b/wpilibc/Athena/include/DigitalOutput.h
index 367fb80..e8bb514 100644
--- a/wpilibc/Athena/include/DigitalOutput.h
+++ b/wpilibc/Athena/include/DigitalOutput.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "DigitalSource.h"
diff --git a/wpilibc/Athena/include/DigitalSource.h b/wpilibc/Athena/include/DigitalSource.h
index c716715..d85102b 100644
--- a/wpilibc/Athena/include/DigitalSource.h
+++ b/wpilibc/Athena/include/DigitalSource.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "InterruptableSensorBase.h"
diff --git a/wpilibc/Athena/include/DoubleSolenoid.h b/wpilibc/Athena/include/DoubleSolenoid.h
index fd20397..9d1f033 100644
--- a/wpilibc/Athena/include/DoubleSolenoid.h
+++ b/wpilibc/Athena/include/DoubleSolenoid.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SolenoidBase.h"
diff --git a/wpilibc/Athena/include/DriverStation.h b/wpilibc/Athena/include/DriverStation.h
index 23ee095..b98c6ec 100644
--- a/wpilibc/Athena/include/DriverStation.h
+++ b/wpilibc/Athena/include/DriverStation.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SensorBase.h"
@@ -29,6 +31,10 @@
   virtual ~DriverStation();
   static DriverStation &GetInstance();
   static void ReportError(std::string error);
+  static void ReportWarning(std::string error);
+  static void ReportError(bool is_error, int32_t code, const std::string& error,
+                          const std::string& location,
+                          const std::string& stack);
 
   static const uint32_t kJoystickPorts = 6;
 
@@ -95,6 +101,7 @@
  private:
   static DriverStation *m_instance;
   void ReportJoystickUnpluggedError(std::string message);
+  void ReportJoystickUnpluggedWarning(std::string message);
   void Run();
 
   HALJoystickAxes m_joystickAxes[kJoystickPorts];
diff --git a/wpilibc/Athena/include/Encoder.h b/wpilibc/Athena/include/Encoder.h
index 76bfaf9..5c692f0 100644
--- a/wpilibc/Athena/include/Encoder.h
+++ b/wpilibc/Athena/include/Encoder.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "HAL/HAL.hpp"
diff --git a/wpilibc/Athena/include/GearTooth.h b/wpilibc/Athena/include/GearTooth.h
index 3889f9c..070f397 100644
--- a/wpilibc/Athena/include/GearTooth.h
+++ b/wpilibc/Athena/include/GearTooth.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "Counter.h"
diff --git a/wpilibc/Athena/include/I2C.h b/wpilibc/Athena/include/I2C.h
index 89041e7..3267032 100644
--- a/wpilibc/Athena/include/I2C.h
+++ b/wpilibc/Athena/include/I2C.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SensorBase.h"
diff --git a/wpilibc/Athena/include/Internal/HardwareHLReporting.h b/wpilibc/Athena/include/Internal/HardwareHLReporting.h
index a91a20d..b411ecf 100644
--- a/wpilibc/Athena/include/Internal/HardwareHLReporting.h
+++ b/wpilibc/Athena/include/Internal/HardwareHLReporting.h
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HLUsageReporting.h"
 
diff --git a/wpilibc/Athena/include/InterruptableSensorBase.h b/wpilibc/Athena/include/InterruptableSensorBase.h
index d77ae2f..708089b 100644
--- a/wpilibc/Athena/include/InterruptableSensorBase.h
+++ b/wpilibc/Athena/include/InterruptableSensorBase.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "HAL/HAL.hpp"
diff --git a/wpilibc/Athena/include/IterativeRobot.h b/wpilibc/Athena/include/IterativeRobot.h
index ccea4f8..acba235 100644
--- a/wpilibc/Athena/include/IterativeRobot.h
+++ b/wpilibc/Athena/include/IterativeRobot.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "Timer.h"
diff --git a/wpilibc/Athena/include/Jaguar.h b/wpilibc/Athena/include/Jaguar.h
index feb00c7..c129559 100644
--- a/wpilibc/Athena/include/Jaguar.h
+++ b/wpilibc/Athena/include/Jaguar.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SafePWM.h"
@@ -20,6 +21,7 @@
   virtual void Set(float value, uint8_t syncGroup = 0) override;
   virtual float Get() const override;
   virtual void Disable() override;
+  virtual void StopMotor() override;
 
   virtual void PIDWrite(float output) override;
   virtual void SetInverted(bool isInverted) override;
diff --git a/wpilibc/Athena/include/Joystick.h b/wpilibc/Athena/include/Joystick.h
index b8ea292..fdd4d7d 100644
--- a/wpilibc/Athena/include/Joystick.h
+++ b/wpilibc/Athena/include/Joystick.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef JOYSTICK_H_
diff --git a/wpilibc/Athena/include/MotorSafety.h b/wpilibc/Athena/include/MotorSafety.h
index 6963ae7..373fddf 100644
--- a/wpilibc/Athena/include/MotorSafety.h
+++ b/wpilibc/Athena/include/MotorSafety.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #define DEFAULT_SAFETY_EXPIRATION 0.1
diff --git a/wpilibc/Athena/include/MotorSafetyHelper.h b/wpilibc/Athena/include/MotorSafetyHelper.h
index bbe7658..f124605 100644
--- a/wpilibc/Athena/include/MotorSafetyHelper.h
+++ b/wpilibc/Athena/include/MotorSafetyHelper.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "ErrorBase.h"
diff --git a/wpilibc/Athena/include/Notifier.h b/wpilibc/Athena/include/Notifier.h
new file mode 100644
index 0000000..070853f
--- /dev/null
+++ b/wpilibc/Athena/include/Notifier.h
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2016. 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 <functional>
+
+#include "ErrorBase.h"
+#include "HAL/cpp/priority_mutex.h"
+
+typedef std::function<void()> TimerEventHandler;
+
+class Notifier : public ErrorBase {
+ public:
+  explicit Notifier(TimerEventHandler handler);
+
+  template <typename Callable, typename Arg, typename... Args>
+  Notifier(Callable&& f, Arg&& arg, Args&&... args)
+      : Notifier(std::bind(std::forward<Callable>(f),
+                           std::forward<Arg>(arg),
+                           std::forward<Args>(args)...)) {}
+
+  virtual ~Notifier();
+
+  Notifier(const Notifier&) = delete;
+  Notifier& operator=(const Notifier&) = delete;
+
+  void StartSingle(double delay);
+  void StartPeriodic(double period);
+  void Stop();
+
+ private:
+  // update the HAL alarm
+  void UpdateAlarm();
+  // HAL callback
+  static void Notify(uint64_t currentTimeInt, void *param);
+
+  // held while updating process information
+  priority_mutex m_processMutex;
+  // HAL handle
+  void *m_notifier;
+  // address of the handler
+  TimerEventHandler m_handler;
+  // the absolute expiration time
+  double m_expirationTime = 0;
+  // the relative time (either periodic or single)
+  double m_period = 0;
+  // true if this is a periodic event
+  bool m_periodic = false;
+
+  // held by interrupt manager task while handler call is in progress
+  priority_mutex m_handlerMutex;
+};
diff --git a/wpilibc/Athena/include/PWM.h b/wpilibc/Athena/include/PWM.h
index b7120c0..8f9976a 100644
--- a/wpilibc/Athena/include/PWM.h
+++ b/wpilibc/Athena/include/PWM.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SensorBase.h"
diff --git a/wpilibc/Athena/include/PowerDistributionPanel.h b/wpilibc/Athena/include/PowerDistributionPanel.h
index 9a1bd7c..b9769ec 100644
--- a/wpilibc/Athena/include/PowerDistributionPanel.h
+++ b/wpilibc/Athena/include/PowerDistributionPanel.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #pragma once
diff --git a/wpilibc/Athena/include/Preferences.h b/wpilibc/Athena/include/Preferences.h
index a2c3bc4..1e1beff 100644
--- a/wpilibc/Athena/include/Preferences.h
+++ b/wpilibc/Athena/include/Preferences.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "ErrorBase.h"
diff --git a/wpilibc/Athena/include/Relay.h b/wpilibc/Athena/include/Relay.h
index f582221..a9bd26a 100644
--- a/wpilibc/Athena/include/Relay.h
+++ b/wpilibc/Athena/include/Relay.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "MotorSafety.h"
diff --git a/wpilibc/Athena/include/RobotBase.h b/wpilibc/Athena/include/RobotBase.h
index 2fcd146..b6626b9 100644
--- a/wpilibc/Athena/include/RobotBase.h
+++ b/wpilibc/Athena/include/RobotBase.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "Base.h"
diff --git a/wpilibc/Athena/include/RobotDrive.h b/wpilibc/Athena/include/RobotDrive.h
index d91e80d..547d06a 100644
--- a/wpilibc/Athena/include/RobotDrive.h
+++ b/wpilibc/Athena/include/RobotDrive.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "ErrorBase.h"
diff --git a/wpilibc/Athena/include/SD540.h b/wpilibc/Athena/include/SD540.h
new file mode 100644
index 0000000..9e98678
--- /dev/null
+++ b/wpilibc/Athena/include/SD540.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2016. 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 "SafePWM.h"
+#include "SpeedController.h"
+#include "PIDOutput.h"
+
+/**
+ * Mindsensors SD540 Speed Controller
+ */
+class SD540 : public SafePWM, public SpeedController {
+ public:
+  explicit SD540(uint32_t channel);
+  virtual ~SD540() = default;
+  virtual void Set(float value, uint8_t syncGroup = 0) override;
+  virtual float Get() const override;
+  virtual void Disable() override;
+  virtual void StopMotor() override;
+
+  virtual void PIDWrite(float output) override;
+
+  virtual void SetInverted(bool isInverted) override;
+  virtual bool GetInverted() const override;
+
+ private:
+  bool m_isInverted = false;
+};
diff --git a/wpilibc/Athena/include/SPI.h b/wpilibc/Athena/include/SPI.h
index 7b33dd7..b6d68f3 100644
--- a/wpilibc/Athena/include/SPI.h
+++ b/wpilibc/Athena/include/SPI.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "HAL/HAL.hpp"
diff --git a/wpilibc/Athena/include/SafePWM.h b/wpilibc/Athena/include/SafePWM.h
index f364626..3c908c7 100644
--- a/wpilibc/Athena/include/SafePWM.h
+++ b/wpilibc/Athena/include/SafePWM.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "MotorSafety.h"
diff --git a/wpilibc/Athena/include/SampleRobot.h b/wpilibc/Athena/include/SampleRobot.h
index 64ca32c..61f8bc0 100644
--- a/wpilibc/Athena/include/SampleRobot.h
+++ b/wpilibc/Athena/include/SampleRobot.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "RobotBase.h"
diff --git a/wpilibc/Athena/include/SerialPort.h b/wpilibc/Athena/include/SerialPort.h
index 3cd1c1c..e94af87 100644
--- a/wpilibc/Athena/include/SerialPort.h
+++ b/wpilibc/Athena/include/SerialPort.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "ErrorBase.h"
diff --git a/wpilibc/Athena/include/Servo.h b/wpilibc/Athena/include/Servo.h
index 040d9d1..f33a82e 100644
--- a/wpilibc/Athena/include/Servo.h
+++ b/wpilibc/Athena/include/Servo.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SafePWM.h"
diff --git a/wpilibc/Athena/include/Solenoid.h b/wpilibc/Athena/include/Solenoid.h
index dc3d53a..d032930 100644
--- a/wpilibc/Athena/include/Solenoid.h
+++ b/wpilibc/Athena/include/Solenoid.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SolenoidBase.h"
diff --git a/wpilibc/Athena/include/SolenoidBase.h b/wpilibc/Athena/include/SolenoidBase.h
index 159beeb..0a71de2 100644
--- a/wpilibc/Athena/include/SolenoidBase.h
+++ b/wpilibc/Athena/include/SolenoidBase.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "Resource.h"
diff --git a/wpilibc/Athena/include/Spark.h b/wpilibc/Athena/include/Spark.h
new file mode 100644
index 0000000..d4859ce
--- /dev/null
+++ b/wpilibc/Athena/include/Spark.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2016. 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 "SafePWM.h"
+#include "SpeedController.h"
+#include "PIDOutput.h"
+
+/**
+ * REV Robotics Speed Controller
+ */
+class Spark : public SafePWM, public SpeedController {
+ public:
+  explicit Spark(uint32_t channel);
+  virtual ~Spark() = default;
+  virtual void Set(float value, uint8_t syncGroup = 0) override;
+  virtual float Get() const override;
+  virtual void Disable() override;
+  virtual void StopMotor() override;
+
+  virtual void PIDWrite(float output) override;
+
+  virtual void SetInverted(bool isInverted) override;
+  virtual bool GetInverted() const override;
+
+ private:
+  bool m_isInverted = false;
+};
diff --git a/wpilibc/Athena/include/SpeedController.h b/wpilibc/Athena/include/SpeedController.h
index a87ed2b..47ba843 100644
--- a/wpilibc/Athena/include/SpeedController.h
+++ b/wpilibc/Athena/include/SpeedController.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "HAL/HAL.hpp"
@@ -47,4 +48,9 @@
    * @return isInverted The state of inversion, true is inverted.
    */
   virtual bool GetInverted() const = 0;
+
+  /**
+   * Common interface to stop the motor until Set is called again.
+   */
+  virtual void StopMotor() = 0;
 };
diff --git a/wpilibc/Athena/include/Talon.h b/wpilibc/Athena/include/Talon.h
index 38764b8..0a88012 100644
--- a/wpilibc/Athena/include/Talon.h
+++ b/wpilibc/Athena/include/Talon.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SafePWM.h"
@@ -24,6 +25,7 @@
   virtual void PIDWrite(float output) override;
   virtual void SetInverted(bool isInverted) override;
   virtual bool GetInverted() const override;
+  virtual void StopMotor() override;
 
  private:
   bool m_isInverted = false;
diff --git a/wpilibc/Athena/include/TalonSRX.h b/wpilibc/Athena/include/TalonSRX.h
index 8819723..61b1fd8 100644
--- a/wpilibc/Athena/include/TalonSRX.h
+++ b/wpilibc/Athena/include/TalonSRX.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SafePWM.h"
@@ -21,6 +22,7 @@
   virtual void Set(float value, uint8_t syncGroup = 0) override;
   virtual float Get() const override;
   virtual void Disable() override;
+  virtual void StopMotor() override;
 
   virtual void PIDWrite(float output) override;
   virtual void SetInverted(bool isInverted) override;
diff --git a/wpilibc/Athena/include/USBCamera.h b/wpilibc/Athena/include/USBCamera.h
index d02c5d3..522e889 100644
--- a/wpilibc/Athena/include/USBCamera.h
+++ b/wpilibc/Athena/include/USBCamera.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 "ErrorBase.h"
diff --git a/wpilibc/Athena/include/Ultrasonic.h b/wpilibc/Athena/include/Ultrasonic.h
index 9f36171..d586173 100644
--- a/wpilibc/Athena/include/Ultrasonic.h
+++ b/wpilibc/Athena/include/Ultrasonic.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SensorBase.h"
@@ -12,10 +13,8 @@
 #include "PIDSource.h"
 #include "LiveWindow/LiveWindowSendable.h"
 #include <atomic>
-
-#include "HAL/cpp/priority_mutex.h"
-
 #include <memory>
+#include <set>
 
 class DigitalInput;
 class DigitalOutput;
@@ -80,24 +79,22 @@
 
   static void UltrasonicChecker();
 
-  static constexpr double kPingTime =
-      10 * 1e-6;  ///< Time (sec) for the ping trigger pulse.
-  static const uint32_t kPriority =
-      64;  ///< Priority that the ultrasonic round robin task runs.
-  static constexpr double kMaxUltrasonicTime =
-      0.1;  ///< Max time (ms) between readings.
+  // Time (sec) for the ping trigger pulse.
+  static constexpr double kPingTime = 10 * 1e-6;
+  // Priority that the ultrasonic round robin task runs.
+  static const uint32_t kPriority = 64;
+  // Max time (ms) between readings.
+  static constexpr double kMaxUltrasonicTime = 0.1;
   static constexpr double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0;
 
   static Task m_task;  // task doing the round-robin automatic sensing
-  static Ultrasonic *m_firstSensor;  // head of the ultrasonic sensor list
+  static std::set<Ultrasonic*> m_sensors; // ultrasonic sensors
   static std::atomic<bool> m_automaticEnabled; // automatic round robin mode
-  static priority_mutex m_mutex;  // synchronize access to the list of sensors
 
   std::shared_ptr<DigitalOutput> m_pingChannel;
   std::shared_ptr<DigitalInput> m_echoChannel;
   bool m_enabled = false;
   Counter m_counter;
-  Ultrasonic *m_nextSensor;
   DistanceUnit m_units;
 
   std::shared_ptr<ITable> m_table;
diff --git a/wpilibc/Athena/include/Victor.h b/wpilibc/Athena/include/Victor.h
index 755955f..2aa2ecf 100644
--- a/wpilibc/Athena/include/Victor.h
+++ b/wpilibc/Athena/include/Victor.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SafePWM.h"
@@ -23,6 +24,7 @@
   virtual void Set(float value, uint8_t syncGroup = 0) override;
   virtual float Get() const override;
   virtual void Disable() override;
+  virtual void StopMotor() override;
 
   virtual void PIDWrite(float output) override;
 
diff --git a/wpilibc/Athena/include/VictorSP.h b/wpilibc/Athena/include/VictorSP.h
index 978cd0a..a53ccfd 100644
--- a/wpilibc/Athena/include/VictorSP.h
+++ b/wpilibc/Athena/include/VictorSP.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SafePWM.h"
@@ -20,6 +21,7 @@
   virtual void Set(float value, uint8_t syncGroup = 0) override;
   virtual float Get() const override;
   virtual void Disable() override;
+  virtual void StopMotor() override;
 
   virtual void PIDWrite(float output) override;
 
diff --git a/wpilibc/Athena/include/Vision/AxisCamera.h b/wpilibc/Athena/include/Vision/AxisCamera.h
index b315938..9252442 100644
--- a/wpilibc/Athena/include/Vision/AxisCamera.h
+++ b/wpilibc/Athena/include/Vision/AxisCamera.h
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #pragma once
diff --git a/wpilibc/Athena/include/Vision/BaeUtilities.h b/wpilibc/Athena/include/Vision/BaeUtilities.h
index 8983ef4..5a1270b 100644
--- a/wpilibc/Athena/include/Vision/BaeUtilities.h
+++ b/wpilibc/Athena/include/Vision/BaeUtilities.h
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #pragma once
diff --git a/wpilibc/Athena/include/Vision/BinaryImage.h b/wpilibc/Athena/include/Vision/BinaryImage.h
index 8b7b25c..d9a24c5 100644
--- a/wpilibc/Athena/include/Vision/BinaryImage.h
+++ b/wpilibc/Athena/include/Vision/BinaryImage.h
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #pragma once
diff --git a/wpilibc/Athena/include/Vision/ColorImage.h b/wpilibc/Athena/include/Vision/ColorImage.h
index 0304ad8..493c541 100644
--- a/wpilibc/Athena/include/Vision/ColorImage.h
+++ b/wpilibc/Athena/include/Vision/ColorImage.h
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #pragma once
diff --git a/wpilibc/Athena/include/Vision/FrcError.h b/wpilibc/Athena/include/Vision/FrcError.h
index 0897c84..bfe0748 100644
--- a/wpilibc/Athena/include/Vision/FrcError.h
+++ b/wpilibc/Athena/include/Vision/FrcError.h
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #pragma once
diff --git a/wpilibc/Athena/include/Vision/HSLImage.h b/wpilibc/Athena/include/Vision/HSLImage.h
index 0407748..057a8c7 100644
--- a/wpilibc/Athena/include/Vision/HSLImage.h
+++ b/wpilibc/Athena/include/Vision/HSLImage.h
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #pragma once
diff --git a/wpilibc/Athena/include/Vision/ImageBase.h b/wpilibc/Athena/include/Vision/ImageBase.h
index c20ecfe..5fc0470 100644
--- a/wpilibc/Athena/include/Vision/ImageBase.h
+++ b/wpilibc/Athena/include/Vision/ImageBase.h
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #pragma once
diff --git a/wpilibc/Athena/include/Vision/MonoImage.h b/wpilibc/Athena/include/Vision/MonoImage.h
index d31f0a4..856d891 100644
--- a/wpilibc/Athena/include/Vision/MonoImage.h
+++ b/wpilibc/Athena/include/Vision/MonoImage.h
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #pragma once
diff --git a/wpilibc/Athena/include/Vision/RGBImage.h b/wpilibc/Athena/include/Vision/RGBImage.h
index cb3b3e5..eeed545 100644
--- a/wpilibc/Athena/include/Vision/RGBImage.h
+++ b/wpilibc/Athena/include/Vision/RGBImage.h
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #pragma once
diff --git a/wpilibc/Athena/include/Vision/Threshold.h b/wpilibc/Athena/include/Vision/Threshold.h
index 83493e8..78d82b4 100644
--- a/wpilibc/Athena/include/Vision/Threshold.h
+++ b/wpilibc/Athena/include/Vision/Threshold.h
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #pragma once
diff --git a/wpilibc/Athena/include/Vision/VisionAPI.h b/wpilibc/Athena/include/Vision/VisionAPI.h
index 3153f1b..7c7b5c1 100644
--- a/wpilibc/Athena/include/Vision/VisionAPI.h
+++ b/wpilibc/Athena/include/Vision/VisionAPI.h
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #pragma once
diff --git a/wpilibc/Athena/include/WPILib.h b/wpilibc/Athena/include/WPILib.h
index 0386b03..8780c85 100644
--- a/wpilibc/Athena/include/WPILib.h
+++ b/wpilibc/Athena/include/WPILib.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #define REAL
@@ -50,6 +51,7 @@
 #include "DriverStation.h"
 #include "Encoder.h"
 #include "ErrorBase.h"
+#include "Filters/LinearDigitalFilter.h"
 #include "GearTooth.h"
 #include "GenericHID.h"
 #include "interfaces/Accelerometer.h"
@@ -71,6 +73,7 @@
 #include "Resource.h"
 #include "RobotBase.h"
 #include "RobotDrive.h"
+#include "SD540.h"
 #include "SensorBase.h"
 #include "SerialPort.h"
 #include "Servo.h"
@@ -78,6 +81,7 @@
 #include "SmartDashboard/SendableChooser.h"
 #include "SmartDashboard/SmartDashboard.h"
 #include "Solenoid.h"
+#include "Spark.h"
 #include "SpeedController.h"
 #include "SPI.h"
 #include "Talon.h"
diff --git a/wpilibc/Athena/src/ADXL345_I2C.cpp b/wpilibc/Athena/src/ADXL345_I2C.cpp
index 000d4b8..ec87376 100644
--- a/wpilibc/Athena/src/ADXL345_I2C.cpp
+++ b/wpilibc/Athena/src/ADXL345_I2C.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "ADXL345_I2C.h"
@@ -17,12 +17,13 @@
 constexpr double ADXL345_I2C::kGsPerLSB;
 
 /**
- * Constructor.
+ * Constructs the ADXL345 Accelerometer over I2C.
  *
  * @param port The I2C port the accelerometer is attached to
  * @param range The range (+ or -) that the accelerometer will measure.
+ * @param deviceAddress the I2C address of the accelerometer (0x1D or 0x53)
  */
-ADXL345_I2C::ADXL345_I2C(Port port, Range range) : I2C(port, kAddress) {
+ADXL345_I2C::ADXL345_I2C(Port port, Range range, int deviceAddress) : I2C(port, deviceAddress) {
   // Turn on the measurements
   Write(kPowerCtlRegister, kPowerCtl_Measure);
   // Specify the data format to read
diff --git a/wpilibc/Athena/src/ADXL345_SPI.cpp b/wpilibc/Athena/src/ADXL345_SPI.cpp
index 7fb3b71..9341db1 100644
--- a/wpilibc/Athena/src/ADXL345_SPI.cpp
+++ b/wpilibc/Athena/src/ADXL345_SPI.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "ADXL345_SPI.h"
diff --git a/wpilibc/Athena/src/ADXL362.cpp b/wpilibc/Athena/src/ADXL362.cpp
index 3c70b9b..889e326 100644
--- a/wpilibc/Athena/src/ADXL362.cpp
+++ b/wpilibc/Athena/src/ADXL362.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "ADXL362.h"
diff --git a/wpilibc/Athena/src/ADXRS450_Gyro.cpp b/wpilibc/Athena/src/ADXRS450_Gyro.cpp
index 6b111cf..a1ec4e3 100644
--- a/wpilibc/Athena/src/ADXRS450_Gyro.cpp
+++ b/wpilibc/Athena/src/ADXRS450_Gyro.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2015. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2015-2016. 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.                                                               */
@@ -151,7 +151,3 @@
 double ADXRS450_Gyro::GetRate() const {
   return (double)m_spi.GetAccumulatorLastValue() * kDegreePerSecondPerLSB;
 }
-
-std::string ADXRS450_Gyro::GetSmartDashboardType() const {
-  return "ADXRS450_Gyro";
-}
diff --git a/wpilibc/Athena/src/AnalogAccelerometer.cpp b/wpilibc/Athena/src/AnalogAccelerometer.cpp
index 5cf41d9..824e751 100644
--- a/wpilibc/Athena/src/AnalogAccelerometer.cpp
+++ b/wpilibc/Athena/src/AnalogAccelerometer.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "AnalogAccelerometer.h"
diff --git a/wpilibc/Athena/src/AnalogGyro.cpp b/wpilibc/Athena/src/AnalogGyro.cpp
index 54093ec..2574792 100644
--- a/wpilibc/Athena/src/AnalogGyro.cpp
+++ b/wpilibc/Athena/src/AnalogGyro.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "AnalogGyro.h"
@@ -132,7 +132,7 @@
   SetPIDSourceType(PIDSourceType::kDisplacement);
 
   HALReport(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel());
-  LiveWindow::GetInstance()->AddSensor("Gyro", m_analog->GetChannel(), this);
+  LiveWindow::GetInstance()->AddSensor("AnalogGyro", m_analog->GetChannel(), this);
 }
 
 /**
@@ -251,5 +251,3 @@
                      (1 << m_analog->GetOversampleBits());
   m_analog->SetAccumulatorDeadband(deadband);
 }
-
-std::string AnalogGyro::GetSmartDashboardType() const { return "AnalogGyro"; }
diff --git a/wpilibc/Athena/src/AnalogInput.cpp b/wpilibc/Athena/src/AnalogInput.cpp
index dc8e872..7852aea 100644
--- a/wpilibc/Athena/src/AnalogInput.cpp
+++ b/wpilibc/Athena/src/AnalogInput.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "AnalogInput.h"
diff --git a/wpilibc/Athena/src/AnalogOutput.cpp b/wpilibc/Athena/src/AnalogOutput.cpp
index 74a1f9c..2092936 100644
--- a/wpilibc/Athena/src/AnalogOutput.cpp
+++ b/wpilibc/Athena/src/AnalogOutput.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibc/Athena/src/AnalogPotentiometer.cpp b/wpilibc/Athena/src/AnalogPotentiometer.cpp
index 1372d84..8c8aaac 100644
--- a/wpilibc/Athena/src/AnalogPotentiometer.cpp
+++ b/wpilibc/Athena/src/AnalogPotentiometer.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "AnalogPotentiometer.h"
 #include "ControllerPower.h"
 
diff --git a/wpilibc/Athena/src/AnalogTrigger.cpp b/wpilibc/Athena/src/AnalogTrigger.cpp
index b49d6a0..36a1459 100644
--- a/wpilibc/Athena/src/AnalogTrigger.cpp
+++ b/wpilibc/Athena/src/AnalogTrigger.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "AnalogTrigger.h"
diff --git a/wpilibc/Athena/src/AnalogTriggerOutput.cpp b/wpilibc/Athena/src/AnalogTriggerOutput.cpp
index 8254275..eb67d36 100644
--- a/wpilibc/Athena/src/AnalogTriggerOutput.cpp
+++ b/wpilibc/Athena/src/AnalogTriggerOutput.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "AnalogTriggerOutput.h"
diff --git a/wpilibc/Athena/src/BuiltInAccelerometer.cpp b/wpilibc/Athena/src/BuiltInAccelerometer.cpp
index a504524..fb4ae04 100644
--- a/wpilibc/Athena/src/BuiltInAccelerometer.cpp
+++ b/wpilibc/Athena/src/BuiltInAccelerometer.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "BuiltInAccelerometer.h"
diff --git a/wpilibc/Athena/src/CANJaguar.cpp b/wpilibc/Athena/src/CANJaguar.cpp
index fc71e84..7dcca19 100644
--- a/wpilibc/Athena/src/CANJaguar.cpp
+++ b/wpilibc/Athena/src/CANJaguar.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2009. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2009-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "CANJaguar.h"
@@ -245,8 +246,11 @@
   uint8_t dataBuffer[8];
   uint8_t dataSize;
 
-  if (m_safetyHelper && !m_safetyHelper->IsAlive() && m_controlEnabled) {
+  if (m_safetyHelper) m_safetyHelper->Feed();
+
+  if (m_stopped) {
     EnableControl();
+    m_stopped = false;
   }
 
   if (m_controlEnabled) {
@@ -289,8 +293,6 @@
     }
 
     sendMessage(messageID, dataBuffer, dataSize, kSendMessagePeriod);
-
-    if (m_safetyHelper) m_safetyHelper->Feed();
   }
 
   m_value = outputValue;
@@ -1010,6 +1012,7 @@
     case kPercentVbus:
     case kVoltage:
     case kFollower:
+    case kMotionProfile:
       wpi_setWPIErrorWithContext(
           IncompatibleMode,
           "PID constants only apply in Speed, Position, and Current mode");
@@ -1045,6 +1048,7 @@
     case kPercentVbus:
     case kVoltage:
     case kFollower:
+    case kMotionProfile:
       wpi_setWPIErrorWithContext(
           IncompatibleMode,
           "PID constants only apply in Speed, Position, and Current mode");
@@ -1080,6 +1084,7 @@
     case kPercentVbus:
     case kVoltage:
     case kFollower:
+    case kMotionProfile:
       wpi_setWPIErrorWithContext(
           IncompatibleMode,
           "PID constants only apply in Speed, Position, and Current mode");
@@ -1516,7 +1521,7 @@
   // Disable the previous mode
   DisableControl();
 
-  if (controlMode == kFollower)
+  if ((controlMode == kFollower) || (controlMode == kMotionProfile))
     wpi_setWPIErrorWithContext(IncompatibleMode,
                                "The Jaguar only supports Current, Voltage, "
                                "Position, Speed, and Percent (Throttle) "
@@ -1930,12 +1935,14 @@
 uint8_t CANJaguar::GetDeviceID() const { return m_deviceNumber; }
 
 /**
- * Common interface for stopping the motor
+ * Common interface for stopping the motor until the next Set() command
  * Part of the MotorSafety interface
  *
  * @deprecated Call DisableControl instead.
  */
-void CANJaguar::StopMotor() { DisableControl(); }
+void CANJaguar::StopMotor() {
+	m_stopped = true;
+}
 
 /**
 * Common interface for inverting direction of a speed controller.
@@ -1978,7 +1985,7 @@
   if (m_table != nullptr) {
     m_table->PutString("~TYPE~", "CANSpeedController");
     m_table->PutString("Type", "CANJaguar");
-    m_table->PutString("Mode", GetModeName(m_controlMode));
+    m_table->PutNumber("Mode", m_controlMode);
     if (IsModePID(m_controlMode)) {
         m_table->PutNumber("p", GetP());
         m_table->PutNumber("i", GetI());
diff --git a/wpilibc/Athena/src/CANTalon.cpp b/wpilibc/Athena/src/CANTalon.cpp
index f937212..9adc66c 100644
--- a/wpilibc/Athena/src/CANTalon.cpp
+++ b/wpilibc/Athena/src/CANTalon.cpp
@@ -1,13 +1,16 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "CANTalon.h"
 #include "WPIErrors.h"
 #include <unistd.h>  // usleep
 #include <sstream>
+#include "LiveWindow/LiveWindow.h"
+
 /**
  * Number of adc engineering units per 0 to 3.3V sweep.
  * This is necessary for scaling Analog Position in rotations/RPM.
@@ -35,6 +38,7 @@
   ApplyControlMode(m_controlMode);
   m_impl->SetProfileSlotSelect(m_profile);
   m_isInverted = false;
+  LiveWindow::GetInstance()->AddActuator("CANTalon", m_deviceNumber, this);
 }
 /**
  * Constructor for the CANTalon device.
@@ -48,6 +52,7 @@
       m_safetyHelper(new MotorSafetyHelper(this)) {
   ApplyControlMode(m_controlMode);
   m_impl->SetProfileSlotSelect(m_profile);
+  LiveWindow::GetInstance()->AddActuator("CANTalon", m_deviceNumber, this);
 }
 
 CANTalon::~CANTalon() {
@@ -129,6 +134,12 @@
 void CANTalon::Set(float value, uint8_t syncGroup) {
   /* feed safety helper since caller just updated our output */
   m_safetyHelper->Feed();
+
+  if (m_stopped) {
+    EnableControl();
+    m_stopped = false;
+  }
+
   if (m_controlEnabled) {
     m_setPoint = value;  /* cache set point for GetSetpoint() */
     CTR_Code status = CTR_OKAY;
@@ -156,6 +167,9 @@
         double milliamperes = (m_isInverted ? -value : value) * 1000.0; /* mA*/
         status = m_impl->SetDemand(milliamperes);
       } break;
+      case CANSpeedController::kMotionProfile: {
+        status = m_impl->SetDemand((int)value);
+      } break;
       default:
         wpi_setWPIErrorWithContext(
             IncompatibleMode,
@@ -1198,7 +1212,43 @@
 }
 
 /**
- * TODO documentation (see CANJaguar.cpp)
+ * Overrides the forward and reverse limit switch enables.
+ * Unlike ConfigLimitMode, this function allows individual control of forward and
+ * reverse limit switch enables.
+ * Unlike ConfigLimitMode, this function does not affect the soft-limit features of Talon SRX.
+ * @see ConfigLimitMode()
+ */
+void CANTalon::ConfigLimitSwitchOverrides(bool bForwardLimitSwitchEn, bool bReverseLimitSwitchEn) {
+  CTR_Code status = CTR_OKAY;
+  int fwdRevEnable;
+  /* chose correct signal value based on caller's requests enables */
+  if(!bForwardLimitSwitchEn) {
+    /* caller wants Forward Limit Switch OFF */
+    if(!bReverseLimitSwitchEn) {
+      /* caller wants both OFF */
+      fwdRevEnable = CanTalonSRX::kLimitSwitchOverride_DisableFwd_DisableRev;
+    } else {
+      /* caller Forward OFF and Reverse ON */
+      fwdRevEnable = CanTalonSRX::kLimitSwitchOverride_DisableFwd_EnableRev;
+    }
+  } else {
+    /* caller wants Forward Limit Switch ON */
+    if(!bReverseLimitSwitchEn) {
+      /* caller wants Forward ON and Reverse OFF */
+      fwdRevEnable = CanTalonSRX::kLimitSwitchOverride_EnableFwd_DisableRev;
+    } else {
+      /* caller wants both ON */
+      fwdRevEnable = CanTalonSRX::kLimitSwitchOverride_EnableFwd_EnableRev;
+    }
+  }
+  /* update signal and error check code */
+  status = m_impl->SetOverrideLimitSwitchEn(fwdRevEnable);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+/**
  * Configures the soft limit enable (wear leveled persistent memory).
  * Also sets the limit switch overrides.
  */
@@ -1275,6 +1325,32 @@
     wpi_setErrorWithContext(status, getHALErrorMessage(status));
   }
 }
+
+/**
+ * Set the Forward Soft Limit Enable.
+ * This is the same setting that is in the Web-Based Configuration.
+ * @param bForwardSoftLimitEn true to enable Soft limit, false to disable.
+ */
+void CANTalon::ConfigForwardSoftLimitEnable(bool bForwardSoftLimitEn) {
+  CTR_Code status = CTR_OKAY;
+  status = m_impl->SetForwardSoftEnable(bForwardSoftLimitEn);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+/**
+ * Set the Reverse Soft Limit Enable.
+ * This is the same setting that is in the Web-Based Configuration.
+ * @param bReverseSoftLimitEn true to enable Soft limit, false to disable.
+ */
+void CANTalon::ConfigReverseSoftLimitEnable(bool bReverseSoftLimitEn) {
+  CTR_Code status = CTR_OKAY;
+  status = m_impl->SetReverseSoftEnable(bReverseSoftLimitEn);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
 /**
  * Change the fwd limit switch setting to normally open or closed.
  * Talon will disable momentarilly if the Talon's current setting
@@ -1430,6 +1506,9 @@
     case kFollower:
       m_sendMode = kFollowerMode;
       break;
+    case kMotionProfile:
+      m_sendMode = kMotionProfileMode;
+      break;
   }
   // Keep the talon disabled until Set() is called.
   CTR_Code status = m_impl->SetModeSelect((int)kDisabled);
@@ -1668,6 +1747,136 @@
     ConfigSetParameter(CanTalonSRX::eQuadIdxPolarity,risingEdge  ? 1 : 0);
   }
 }
+
+/**
+ * Calling application can opt to speed up the handshaking between the robot API and the Talon to increase the
+ * download rate of the Talon's Motion Profile.  Ideally the period should be no more than half the period
+ * of a trajectory point.
+ */
+void CANTalon::ChangeMotionControlFramePeriod(int periodMs)
+{
+  m_impl->ChangeMotionControlFramePeriod(periodMs);
+}
+
+/**
+ * Clear the buffered motion profile in both Talon RAM (bottom), and in the API (top).
+ * Be sure to check GetMotionProfileStatus() to know when the buffer is actually cleared.
+ */
+void CANTalon::ClearMotionProfileTrajectories()
+{
+  m_impl->ClearMotionProfileTrajectories();
+}
+
+/**
+ * Retrieve just the buffer count for the api-level (top) buffer.
+ * This routine performs no CAN or data structure lookups, so its fast and ideal
+ * if caller needs to quickly poll the progress of trajectory points being emptied
+ * into Talon's RAM. Otherwise just use GetMotionProfileStatus.
+ * @return number of trajectory points in the top buffer.
+ */
+int CANTalon::GetMotionProfileTopLevelBufferCount()
+{
+  return m_impl->GetMotionProfileTopLevelBufferCount();
+}
+
+/**
+ * Push another trajectory point into the top level buffer (which is emptied into
+ * the Talon's bottom buffer as room allows).
+ * @param trajPt the trajectory point to insert into buffer.
+ * @return true  if trajectory point push ok. CTR_BufferFull if buffer is full
+ * due to kMotionProfileTopBufferCapacity.
+ */
+bool CANTalon::PushMotionProfileTrajectory(const TrajectoryPoint & trajPt)
+{
+  /* convert positiona and velocity to native units */
+  int32_t targPos  = ScaleRotationsToNativeUnits(m_feedbackDevice, trajPt.position);
+  int32_t targVel = ScaleVelocityToNativeUnits(m_feedbackDevice, trajPt.velocity);
+  /* bounds check signals that require it */
+  uint32_t profileSlotSelect = (trajPt.profileSlotSelect) ? 1 : 0;
+  uint8_t timeDurMs = (trajPt.timeDurMs >= 255) ? 255 : trajPt.timeDurMs; /* cap time to 255ms */
+  /* send it to the top level buffer */
+  CTR_Code status = m_impl->PushMotionProfileTrajectory(targPos, targVel, profileSlotSelect, timeDurMs, trajPt.velocityOnly, trajPt.isLastPoint, trajPt.zeroPos);
+  return (status == CTR_OKAY) ? true : false;
+}
+/**
+ * @return true if api-level (top) buffer is full.
+ */
+bool CANTalon::IsMotionProfileTopLevelBufferFull()
+{
+  return m_impl->IsMotionProfileTopLevelBufferFull();
+}
+
+/**
+ * This must be called periodically to funnel the trajectory points from the API's top level buffer to
+ * the Talon's bottom level buffer.  Recommendation is to call this twice as fast as the executation rate of the motion profile.
+ * So if MP is running with 20ms trajectory points, try calling this routine every 10ms.  All motion profile functions are thread-safe
+ * through the use of a mutex, so there is no harm in having the caller utilize threading.
+ */
+void CANTalon::ProcessMotionProfileBuffer()
+{
+  m_impl->ProcessMotionProfileBuffer();
+}
+
+/**
+ * Retrieve all status information.
+ * Since this all comes from one CAN frame, its ideal to have one routine to retrieve the frame once and decode everything.
+ * @param [out] motionProfileStatus contains all progress information on the currently running MP.
+ */
+void CANTalon::GetMotionProfileStatus(MotionProfileStatus & motionProfileStatus)
+{
+  uint32_t flags;
+  uint32_t profileSlotSelect;
+  int32_t targPos, targVel;
+  uint32_t topBufferRem, topBufferCnt, btmBufferCnt;
+  uint32_t outputEnable;
+  /* retrieve all motion profile signals from status frame */
+  CTR_Code status = m_impl->GetMotionProfileStatus(flags, profileSlotSelect, targPos, targVel, topBufferRem, topBufferCnt, btmBufferCnt, outputEnable);
+  /* completely update the caller's structure */
+  motionProfileStatus.topBufferRem = topBufferRem;
+  motionProfileStatus.topBufferCnt = topBufferCnt;
+  motionProfileStatus.btmBufferCnt = btmBufferCnt;
+  motionProfileStatus.hasUnderrun =              (flags & CanTalonSRX::kMotionProfileFlag_HasUnderrun)     ? true :false;
+  motionProfileStatus.isUnderrun  =              (flags & CanTalonSRX::kMotionProfileFlag_IsUnderrun)      ? true :false;
+  motionProfileStatus.activePointValid =         (flags & CanTalonSRX::kMotionProfileFlag_ActTraj_IsValid) ? true :false;
+  motionProfileStatus.activePoint.isLastPoint =  (flags & CanTalonSRX::kMotionProfileFlag_ActTraj_IsLast)  ? true :false;
+  motionProfileStatus.activePoint.velocityOnly = (flags & CanTalonSRX::kMotionProfileFlag_ActTraj_VelOnly) ? true :false;
+  motionProfileStatus.activePoint.position = ScaleNativeUnitsToRotations(m_feedbackDevice, targPos);
+  motionProfileStatus.activePoint.velocity = ScaleNativeUnitsToRpm(m_feedbackDevice, targVel);
+  motionProfileStatus.activePoint.profileSlotSelect = profileSlotSelect;
+  switch(outputEnable){
+    case CanTalonSRX::kMotionProf_Disabled:
+      motionProfileStatus.outputEnable = SetValueMotionProfileDisable;
+    break;
+    case CanTalonSRX::kMotionProf_Enable:
+      motionProfileStatus.outputEnable = SetValueMotionProfileEnable;
+      break;
+    case CanTalonSRX::kMotionProf_Hold:
+      motionProfileStatus.outputEnable = SetValueMotionProfileHold;
+      break;
+    default:
+      motionProfileStatus.outputEnable = SetValueMotionProfileDisable;
+      break;
+  }
+  motionProfileStatus.activePoint.zeroPos = false; /* this signal is only used sending pts to Talon */
+  motionProfileStatus.activePoint.timeDurMs = 0;   /* this signal is only used sending pts to Talon */
+
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * Clear the hasUnderrun flag in Talon's Motion Profile Executer when MPE is ready for another point,
+ * but the low level buffer is empty.
+ *
+ * Once the Motion Profile Executer sets the hasUnderrun flag, it stays set until
+ * Robot Application clears it with this routine, which ensures Robot Application
+ * gets a chance to instrument or react.  Caller could also check the isUnderrun flag
+ * which automatically clears when fault condition is removed.
+ */
+void CANTalon::ClearMotionProfileHasUnderrun()
+{
+  ConfigSetParameter(CanTalonSRX::eMotionProfileHasUnderrunErr, 0);
+}
 /**
 * Common interface for inverting direction of a speed controller.
 * Only works in PercentVbus, speed, and Voltage modes.
@@ -1684,12 +1893,15 @@
 bool CANTalon::GetInverted() const { return m_isInverted; }
 
 /**
- * Common interface for stopping the motor
+ * Common interface for stopping the motor until the next Set() call
  * Part of the MotorSafety interface
  *
  * @deprecated Call Disable instead.
 */
-void CANTalon::StopMotor() { Disable(); }
+void CANTalon::StopMotor() {
+	Disable();
+	m_stopped = true;
+}
 
 void CANTalon::ValueChanged(ITable* source, llvm::StringRef key,
                             std::shared_ptr<nt::Value> value, bool isNew) {
@@ -1716,7 +1928,7 @@
   if (m_table != nullptr) {
     m_table->PutString("~TYPE~", "CANSpeedController");
     m_table->PutString("Type", "CANTalon");
-    m_table->PutString("Mode", GetModeName(m_controlMode));
+    m_table->PutNumber("Mode", m_controlMode);
     m_table->PutNumber("p", GetP());
     m_table->PutNumber("i", GetI());
     m_table->PutNumber("d", GetD());
diff --git a/wpilibc/Athena/src/CameraServer.cpp b/wpilibc/Athena/src/CameraServer.cpp
index af319a4..54b7e06 100644
--- a/wpilibc/Athena/src/CameraServer.cpp
+++ b/wpilibc/Athena/src/CameraServer.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "WPIErrors.h"
 #include "Utility.h"
diff --git a/wpilibc/Athena/src/ControllerPower.cpp b/wpilibc/Athena/src/ControllerPower.cpp
index ea508af..a62539f 100644
--- a/wpilibc/Athena/src/ControllerPower.cpp
+++ b/wpilibc/Athena/src/ControllerPower.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "ControllerPower.h"
diff --git a/wpilibc/Athena/src/Counter.cpp b/wpilibc/Athena/src/Counter.cpp
index cd70de5..a138867 100644
--- a/wpilibc/Athena/src/Counter.cpp
+++ b/wpilibc/Athena/src/Counter.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Counter.h"
diff --git a/wpilibc/Athena/src/DigitalGlitchFilter.cpp b/wpilibc/Athena/src/DigitalGlitchFilter.cpp
index 56147cb..4cde562 100644
--- a/wpilibc/Athena/src/DigitalGlitchFilter.cpp
+++ b/wpilibc/Athena/src/DigitalGlitchFilter.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2015. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2015-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include <algorithm>
diff --git a/wpilibc/Athena/src/DigitalInput.cpp b/wpilibc/Athena/src/DigitalInput.cpp
index f6b96f5..19538a4 100644
--- a/wpilibc/Athena/src/DigitalInput.cpp
+++ b/wpilibc/Athena/src/DigitalInput.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "DigitalInput.h"
diff --git a/wpilibc/Athena/src/DigitalOutput.cpp b/wpilibc/Athena/src/DigitalOutput.cpp
index d74f93b..99b16e8 100644
--- a/wpilibc/Athena/src/DigitalOutput.cpp
+++ b/wpilibc/Athena/src/DigitalOutput.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "DigitalOutput.h"
diff --git a/wpilibc/Athena/src/DoubleSolenoid.cpp b/wpilibc/Athena/src/DoubleSolenoid.cpp
index 4fb2943..f8ed267 100644
--- a/wpilibc/Athena/src/DoubleSolenoid.cpp
+++ b/wpilibc/Athena/src/DoubleSolenoid.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "DoubleSolenoid.h"
diff --git a/wpilibc/Athena/src/DriverStation.cpp b/wpilibc/Athena/src/DriverStation.cpp
index 455a987..3226223 100644
--- a/wpilibc/Athena/src/DriverStation.cpp
+++ b/wpilibc/Athena/src/DriverStation.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "DriverStation.h"
@@ -88,8 +88,8 @@
  * @return Pointer to the DS instance
  */
 DriverStation &DriverStation::GetInstance() {
-  static DriverStation instance;
-  return instance;
+  static DriverStation *instance = new DriverStation();
+  return *instance;
 }
 
 /**
@@ -134,6 +134,18 @@
 }
 
 /**
+ * Reports errors related to unplugged joysticks
+ * Throttles the errors so that they don't overwhelm the DS
+ */
+void DriverStation::ReportJoystickUnpluggedWarning(std::string message) {
+  double currentTime = Timer::GetFPGATimestamp();
+  if (currentTime > m_nextMessageTime) {
+    ReportWarning(message);
+    m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL;
+  }
+}
+
+/**
  * Returns the number of axes on a given joystick port
  *
  * @param stick The joystick port number
@@ -159,7 +171,7 @@
   if (stick >= kJoystickPorts) {
     wpi_setWPIError(BadJoystickIndex);
   }
-  std::string retVal(m_joystickDescriptor[0].name);
+  std::string retVal(m_joystickDescriptor[stick].name);
   return retVal;
 }
 
@@ -255,9 +267,8 @@
     if (axis >= kMaxJoystickAxes)
       wpi_setWPIError(BadJoystickAxis);
     else
-      ReportJoystickUnpluggedError(
-          "WARNING: Joystick Axis missing, check if all controllers are "
-          "plugged in\n");
+      ReportJoystickUnpluggedWarning(
+          "Joystick Axis missing, check if all controllers are plugged in");
     return 0.0f;
   }
 
@@ -285,9 +296,8 @@
     if (pov >= kMaxJoystickPOVs)
       wpi_setWPIError(BadJoystickAxis);
     else
-      ReportJoystickUnpluggedError(
-          "WARNING: Joystick POV missing, check if all controllers are plugged "
-          "in\n");
+      ReportJoystickUnpluggedWarning(
+          "Joystick POV missing, check if all controllers are plugged in");
     return -1;
   }
 
@@ -323,14 +333,13 @@
   }
 
   if (button > m_joystickButtons[stick].count) {
-    ReportJoystickUnpluggedError(
-        "WARNING: Joystick Button missing, check if all controllers are "
-        "plugged in\n");
+    ReportJoystickUnpluggedWarning(
+        "Joystick Button missing, check if all controllers are plugged in");
     return false;
   }
   if (button == 0) {
     ReportJoystickUnpluggedError(
-        "ERROR: Button indexes begin at 1 in WPILib for C++ and Java");
+        "Button indexes begin at 1 in WPILib for C++ and Java");
     return false;
   }
   return ((0x1 << (button - 1)) & m_joystickButtons[stick].buttons) != 0;
@@ -527,11 +536,25 @@
  * The error is also printed to the program console.
  */
 void DriverStation::ReportError(std::string error) {
-  std::cout << error << std::endl;
+  HALSendError(1, 1, 0, error.c_str(), "", "", 1);
+}
 
-  HALControlWord controlWord;
-  HALGetControlWord(&controlWord);
-  if (controlWord.dsAttached) {
-    HALSetErrorData(error.c_str(), error.size(), 0);
-  }
+/**
+ * Report a warning to the DriverStation messages window.
+ * The warning is also printed to the program console.
+ */
+void DriverStation::ReportWarning(std::string error) {
+  HALSendError(0, 1, 0, error.c_str(), "", "", 1);
+}
+
+/**
+ * Report an error to the DriverStation messages window.
+ * The error is also printed to the program console.
+ */
+void DriverStation::ReportError(bool is_error, int32_t code,
+                                const std::string &error,
+                                const std::string &location,
+                                const std::string &stack) {
+  HALSendError(is_error, code, 0, error.c_str(), location.c_str(),
+               stack.c_str(), 1);
 }
diff --git a/wpilibc/Athena/src/Encoder.cpp b/wpilibc/Athena/src/Encoder.cpp
index 0fa12df..7c5a499 100644
--- a/wpilibc/Athena/src/Encoder.cpp
+++ b/wpilibc/Athena/src/Encoder.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Encoder.h"
diff --git a/wpilibc/Athena/src/GearTooth.cpp b/wpilibc/Athena/src/GearTooth.cpp
index b659125..4eed6b6 100644
--- a/wpilibc/Athena/src/GearTooth.cpp
+++ b/wpilibc/Athena/src/GearTooth.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "GearTooth.h"
diff --git a/wpilibc/Athena/src/I2C.cpp b/wpilibc/Athena/src/I2C.cpp
index 79767b3..d70a132 100644
--- a/wpilibc/Athena/src/I2C.cpp
+++ b/wpilibc/Athena/src/I2C.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "I2C.h"
diff --git a/wpilibc/Athena/src/Internal/HardwareHLReporting.cpp b/wpilibc/Athena/src/Internal/HardwareHLReporting.cpp
index 2176c80..3b1a7b6 100644
--- a/wpilibc/Athena/src/Internal/HardwareHLReporting.cpp
+++ b/wpilibc/Athena/src/Internal/HardwareHLReporting.cpp
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "Internal/HardwareHLReporting.h"
 #include "HAL/HAL.hpp"
diff --git a/wpilibc/Athena/src/InterruptableSensorBase.cpp b/wpilibc/Athena/src/InterruptableSensorBase.cpp
index 6e66c34..7c9a80f 100644
--- a/wpilibc/Athena/src/InterruptableSensorBase.cpp
+++ b/wpilibc/Athena/src/InterruptableSensorBase.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "InterruptableSensorBase.h"
diff --git a/wpilibc/Athena/src/IterativeRobot.cpp b/wpilibc/Athena/src/IterativeRobot.cpp
index fa1d2ba..3d6946a 100644
--- a/wpilibc/Athena/src/IterativeRobot.cpp
+++ b/wpilibc/Athena/src/IterativeRobot.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "IterativeRobot.h"
diff --git a/wpilibc/Athena/src/Jaguar.cpp b/wpilibc/Athena/src/Jaguar.cpp
index ce61d36..b2bd57a 100644
--- a/wpilibc/Athena/src/Jaguar.cpp
+++ b/wpilibc/Athena/src/Jaguar.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Jaguar.h"
@@ -77,3 +77,8 @@
  * @param output Write out the PWM value as was found in the PIDController
  */
 void Jaguar::PIDWrite(float output) { Set(output); }
+
+/**
+ * Common interface to stop the motor until Set is called again.
+ */
+void Jaguar::StopMotor() { this->SafePWM::StopMotor(); }
\ No newline at end of file
diff --git a/wpilibc/Athena/src/Joystick.cpp b/wpilibc/Athena/src/Joystick.cpp
index 388832c..0a5b623 100644
--- a/wpilibc/Athena/src/Joystick.cpp
+++ b/wpilibc/Athena/src/Joystick.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Joystick.h"
diff --git a/wpilibc/Athena/src/MotorSafetyHelper.cpp b/wpilibc/Athena/src/MotorSafetyHelper.cpp
index 60bba30..a78c348 100644
--- a/wpilibc/Athena/src/MotorSafetyHelper.cpp
+++ b/wpilibc/Athena/src/MotorSafetyHelper.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "MotorSafetyHelper.h"
diff --git a/wpilibc/Athena/src/Notifier.cpp b/wpilibc/Athena/src/Notifier.cpp
index fc3059c..0023100 100644
--- a/wpilibc/Athena/src/Notifier.cpp
+++ b/wpilibc/Athena/src/Notifier.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Notifier.h"
@@ -11,207 +11,63 @@
 #include "WPIErrors.h"
 #include "HAL/HAL.hpp"
 
-Notifier *Notifier::timerQueueHead = nullptr;
-priority_recursive_mutex Notifier::queueMutex;
-priority_mutex Notifier::halMutex;
-void *Notifier::m_notifier = nullptr;
-std::atomic<int> Notifier::refcount{0};
-
 /**
  * Create a Notifier for timer event notification.
  * @param handler The handler is called at the notification time which is set
  * using StartSingle or StartPeriodic.
  */
-Notifier::Notifier(TimerEventHandler handler, void *param) {
+Notifier::Notifier(TimerEventHandler handler) {
   if (handler == nullptr)
     wpi_setWPIErrorWithContext(NullParameter, "handler must not be nullptr");
   m_handler = handler;
-  m_param = param;
-  // do the first time intialization of static variables
-  if (refcount.fetch_add(1) == 0) {
-    int32_t status = 0;
-    {
-      std::lock_guard<priority_mutex> sync(halMutex);
-      if (!m_notifier)
-        m_notifier = initializeNotifier(ProcessQueue, nullptr, &status);
-    }
-    wpi_setErrorWithContext(status, getHALErrorMessage(status));
-  }
+  int32_t status = 0;
+  m_notifier = initializeNotifier(&Notifier::Notify, this, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
 }
 
 /**
  * Free the resources for a timer event.
- * All resources will be freed and the timer event will be removed from the
- * queue if necessary.
  */
 Notifier::~Notifier() {
-  {
-    std::lock_guard<priority_recursive_mutex> sync(queueMutex);
-    DeleteFromQueue();
-  }
+  int32_t status = 0;
+  cleanNotifier(m_notifier, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
 
-  // Delete the static variables when the last one is going away
-  if (refcount.fetch_sub(1) == 1) {
-    int32_t status = 0;
-    {
-      std::lock_guard<priority_mutex> sync(halMutex);
-      if (m_notifier) {
-        cleanNotifier(m_notifier, &status);
-        m_notifier = nullptr;
-      }
-    }
-    wpi_setErrorWithContext(status, getHALErrorMessage(status));
-  }
-
-  // Acquire the mutex; this makes certain that the handler is
-  // not being executed by the interrupt manager.
+  /* Acquire the mutex; this makes certain that the handler is not being
+   * executed by the interrupt manager.
+   */
   std::lock_guard<priority_mutex> lock(m_handlerMutex);
 }
 
 /**
- * Update the alarm hardware to reflect the current first element in the queue.
- * Compute the time the next alarm should occur based on the current time and
- * the
- * period for the first element in the timer queue.
- * WARNING: this method does not do synchronization! It must be called from
- * somewhere
- * that is taking care of synchronizing access to the queue.
+ * Update the HAL alarm time.
  */
 void Notifier::UpdateAlarm() {
-  if (timerQueueHead != nullptr) {
-    int32_t status = 0;
-    // This locking is necessary in order to avoid two things:
-    //  1) Race condition issues with calling cleanNotifer() and
-    //     updateNotifierAlarm() at the same time.
-    //  2) Avoid deadlock by making it so that this won't block waiting
-    //     for the mutex to unlock.
-    // Checking refcount as well is unnecessary, but will not hurt.
-    if (halMutex.try_lock() && refcount != 0) {
-      if (m_notifier)
-        updateNotifierAlarm(m_notifier,
-                            (uint32_t)(timerQueueHead->m_expirationTime * 1e6),
-                            &status);
-      halMutex.unlock();
-    }
-    wpi_setStaticErrorWithContext(timerQueueHead, status,
-                                  getHALErrorMessage(status));
-  }
+  int32_t status = 0;
+  updateNotifierAlarm(m_notifier, (uint64_t)(m_expirationTime * 1e6), &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
 }
 
 /**
- * ProcessQueue is called whenever there is a timer interrupt.
- * We need to wake up and process the current top item in the timer queue as
- * long
- * as its scheduled time is after the current time. Then the item is removed or
- * rescheduled (repetitive events) in the queue.
+ * Notify is called by the HAL layer.  We simply need to pass it through to
+ * the user handler.
  */
-void Notifier::ProcessQueue(uint32_t currentTimeInt, void *params) {
-  Notifier *current;
-  while (true)  // keep processing past events until no more
-  {
-    {
-      std::lock_guard<priority_recursive_mutex> sync(queueMutex);
-      double currentTime = currentTimeInt * 1.0e-6;
-      current = timerQueueHead;
-      if (current == nullptr || current->m_expirationTime > currentTime) {
-        break;  // no more timer events to process
-      }
-      // need to process this entry
-      timerQueueHead = current->m_nextEvent;
-      if (current->m_periodic) {
-        // if periodic, requeue the event
-        // compute when to put into queue
-        current->InsertInQueue(true);
-      } else {
-        // not periodic; removed from queue
-        current->m_queued = false;
-      }
-      // Take handler mutex while holding queue mutex to make sure
-      //  the handler will execute to completion in case we are being deleted.
-      current->m_handlerMutex.lock();
-    }
+void Notifier::Notify(uint64_t currentTimeInt, void *param) {
+  Notifier* notifier = static_cast<Notifier*>(param);
 
-    current->m_handler(current->m_param);  // call the event handler
-    current->m_handlerMutex.unlock();
+  notifier->m_processMutex.lock();
+  if (notifier->m_periodic) {
+    notifier->m_expirationTime += notifier->m_period;
+    notifier->UpdateAlarm();
   }
-  // reschedule the first item in the queue
-  std::lock_guard<priority_recursive_mutex> sync(queueMutex);
-  UpdateAlarm();
-}
 
-/**
- * Insert this Notifier into the timer queue in right place.
- * WARNING: this method does not do synchronization! It must be called from
- * somewhere
- * that is taking care of synchronizing access to the queue.
- * @param reschedule If false, the scheduled alarm is based on the current time
- * and UpdateAlarm
- * method is called which will enable the alarm if necessary.
- * If true, update the time by adding the period (no drift) when rescheduled
- * periodic from ProcessQueue.
- * This ensures that the public methods only update the queue after finishing
- * inserting.
- */
-void Notifier::InsertInQueue(bool reschedule) {
-  if (reschedule) {
-    m_expirationTime += m_period;
-  } else {
-    m_expirationTime = GetClock() + m_period;
-  }
-  if (m_expirationTime > Timer::kRolloverTime) {
-    m_expirationTime -= Timer::kRolloverTime;
-  }
-  if (timerQueueHead == nullptr ||
-      timerQueueHead->m_expirationTime >= this->m_expirationTime) {
-    // the queue is empty or greater than the new entry
-    // the new entry becomes the first element
-    this->m_nextEvent = timerQueueHead;
-    timerQueueHead = this;
-    if (!reschedule) {
-      // since the first element changed, update alarm, unless we already plan
-      // to
-      UpdateAlarm();
-    }
-  } else {
-    for (Notifier **npp = &(timerQueueHead->m_nextEvent);;
-         npp = &(*npp)->m_nextEvent) {
-      Notifier *n = *npp;
-      if (n == nullptr || n->m_expirationTime > this->m_expirationTime) {
-        *npp = this;
-        this->m_nextEvent = n;
-        break;
-      }
-    }
-  }
-  m_queued = true;
-}
+  auto handler = notifier->m_handler;
 
-/**
- * Delete this Notifier from the timer queue.
- * WARNING: this method does not do synchronization! It must be called from
- * somewhere
- * that is taking care of synchronizing access to the queue.
- * Remove this Notifier from the timer queue and adjust the next interrupt time
- * to reflect
- * the current top of the queue.
- */
-void Notifier::DeleteFromQueue() {
-  if (m_queued) {
-    m_queued = false;
-    wpi_assert(timerQueueHead != nullptr);
-    if (timerQueueHead == this) {
-      // remove the first item in the list - update the alarm
-      timerQueueHead = this->m_nextEvent;
-      UpdateAlarm();
-    } else {
-      for (Notifier *n = timerQueueHead; n != nullptr; n = n->m_nextEvent) {
-        if (n->m_nextEvent == this) {
-          // this element is the next element from *n from the queue
-          n->m_nextEvent = this->m_nextEvent;  // point around this one
-        }
-      }
-    }
-  }
+  notifier->m_handlerMutex.lock();
+  notifier->m_processMutex.unlock();
+
+  if (handler) handler();
+  notifier->m_handlerMutex.unlock();
 }
 
 /**
@@ -220,43 +76,41 @@
  * @param delay Seconds to wait before the handler is called.
  */
 void Notifier::StartSingle(double delay) {
-  std::lock_guard<priority_recursive_mutex> sync(queueMutex);
+  std::lock_guard<priority_mutex> sync(m_processMutex);
   m_periodic = false;
   m_period = delay;
-  DeleteFromQueue();
-  InsertInQueue(false);
+  m_expirationTime = GetClock() + m_period;
+  UpdateAlarm();
 }
 
 /**
  * Register for periodic event notification.
  * A timer event is queued for periodic event notification. Each time the
- * interrupt
- * occurs, the event will be immediately requeued for the same time interval.
+ * interrupt occurs, the event will be immediately requeued for the same time
+ * interval.
  * @param period Period in seconds to call the handler starting one period after
  * the call to this method.
  */
 void Notifier::StartPeriodic(double period) {
-  std::lock_guard<priority_recursive_mutex> sync(queueMutex);
+  std::lock_guard<priority_mutex> sync(m_processMutex);
   m_periodic = true;
   m_period = period;
-  DeleteFromQueue();
-  InsertInQueue(false);
+  m_expirationTime = GetClock() + m_period;
+  UpdateAlarm();
 }
 
 /**
  * Stop timer events from occuring.
  * Stop any repeating timer events from occuring. This will also remove any
- * single
- * notification events from the queue.
+ * single notification events from the queue.
  * If a timer-based call to the registered handler is in progress, this function
- * will
- * block until the handler call is complete.
+ * will block until the handler call is complete.
  */
 void Notifier::Stop() {
-  {
-    std::lock_guard<priority_recursive_mutex> sync(queueMutex);
-    DeleteFromQueue();
-  }
+  int32_t status = 0;
+  stopNotifierAlarm(m_notifier, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
   // Wait for a currently executing handler to complete before returning from
   // Stop()
   std::lock_guard<priority_mutex> sync(m_handlerMutex);
diff --git a/wpilibc/Athena/src/PIDController.cpp b/wpilibc/Athena/src/PIDController.cpp
index fdbbb5a..c8fb63f 100644
--- a/wpilibc/Athena/src/PIDController.cpp
+++ b/wpilibc/Athena/src/PIDController.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "PIDController.h"
@@ -55,7 +55,7 @@
 void PIDController::Initialize(float Kp, float Ki, float Kd, float Kf,
                                PIDSource *source, PIDOutput *output,
                                float period) {
-  m_controlLoop = std::make_unique<Notifier>(PIDController::CallCalculate, this);
+  m_controlLoop = std::make_unique<Notifier>(&PIDController::Calculate, this);
 
   m_P = Kp;
   m_I = Ki;
@@ -67,6 +67,7 @@
   m_period = period;
 
   m_controlLoop->StartPeriodic(m_period);
+  m_setpointTimer.Start();
 
   static int32_t instances = 0;
   instances++;
@@ -78,24 +79,8 @@
 }
 
 /**
- * Call the Calculate method as a non-static method. This avoids having to
- * prepend
- * all local variables in that method with the class pointer. This way the
- * "this"
- * pointer will be set up and class variables can be called more easily.
- * This method is static and called by the Notifier class.
- * @param controller the address of the PID controller object to use in the
- * background loop
- */
-void PIDController::CallCalculate(void *controller) {
-  PIDController *control = (PIDController *)controller;
-  control->Calculate();
-}
-
-/**
  * Read the input, calculate the output accordingly, and write to the output.
- * This should only be called by the Notifier indirectly through CallCalculate
- * and is created during initialization.
+ * This should only be called by the Notifier.
  */
 void PIDController::Calculate() {
   bool enabled;
@@ -103,7 +88,7 @@
   PIDOutput *pidOutput;
 
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     pidInput = m_pidInput;
     pidOutput = m_pidOutput;
     enabled = m_enabled;
@@ -113,7 +98,7 @@
   if (pidOutput == nullptr) return;
 
   if (enabled) {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     float input = pidInput->PIDGet();
     float result;
     PIDOutput *pidOutput;
@@ -142,7 +127,7 @@
         }
       }
 
-      m_result = m_D * m_error + m_P * m_totalError + m_setpoint * m_F;
+      m_result = m_D * m_error + m_P * m_totalError + CalculateFeedForward();
     }
     else {
       if (m_I != 0) {
@@ -158,9 +143,9 @@
       }
 
       m_result = m_P * m_error + m_I * m_totalError +
-                 m_D * (m_prevInput - input) + m_setpoint * m_F;
+                 m_D * (m_error - m_prevError) + CalculateFeedForward();
     }
-    m_prevInput = input;
+    m_prevError = m_error;
 
     if (m_result > m_maximumOutput)
       m_result = m_maximumOutput;
@@ -184,6 +169,33 @@
 }
 
 /**
+ * Calculate the feed forward term
+ *
+ * Both of the provided feed forward calculations are velocity feed forwards.
+ * If a different feed forward calculation is desired, the user can override
+ * this function and provide his or her own. This function  does no
+ * synchronization because the PIDController class only calls it in synchronized
+ * code, so be careful if calling it oneself.
+ *
+ * If a velocity PID controller is being used, the F term should be set to 1
+ * over the maximum setpoint for the output. If a position PID controller is
+ * being used, the F term should be set to 1 over the maximum speed for the
+ * output measured in setpoint units per this controller's update period (see
+ * the default period in this class's constructor).
+ */
+double PIDController::CalculateFeedForward() {
+  if (m_pidInput->GetPIDSourceType() == PIDSourceType::kRate) {
+    return m_F * GetSetpoint();
+  }
+  else {
+    double temp = m_F * GetDeltaSetpoint();
+    m_prevSetpoint = m_setpoint;
+    m_setpointTimer.Reset();
+    return temp;
+  }
+}
+
+/**
  * Set the PID Controller gain parameters.
  * Set the proportional, integral, and differential coefficients.
  * @param p Proportional coefficient
@@ -192,7 +204,7 @@
  */
 void PIDController::SetPID(double p, double i, double d) {
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     m_P = p;
     m_I = i;
     m_D = d;
@@ -215,7 +227,7 @@
  */
 void PIDController::SetPID(double p, double i, double d, double f) {
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     m_P = p;
     m_I = i;
     m_D = d;
@@ -235,7 +247,7 @@
  * @return proportional coefficient
  */
 double PIDController::GetP() const {
-  std::lock_guard<priority_mutex> sync(m_mutex);
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
   return m_P;
 }
 
@@ -244,7 +256,7 @@
  * @return integral coefficient
  */
 double PIDController::GetI() const {
-  std::lock_guard<priority_mutex> sync(m_mutex);
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
   return m_I;
 }
 
@@ -253,7 +265,7 @@
  * @return differential coefficient
  */
 double PIDController::GetD() const {
-  std::lock_guard<priority_mutex> sync(m_mutex);
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
   return m_D;
 }
 
@@ -262,7 +274,7 @@
  * @return Feed forward coefficient
  */
 double PIDController::GetF() const {
-  std::lock_guard<priority_mutex> sync(m_mutex);
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
   return m_F;
 }
 
@@ -272,7 +284,7 @@
  * @return the latest calculated output
  */
 float PIDController::Get() const {
-  std::lock_guard<priority_mutex> sync(m_mutex);
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
   return m_result;
 }
 
@@ -284,7 +296,7 @@
  * @param continuous Set to true turns on continuous, false turns off continuous
  */
 void PIDController::SetContinuous(bool continuous) {
-  std::lock_guard<priority_mutex> sync(m_mutex);
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
   m_continuous = continuous;
 }
 
@@ -296,7 +308,7 @@
  */
 void PIDController::SetInputRange(float minimumInput, float maximumInput) {
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     m_minimumInput = minimumInput;
     m_maximumInput = maximumInput;
   }
@@ -312,7 +324,7 @@
  */
 void PIDController::SetOutputRange(float minimumOutput, float maximumOutput) {
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     m_minimumOutput = minimumOutput;
     m_maximumOutput = maximumOutput;
   }
@@ -325,7 +337,8 @@
  */
 void PIDController::SetSetpoint(float setpoint) {
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+
     if (m_maximumInput > m_minimumInput) {
       if (setpoint > m_maximumInput)
         m_setpoint = m_maximumInput;
@@ -351,18 +364,27 @@
  * @return the current setpoint
  */
 double PIDController::GetSetpoint() const {
-  std::lock_guard<priority_mutex> sync(m_mutex);
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
   return m_setpoint;
 }
 
 /**
+ * Returns the change in setpoint over time of the PIDController
+ * @return the change in setpoint over time
+ */
+double PIDController::GetDeltaSetpoint() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get();
+}
+
+/**
  * Returns the current difference of the input from the setpoint
  * @return the current error
  */
 float PIDController::GetError() const {
   double pidInput;
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     pidInput = m_pidInput->PIDGet();
   }
   return GetSetpoint() - pidInput;
@@ -391,7 +413,7 @@
 float PIDController::GetAvgError() const {
   float avgError = 0;
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     // Don't divide by zero.
     if (m_buf.size()) avgError = m_bufTotal / m_buf.size();
   }
@@ -405,7 +427,7 @@
  */
 void PIDController::SetTolerance(float percent) {
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     m_toleranceType = kPercentTolerance;
     m_tolerance = percent;
   }
@@ -418,7 +440,7 @@
  */
 void PIDController::SetPercentTolerance(float percent) {
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     m_toleranceType = kPercentTolerance;
     m_tolerance = percent;
   }
@@ -431,7 +453,7 @@
  */
 void PIDController::SetAbsoluteTolerance(float absTolerance) {
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     m_toleranceType = kAbsoluteTolerance;
     m_tolerance = absTolerance;
   }
@@ -447,6 +469,7 @@
  * @param bufLength Number of previous cycles to average. Defaults to 1.
  */
 void PIDController::SetToleranceBuffer(unsigned bufLength) {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
   m_bufLength = bufLength;
 
   // Cut the buffer down to size if needed.
@@ -464,11 +487,12 @@
  * setpoint.
  * Ideally it should be based on being within the tolerance for some period of
  * time.
+ * This will return false until at least one input value has been computed.
  */
 bool PIDController::OnTarget() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  if (m_buf.size() == 0) return false;
   double error = GetAvgError();
-
-  std::lock_guard<priority_mutex> sync(m_mutex);
   switch (m_toleranceType) {
     case kPercentTolerance:
       return fabs(error) < m_tolerance / 100 * (m_maximumInput - m_minimumInput);
@@ -488,7 +512,7 @@
  */
 void PIDController::Enable() {
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     m_enabled = true;
   }
 
@@ -502,7 +526,7 @@
  */
 void PIDController::Disable() {
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     m_pidOutput->PIDWrite(0);
     m_enabled = false;
   }
@@ -516,7 +540,7 @@
  * Return true if PIDController is enabled.
  */
 bool PIDController::IsEnabled() const {
-  std::lock_guard<priority_mutex> sync(m_mutex);
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
   return m_enabled;
 }
 
@@ -526,8 +550,8 @@
 void PIDController::Reset() {
   Disable();
 
-  std::lock_guard<priority_mutex> sync(m_mutex);
-  m_prevInput = 0;
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  m_prevError = 0;
   m_totalError = 0;
   m_result = 0;
 }
diff --git a/wpilibc/Athena/src/PWM.cpp b/wpilibc/Athena/src/PWM.cpp
index 6b3b4b7..76d10cc 100644
--- a/wpilibc/Athena/src/PWM.cpp
+++ b/wpilibc/Athena/src/PWM.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "PWM.h"
diff --git a/wpilibc/Athena/src/PowerDistributionPanel.cpp b/wpilibc/Athena/src/PowerDistributionPanel.cpp
index fb428cf..8378e2f 100644
--- a/wpilibc/Athena/src/PowerDistributionPanel.cpp
+++ b/wpilibc/Athena/src/PowerDistributionPanel.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "PowerDistributionPanel.h"
diff --git a/wpilibc/Athena/src/Preferences.cpp b/wpilibc/Athena/src/Preferences.cpp
index 95f6a4a..60a5520 100644
--- a/wpilibc/Athena/src/Preferences.cpp
+++ b/wpilibc/Athena/src/Preferences.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Preferences.h"
diff --git a/wpilibc/Athena/src/Relay.cpp b/wpilibc/Athena/src/Relay.cpp
index 17f0ef8..5290d8b 100644
--- a/wpilibc/Athena/src/Relay.cpp
+++ b/wpilibc/Athena/src/Relay.cpp
@@ -1,9 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. 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 $(WIND_BASE)/WPILib.  */
+/* Copyright (c) FIRST 2008-2016. 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 "Relay.h"
diff --git a/wpilibc/Athena/src/RobotBase.cpp b/wpilibc/Athena/src/RobotBase.cpp
index 2bd1d13..a1087c0 100644
--- a/wpilibc/Athena/src/RobotBase.cpp
+++ b/wpilibc/Athena/src/RobotBase.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "RobotBase.h"
@@ -27,6 +27,7 @@
 RobotBase &RobotBase::getInstance() { return *m_instance; }
 
 void RobotBase::robotSetup(RobotBase *robot) {
+  printf("\n********** Robot program starting **********\n");
   robot->StartCompetition();
 }
 
@@ -49,12 +50,13 @@
   RobotBase::setInstance(this);
 
   NetworkTable::SetNetworkIdentity("Robot");
+  NetworkTable::SetPersistentFilename("/home/lvuser/networktables.ini");
 
   FILE *file = nullptr;
   file = fopen("/tmp/frc_versions/FRC_Lib_Version.ini", "w");
 
   if (file != nullptr) {
-    fputs("2016 C++ Beta5.0", file);
+    fputs("2016 C++ Release 4", file);
     fclose(file);
   }
 }
diff --git a/wpilibc/Athena/src/RobotDrive.cpp b/wpilibc/Athena/src/RobotDrive.cpp
index c1353e9..69184e3 100644
--- a/wpilibc/Athena/src/RobotDrive.cpp
+++ b/wpilibc/Athena/src/RobotDrive.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "RobotDrive.h"
@@ -745,9 +745,9 @@
 }
 
 void RobotDrive::StopMotor() {
-  if (m_frontLeftMotor != nullptr) m_frontLeftMotor->Disable();
-  if (m_frontRightMotor != nullptr) m_frontRightMotor->Disable();
-  if (m_rearLeftMotor != nullptr) m_rearLeftMotor->Disable();
-  if (m_rearRightMotor != nullptr) m_rearRightMotor->Disable();
+  if (m_frontLeftMotor != nullptr) m_frontLeftMotor->StopMotor();
+  if (m_frontRightMotor != nullptr) m_frontRightMotor->StopMotor();
+  if (m_rearLeftMotor != nullptr) m_rearLeftMotor->StopMotor();
+  if (m_rearRightMotor != nullptr) m_rearRightMotor->StopMotor();
   m_safetyHelper->Feed();
 }
diff --git a/wpilibc/Athena/src/SD540.cpp b/wpilibc/Athena/src/SD540.cpp
new file mode 100644
index 0000000..9d2ad1e
--- /dev/null
+++ b/wpilibc/Athena/src/SD540.cpp
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2016. 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 "SD540.h"
+
+#include "LiveWindow/LiveWindow.h"
+
+/**
+ * Note that the SD540 uses the following bounds for PWM values. These values
+ * should work reasonably well for
+ * most controllers, but if users experience issues such as asymmetric behavior
+ * around
+ * the deadband or inability to saturate the controller in either direction,
+ * calibration is recommended.
+ * The calibration procedure can be found in the SD540 User Manual available
+ * from Mindsensors.
+ *
+ *   2.05ms = full "forward"
+ *   1.55ms = the "high end" of the deadband range
+ *   1.50ms = center of the deadband range (off)
+ *   1.44ms = the "low end" of the deadband range
+ *   0.94ms = full "reverse"
+ */
+
+/**
+ * Constructor for a SD540
+ * @param channel The PWM channel that the SD540 is attached to. 0-9 are
+ * on-board, 10-19 are on the MXP port
+ */
+SD540::SD540(uint32_t channel) : SafePWM(channel) {
+  SetBounds(2.05, 1.55, 1.50, 1.44, .94);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetRaw(m_centerPwm);
+  SetZeroLatch();
+
+  HALReport(HALUsageReporting::kResourceType_MindsensorsSD540, GetChannel());
+  LiveWindow::GetInstance()->AddActuator("SD540", GetChannel(), this);
+}
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ * @param syncGroup Unused interface.
+ */
+void SD540::Set(float speed, uint8_t syncGroup) {
+  SetSpeed(m_isInverted ? -speed : speed);
+}
+
+/**
+ * Get the recently set value of the PWM.
+ *
+ * @return The most recently set value for the PWM between -1.0 and 1.0.
+ */
+float SD540::Get() const { return GetSpeed(); }
+
+/**
+ * Common interface for inverting direction of a speed controller.
+ * @param isInverted The state of inversion, true is inverted.
+ */
+void SD540::SetInverted(bool isInverted) { m_isInverted = isInverted; }
+
+/**
+ * Common interface for the inverting direction of a speed controller.
+ *
+ * @return isInverted The state of inversion, true is inverted.
+ *
+ */
+bool SD540::GetInverted() const { return m_isInverted; }
+
+/**
+ * Common interface for disabling a motor.
+ */
+void SD540::Disable() { SetRaw(kPwmDisabled); }
+
+/**
+ * Write out the PID value as seen in the PIDOutput base object.
+ *
+ * @param output Write out the PWM value as was found in the PIDController
+ */
+void SD540::PIDWrite(float output) { Set(output); }
+
+/**
+ * Common interface to stop the motor until Set is called again.
+ */
+void SD540::StopMotor() { this->SafePWM::StopMotor(); }
diff --git a/wpilibc/Athena/src/SPI.cpp b/wpilibc/Athena/src/SPI.cpp
index a470597..f0af9e7 100644
--- a/wpilibc/Athena/src/SPI.cpp
+++ b/wpilibc/Athena/src/SPI.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "SPI.h"
diff --git a/wpilibc/Athena/src/SafePWM.cpp b/wpilibc/Athena/src/SafePWM.cpp
index 801e3ee..d400ce4 100644
--- a/wpilibc/Athena/src/SafePWM.cpp
+++ b/wpilibc/Athena/src/SafePWM.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "SafePWM.h"
diff --git a/wpilibc/Athena/src/SampleRobot.cpp b/wpilibc/Athena/src/SampleRobot.cpp
index 37b134f..3cd3cad 100644
--- a/wpilibc/Athena/src/SampleRobot.cpp
+++ b/wpilibc/Athena/src/SampleRobot.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "SampleRobot.h"
diff --git a/wpilibc/Athena/src/SensorBase.cpp b/wpilibc/Athena/src/SensorBase.cpp
index 05f9f4f..984ad57 100644
--- a/wpilibc/Athena/src/SensorBase.cpp
+++ b/wpilibc/Athena/src/SensorBase.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "SensorBase.h"
diff --git a/wpilibc/Athena/src/SerialPort.cpp b/wpilibc/Athena/src/SerialPort.cpp
index c4e259a..1544a62 100644
--- a/wpilibc/Athena/src/SerialPort.cpp
+++ b/wpilibc/Athena/src/SerialPort.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "SerialPort.h"
diff --git a/wpilibc/Athena/src/Servo.cpp b/wpilibc/Athena/src/Servo.cpp
index 4300cc4..6c8c3b0 100644
--- a/wpilibc/Athena/src/Servo.cpp
+++ b/wpilibc/Athena/src/Servo.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Servo.h"
diff --git a/wpilibc/Athena/src/Solenoid.cpp b/wpilibc/Athena/src/Solenoid.cpp
index 5174f98..1192d26 100644
--- a/wpilibc/Athena/src/Solenoid.cpp
+++ b/wpilibc/Athena/src/Solenoid.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Solenoid.h"
diff --git a/wpilibc/Athena/src/SolenoidBase.cpp b/wpilibc/Athena/src/SolenoidBase.cpp
index dfdf1eb..254d144 100644
--- a/wpilibc/Athena/src/SolenoidBase.cpp
+++ b/wpilibc/Athena/src/SolenoidBase.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "SolenoidBase.h"
diff --git a/wpilibc/Athena/src/Spark.cpp b/wpilibc/Athena/src/Spark.cpp
new file mode 100644
index 0000000..3517122
--- /dev/null
+++ b/wpilibc/Athena/src/Spark.cpp
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2016. 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 "Spark.h"
+
+#include "LiveWindow/LiveWindow.h"
+
+/**
+ * Note that the Spark uses the following bounds for PWM values. These values
+ * should work reasonably well for
+ * most controllers, but if users experience issues such as asymmetric behavior
+ * around
+ * the deadband or inability to saturate the controller in either direction,
+ * calibration is recommended.
+ * The calibration procedure can be found in the Spark User Manual available
+ * from REV Robotics.
+ *
+ *   2.003ms = full "forward"
+ *   1.55ms = the "high end" of the deadband range
+ *   1.50ms = center of the deadband range (off)
+ *   1.46ms = the "low end" of the deadband range
+ *   0.999ms = full "reverse"
+ */
+
+/**
+ * Constructor for a Spark
+ * @param channel The PWM channel that the Spark is attached to. 0-9 are
+ * on-board, 10-19 are on the MXP port
+ */
+Spark::Spark(uint32_t channel) : SafePWM(channel) {
+  SetBounds(2.003, 1.55, 1.50, 1.46, .999);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetRaw(m_centerPwm);
+  SetZeroLatch();
+
+  HALReport(HALUsageReporting::kResourceType_RevSPARK, GetChannel());
+  LiveWindow::GetInstance()->AddActuator("Spark", GetChannel(), this);
+}
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ * @param syncGroup Unused interface.
+ */
+void Spark::Set(float speed, uint8_t syncGroup) {
+  SetSpeed(m_isInverted ? -speed : speed);
+}
+
+/**
+ * Get the recently set value of the PWM.
+ *
+ * @return The most recently set value for the PWM between -1.0 and 1.0.
+ */
+float Spark::Get() const { return GetSpeed(); }
+
+/**
+ * Common interface for inverting direction of a speed controller.
+ * @param isInverted The state of inversion, true is inverted.
+ */
+void Spark::SetInverted(bool isInverted) { m_isInverted = isInverted; }
+
+/**
+ * Common interface for the inverting direction of a speed controller.
+ *
+ * @return isInverted The state of inversion, true is inverted.
+ *
+ */
+bool Spark::GetInverted() const { return m_isInverted; }
+
+/**
+ * Common interface for disabling a motor.
+ */
+void Spark::Disable() { SetRaw(kPwmDisabled); }
+
+/**
+ * Write out the PID value as seen in the PIDOutput base object.
+ *
+ * @param output Write out the PWM value as was found in the PIDController
+ */
+void Spark::PIDWrite(float output) { Set(output); }
+
+/**
+ * Common interface to stop the motor until Set is called again.
+ */
+void Spark::StopMotor() { this->SafePWM::StopMotor(); }
\ No newline at end of file
diff --git a/wpilibc/Athena/src/Talon.cpp b/wpilibc/Athena/src/Talon.cpp
index dc1cf3b..64f9db8 100644
--- a/wpilibc/Athena/src/Talon.cpp
+++ b/wpilibc/Athena/src/Talon.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Talon.h"
@@ -82,3 +82,8 @@
  * @param output Write out the PWM value as was found in the PIDController
  */
 void Talon::PIDWrite(float output) { Set(output); }
+
+/**
+ * Common interface to stop the motor until Set is called again.
+ */
+void Talon::StopMotor() { this->SafePWM::StopMotor(); }
diff --git a/wpilibc/Athena/src/TalonSRX.cpp b/wpilibc/Athena/src/TalonSRX.cpp
index 07438c4..e06f8ca 100644
--- a/wpilibc/Athena/src/TalonSRX.cpp
+++ b/wpilibc/Athena/src/TalonSRX.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "TalonSRX.h"
@@ -79,3 +79,8 @@
  * @param output Write out the PWM value as was found in the PIDController
  */
 void TalonSRX::PIDWrite(float output) { Set(output); }
+
+/**
+ * Common interface to stop the motor until Set is called again.
+ */
+void TalonSRX::StopMotor() { this->SafePWM::StopMotor(); }
\ No newline at end of file
diff --git a/wpilibc/Athena/src/Task.cpp b/wpilibc/Athena/src/Task.cpp
index 9157dca..5aa795b 100644
--- a/wpilibc/Athena/src/Task.cpp
+++ b/wpilibc/Athena/src/Task.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Task.h"
diff --git a/wpilibc/Athena/src/Timer.cpp b/wpilibc/Athena/src/Timer.cpp
index 53631e7..850b6be 100644
--- a/wpilibc/Athena/src/Timer.cpp
+++ b/wpilibc/Athena/src/Timer.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Timer.h"
diff --git a/wpilibc/Athena/src/USBCamera.cpp b/wpilibc/Athena/src/USBCamera.cpp
index 0c57d85..3f682a2 100644
--- a/wpilibc/Athena/src/USBCamera.cpp
+++ b/wpilibc/Athena/src/USBCamera.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "USBCamera.h"
 
 #include "Utility.h"
diff --git a/wpilibc/Athena/src/Ultrasonic.cpp b/wpilibc/Athena/src/Ultrasonic.cpp
index ba25a04..183e1ce 100644
--- a/wpilibc/Athena/src/Ultrasonic.cpp
+++ b/wpilibc/Athena/src/Ultrasonic.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Ultrasonic.h"
@@ -15,18 +15,17 @@
 #include "WPIErrors.h"
 #include "LiveWindow/LiveWindow.h"
 
-constexpr double
-    Ultrasonic::kPingTime;  ///< Time (sec) for the ping trigger pulse.
-const uint32_t Ultrasonic::kPriority;  ///< Priority that the ultrasonic round
-                                       ///robin task runs.
-constexpr double
-    Ultrasonic::kMaxUltrasonicTime;  ///< Max time (ms) between readings.
+// Time (sec) for the ping trigger pulse.
+constexpr double Ultrasonic::kPingTime;
+// Priority that the ultrasonic round robin task runs.
+const uint32_t Ultrasonic::kPriority;
+// Max time (ms) between readings.
+constexpr double Ultrasonic::kMaxUltrasonicTime;
 constexpr double Ultrasonic::kSpeedOfSoundInchesPerSec;
-Ultrasonic *Ultrasonic::m_firstSensor =
-    nullptr;  // head of the ultrasonic sensor list
 Task Ultrasonic::m_task;
-std::atomic<bool> Ultrasonic::m_automaticEnabled{false}; // automatic round robin mode
-priority_mutex Ultrasonic::m_mutex;
+// automatic round robin mode
+std::atomic<bool> Ultrasonic::m_automaticEnabled{false};
+std::set<Ultrasonic*> Ultrasonic::m_sensors;
 
 /**
  * Background task that goes through the list of ultrasonic sensors and pings
@@ -34,20 +33,21 @@
  * is configured to read the timing of the returned echo pulse.
  *
  * DANGER WILL ROBINSON, DANGER WILL ROBINSON:
- * This code runs as a task and assumes that none of the ultrasonic sensors will
- * change while it's
- * running. If one does, then this will certainly break. Make sure to disable
- * automatic mode before changing
- * anything with the sensors!!
+ * This code runs as a task and assumes that none of the ultrasonic sensors
+ * will change while it's running. Make sure to disable automatic mode before
+ * touching the list.
  */
 void Ultrasonic::UltrasonicChecker() {
-  Ultrasonic *u = nullptr;
   while (m_automaticEnabled) {
-    if (u == nullptr) u = m_firstSensor;
-    if (u == nullptr) return;
-    if (u->IsEnabled()) u->m_pingChannel->Pulse(kPingTime);  // do the ping
-    u = u->m_nextSensor;
-    Wait(0.1);  // wait for ping to return
+    for (auto& sensor : m_sensors) {
+      if (!m_automaticEnabled) break;
+
+      if (sensor->IsEnabled()) {
+        sensor->m_pingChannel->Pulse(kPingTime); // do the ping
+      }
+
+      Wait(0.1); // wait for ping to return
+    }
   }
 }
 
@@ -65,11 +65,7 @@
   bool originalMode = m_automaticEnabled;
   SetAutomaticMode(false);     // kill task when adding a new sensor
   // link this instance on the list
-  {
-    std::lock_guard<priority_mutex> lock(m_mutex);
-    m_nextSensor = m_firstSensor;
-    m_firstSensor = this;
-  }
+  m_sensors.insert(this);
 
   m_counter.SetMaxPeriod(1.0);
   m_counter.SetSemiPeriodMode(true);
@@ -122,7 +118,6 @@
       m_counter(m_echoChannel) {
   if (pingChannel == nullptr || echoChannel == nullptr) {
     wpi_setWPIError(NullParameter);
-    m_nextSensor = nullptr;
     m_units = units;
     return;
   }
@@ -180,26 +175,13 @@
 Ultrasonic::~Ultrasonic() {
   bool wasAutomaticMode = m_automaticEnabled;
   SetAutomaticMode(false);
-  wpi_assert(m_firstSensor != nullptr);
 
-  {
-    std::lock_guard<priority_mutex> lock(m_mutex);
-    if (this == m_firstSensor) {
-      m_firstSensor = m_nextSensor;
-      if (m_firstSensor == nullptr) {
-        SetAutomaticMode(false);
-      }
-    } else {
-      wpi_assert(m_firstSensor->m_nextSensor != nullptr);
-      for (Ultrasonic *s = m_firstSensor; s != nullptr; s = s->m_nextSensor) {
-        if (this == s->m_nextSensor) {
-          s->m_nextSensor = s->m_nextSensor->m_nextSensor;
-          break;
-        }
-      }
-    }
+  // No synchronization needed because the background task is stopped.
+  m_sensors.erase(this);
+
+  if (!m_sensors.empty() && wasAutomaticMode) {
+    SetAutomaticMode(true);
   }
-  if (m_firstSensor != nullptr && wasAutomaticMode) SetAutomaticMode(true);
 }
 
 /**
@@ -218,15 +200,15 @@
   if (enabling == m_automaticEnabled) return;  // ignore the case of no change
 
   m_automaticEnabled = enabling;
+
   if (enabling) {
-    // enabling automatic mode.
-    // Clear all the counters so no data is valid
-    for (Ultrasonic *u = m_firstSensor; u != nullptr; u = u->m_nextSensor) {
-      u->m_counter.Reset();
+    /* Clear all the counters so no data is valid. No synchronization is needed
+     * because the background task is stopped.
+     */
+    for (auto& sensor : m_sensors) {
+      sensor->m_counter.Reset();
     }
-    // Start round robin task
-    wpi_assert(m_task.Verify() ==
-               false);  // should be false since was previously disabled
+
     m_task = Task("UltrasonicChecker", &Ultrasonic::UltrasonicChecker);
 
     // TODO: Currently, lvuser does not have permissions to set task priorities.
@@ -234,27 +216,25 @@
     // Ultrasonic::SetAutomicMode().
     //m_task.SetPriority(kPriority);
   } else {
-    // disabling automatic mode. Wait for background task to stop running.
-    while (m_task.Verify())
-      Wait(0.15);  // just a little longer than the ping time for round-robin to
-                   // stop
-
-    // clear all the counters (data now invalid) since automatic mode is stopped
-    for (Ultrasonic *u = m_firstSensor; u != nullptr; u = u->m_nextSensor) {
-      u->m_counter.Reset();
-    }
-    m_automaticEnabled = false;
+    // Wait for background task to stop running
     m_task.join();
+
+    /* Clear all the counters (data now invalid) since automatic mode is
+     * disabled. No synchronization is needed because the background task is
+     * stopped.
+     */
+    for (auto& sensor : m_sensors) {
+      sensor->m_counter.Reset();
+    }
   }
 }
 
 /**
  * Single ping to ultrasonic sensor.
  * Send out a single ping to the ultrasonic sensor. This only works if automatic
- * (round robin)
- * mode is disabled. A single ping is sent out, and the counter should count the
- * semi-period
- * when it comes in. The counter is reset to make the current value invalid.
+ * (round robin) mode is disabled. A single ping is sent out, and the counter
+ * should count the semi-period when it comes in. The counter is reset to make
+ * the current value invalid.
  */
 void Ultrasonic::Ping() {
   wpi_assert(!m_automaticEnabled);
@@ -275,9 +255,8 @@
 /**
  * Get the range in inches from the ultrasonic sensor.
  * @return double Range in inches of the target returned from the ultrasonic
- * sensor. If there is
- * no valid value yet, i.e. at least one measurement hasn't completed, then
- * return 0.
+ * sensor. If there is no valid value yet, i.e. at least one measurement hasn't
+ * completed, then return 0.
  */
 double Ultrasonic::GetRangeInches() const {
   if (IsRangeValid())
@@ -291,7 +270,7 @@
  * @return double Range in millimeters of the target returned by the ultrasonic
  * sensor.
  * If there is no valid value yet, i.e. at least one measurement hasn't
- * complted, then return 0.
+ * completed, then return 0.
  */
 double Ultrasonic::GetRangeMM() const { return GetRangeInches() * 25.4; }
 
diff --git a/wpilibc/Athena/src/Utility.cpp b/wpilibc/Athena/src/Utility.cpp
index 5998f0f..d675e60 100644
--- a/wpilibc/Athena/src/Utility.cpp
+++ b/wpilibc/Athena/src/Utility.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Utility.h"
@@ -29,11 +29,13 @@
                      const char *message, const char *fileName,
                      uint32_t lineNumber, const char *funcName) {
   if (!conditionValue) {
+    std::stringstream locStream;
+    locStream << funcName << " [";
+    locStream << basename(fileName) << ":" << lineNumber << "]";
+
     std::stringstream errorStream;
 
     errorStream << "Assertion \"" << conditionText << "\" ";
-    errorStream << "on line " << lineNumber << " ";
-    errorStream << "of " << basename(fileName) << " ";
 
     if (message[0] != '\0') {
       errorStream << "failed: " << message << std::endl;
@@ -41,13 +43,12 @@
       errorStream << "failed." << std::endl;
     }
 
-    errorStream << GetStackTrace(2);
-
+    std::string stack = GetStackTrace(2);
+    std::string location = locStream.str();
     std::string error = errorStream.str();
 
     // Print the error and send it to the DriverStation
-    std::cout << error << std::endl;
-    HALSetErrorData(error.c_str(), error.size(), 100);
+    HALSendError(1, 1, 0, error.c_str(), location.c_str(), stack.c_str(), 1);
   }
 
   return conditionValue;
@@ -65,12 +66,14 @@
                                  const char *fileName,
                                  uint32_t lineNumber,
                                  const char *funcName) {
+  std::stringstream locStream;
+  locStream << funcName << " [";
+  locStream << basename(fileName) << ":" << lineNumber << "]";
+
   std::stringstream errorStream;
 
   errorStream << "Assertion \"" << valueA << " " << equalityType << " "
               << valueB << "\" ";
-  errorStream << "on line " << lineNumber << " ";
-  errorStream << "of " << basename(fileName) << " ";
 
   if (message[0] != '\0') {
     errorStream << "failed: " << message << std::endl;
@@ -78,13 +81,12 @@
     errorStream << "failed." << std::endl;
   }
 
-  errorStream << GetStackTrace(3);
-
+  std::string trace = GetStackTrace(3);
+  std::string location = locStream.str();
   std::string error = errorStream.str();
 
   // Print the error and send it to the DriverStation
-  std::cout << error << std::endl;
-  HALSetErrorData(error.c_str(), error.size(), 100);
+  HALSendError(1, 1, 0, error.c_str(), location.c_str(), trace.c_str(), 1);
 }
 
 /**
@@ -156,9 +158,9 @@
  * @return The current time in microseconds according to the FPGA (since FPGA
  * reset).
  */
-uint32_t GetFPGATime() {
+uint64_t GetFPGATime() {
   int32_t status = 0;
-  uint32_t time = getFPGATime(&status);
+  uint64_t time = getFPGATime(&status);
   wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
   return time;
 }
diff --git a/wpilibc/Athena/src/Victor.cpp b/wpilibc/Athena/src/Victor.cpp
index f8a4970..81c863c 100644
--- a/wpilibc/Athena/src/Victor.cpp
+++ b/wpilibc/Athena/src/Victor.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Victor.h"
@@ -82,3 +82,8 @@
  * @param output Write out the PWM value as was found in the PIDController
  */
 void Victor::PIDWrite(float output) { Set(output); }
+
+/**
+ * Common interface to stop the motor until Set is called again.
+ */
+void Victor::StopMotor() { this->SafePWM::StopMotor(); }
\ No newline at end of file
diff --git a/wpilibc/Athena/src/VictorSP.cpp b/wpilibc/Athena/src/VictorSP.cpp
index ccbc163..57dddea 100644
--- a/wpilibc/Athena/src/VictorSP.cpp
+++ b/wpilibc/Athena/src/VictorSP.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "VictorSP.h"
@@ -86,3 +86,8 @@
  * @param output Write out the PWM value as was found in the PIDController
  */
 void VictorSP::PIDWrite(float output) { Set(output); }
+
+/**
+ * Common interface to stop the motor until Set is called again.
+ */
+void VictorSP::StopMotor() { this->SafePWM::StopMotor(); }
\ No newline at end of file
diff --git a/wpilibc/Athena/src/Vision/AxisCamera.cpp b/wpilibc/Athena/src/Vision/AxisCamera.cpp
index 990c68a..39dcf5b 100644
--- a/wpilibc/Athena/src/Vision/AxisCamera.cpp
+++ b/wpilibc/Athena/src/Vision/AxisCamera.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Vision/AxisCamera.h"
diff --git a/wpilibc/Athena/src/Vision/BaeUtilities.cpp b/wpilibc/Athena/src/Vision/BaeUtilities.cpp
index f09ec64..f1b13ee 100644
--- a/wpilibc/Athena/src/Vision/BaeUtilities.cpp
+++ b/wpilibc/Athena/src/Vision/BaeUtilities.cpp
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #include <stdio.h>
 #include <sys/types.h>
 #include <sys/stat.h>
diff --git a/wpilibc/Athena/src/Vision/BinaryImage.cpp b/wpilibc/Athena/src/Vision/BinaryImage.cpp
index ea14cbc..4a30a79 100644
--- a/wpilibc/Athena/src/Vision/BinaryImage.cpp
+++ b/wpilibc/Athena/src/Vision/BinaryImage.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Vision/BinaryImage.h"
diff --git a/wpilibc/Athena/src/Vision/ColorImage.cpp b/wpilibc/Athena/src/Vision/ColorImage.cpp
index bbbc242..ab37c0f 100644
--- a/wpilibc/Athena/src/Vision/ColorImage.cpp
+++ b/wpilibc/Athena/src/Vision/ColorImage.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Vision/ColorImage.h"
diff --git a/wpilibc/Athena/src/Vision/FrcError.cpp b/wpilibc/Athena/src/Vision/FrcError.cpp
index f0b4725..31b76be 100644
--- a/wpilibc/Athena/src/Vision/FrcError.cpp
+++ b/wpilibc/Athena/src/Vision/FrcError.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "nivision.h"
diff --git a/wpilibc/Athena/src/Vision/HSLImage.cpp b/wpilibc/Athena/src/Vision/HSLImage.cpp
index 5b114c4..c9cdd11 100644
--- a/wpilibc/Athena/src/Vision/HSLImage.cpp
+++ b/wpilibc/Athena/src/Vision/HSLImage.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Vision/HSLImage.h"
diff --git a/wpilibc/Athena/src/Vision/ImageBase.cpp b/wpilibc/Athena/src/Vision/ImageBase.cpp
index f35234a..9ef0a61 100644
--- a/wpilibc/Athena/src/Vision/ImageBase.cpp
+++ b/wpilibc/Athena/src/Vision/ImageBase.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Vision/ImageBase.h"
diff --git a/wpilibc/Athena/src/Vision/MonoImage.cpp b/wpilibc/Athena/src/Vision/MonoImage.cpp
index 90703c0..469182d 100644
--- a/wpilibc/Athena/src/Vision/MonoImage.cpp
+++ b/wpilibc/Athena/src/Vision/MonoImage.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Vision/MonoImage.h"
diff --git a/wpilibc/Athena/src/Vision/RGBImage.cpp b/wpilibc/Athena/src/Vision/RGBImage.cpp
index 5469122..92a305d 100644
--- a/wpilibc/Athena/src/Vision/RGBImage.cpp
+++ b/wpilibc/Athena/src/Vision/RGBImage.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Vision/RGBImage.h"
diff --git a/wpilibc/Athena/src/Vision/Threshold.cpp b/wpilibc/Athena/src/Vision/Threshold.cpp
index 2e17243..35887c1 100644
--- a/wpilibc/Athena/src/Vision/Threshold.cpp
+++ b/wpilibc/Athena/src/Vision/Threshold.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Vision/Threshold.h"
diff --git a/wpilibc/Athena/src/Vision/VisionAPI.cpp b/wpilibc/Athena/src/Vision/VisionAPI.cpp
index 163721d..4d9c7c1 100644
--- a/wpilibc/Athena/src/Vision/VisionAPI.cpp
+++ b/wpilibc/Athena/src/Vision/VisionAPI.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include <stdlib.h>
diff --git a/wpilibc/athena.gradle b/wpilibc/athena.gradle
index da49c5d..26bccfc 100644
--- a/wpilibc/athena.gradle
+++ b/wpilibc/athena.gradle
@@ -1,5 +1,7 @@
 defineNetworkTablesProperties()
 
+def ntSourceDir = "$buildDir/ntSources"
+
 model {
     components {
         wpilib_nonshared(NativeLibrarySpec) {
@@ -93,7 +95,6 @@
     }
 }
 
-
 // Add the hal static and shared libraries as a dependency
 project(':hal').tasks.whenTaskAdded { task ->
     if (task.name == 'hALAthenaStaticLibrary' || task.name == 'hALAthenaSharedLibrary') {
@@ -101,10 +102,72 @@
     }
 }
 
+if (checkDoxygen()) {
+
+    def ntSourcesDependency = project.dependencies.create('edu.wpi.first.wpilib.networktables.cpp:NetworkTables:3.0.0-SNAPSHOT:sources@zip')
+    def ntSourcesConfig = project.configurations.detachedConfiguration(ntSourcesDependency)
+    ntSourcesDependency.setTransitive(false)
+    def ntSources = ntSourcesConfig.singleFile
+
+    task unzipCppNtSources(type: Copy) {
+        description = 'Unzips the C++ networktables sources for doc creation'
+        group = 'WPILib'
+        from zipTree(ntSources)
+        exclude 'META-INF/*'
+        into ntSourceDir
+    }
+
+    doxygen {
+        def halLocation = '../hal'
+        source file("${project.shared}/src")
+        source file("${project.shared}/include")
+        source file("${project.athena}/src")
+        source file("${project.athena}/include")
+        source file("$ntSourceDir/src")
+        source file("$ntSourceDir/include")
+        source file("$halLocation/shared")
+        source file("$halLocation/Athena")
+        source file("$halLocation/include")
+        // template file('cpp.doxy')
+        exclude 'pcre.h'
+        exclude 'nivision.h'
+        project_name 'WPILibC++'
+        javadoc_autobrief true
+        recursive true
+        quiet true
+        warnings false
+        warn_if_doc_error false
+        warn_no_paramdoc false
+        warn_format false
+        warn_logfile false
+        warn_if_undocumented false
+        generate_latex false
+        html_timestamp true
+        generate_treeview true
+        outputDir file("$buildDir/docs")
+    }
+
+    doxygen.dependsOn unzipCppNtSources
+
+    task doxygenZip(type: Zip) {
+        description = 'Generates doxygen zip file for publishing'
+        group = 'WPILib'
+        dependsOn doxygen
+        from doxygen.outputDir
+    }
+}
+
 publishing {
     publications {
         wpilibc(MavenPublication) {
             artifact wpilibcZip
+
+            if (checkDoxygen()) {
+                artifact (doxygenZip) {
+                    classifier = 'doxygen'
+                }
+            }
+
             groupId 'edu.wpi.first.wpilib.cmake'
             artifactId 'cpp-root'
             version '1.0.0'
@@ -113,3 +176,7 @@
 
     setupWpilibRepo(it)
 }
+
+clean {
+    ntSourceDir
+}
diff --git a/wpilibc/build.gradle b/wpilibc/build.gradle
index b535cad..663e0ad 100644
--- a/wpilibc/build.gradle
+++ b/wpilibc/build.gradle
@@ -1,5 +1,8 @@
-apply plugin: 'cpp'
-apply plugin: 'maven-publish'
+plugins {
+    id 'org.ysb33r.doxygen' version '0.2'
+    id 'cpp'
+    id 'maven-publish'
+}
 
 evaluationDependsOn(':hal')
 
@@ -9,7 +12,7 @@
 
 // Attempts to execute the doxygen command. If there is no exception, doxygen exists, so return true. If there's
 // an IOException, it doesn't exist, so return false
-boolean checkDoxygen() {
+ext.checkDoxygen = {
     try {
         'doxygen'.execute()
         true
@@ -19,4 +22,8 @@
 }
 
 apply from: 'athena.gradle'
-apply from: 'simulation.gradle'
+
+if (hasProperty('makeSim')){
+    apply from: 'simulation.gradle'
+}
+
diff --git a/wpilibc/shared/include/Base.h b/wpilibc/shared/include/Base.h
index b1b806f..8bb8d4c 100644
--- a/wpilibc/shared/include/Base.h
+++ b/wpilibc/shared/include/Base.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 // MSVC 2013 doesn't allow "= default" on move constructors, but since we are
diff --git a/wpilibc/shared/include/Buttons/Button.h b/wpilibc/shared/include/Buttons/Button.h
index 8897569..3c77886 100644
--- a/wpilibc/shared/include/Buttons/Button.h
+++ b/wpilibc/shared/include/Buttons/Button.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __BUTTON_H__
diff --git a/wpilibc/shared/include/Buttons/ButtonScheduler.h b/wpilibc/shared/include/Buttons/ButtonScheduler.h
index 6222da7..f05274d 100644
--- a/wpilibc/shared/include/Buttons/ButtonScheduler.h
+++ b/wpilibc/shared/include/Buttons/ButtonScheduler.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __BUTTON_SCHEDULER_H__
diff --git a/wpilibc/shared/include/Buttons/CancelButtonScheduler.h b/wpilibc/shared/include/Buttons/CancelButtonScheduler.h
index ba3ba24..1c5d328 100644
--- a/wpilibc/shared/include/Buttons/CancelButtonScheduler.h
+++ b/wpilibc/shared/include/Buttons/CancelButtonScheduler.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __CANCEL_BUTTON_SCHEDULER_H__
diff --git a/wpilibc/shared/include/Buttons/HeldButtonScheduler.h b/wpilibc/shared/include/Buttons/HeldButtonScheduler.h
index 6dcd7a3..0a29105 100644
--- a/wpilibc/shared/include/Buttons/HeldButtonScheduler.h
+++ b/wpilibc/shared/include/Buttons/HeldButtonScheduler.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __HELD_BUTTON_SCHEDULER_H__
diff --git a/wpilibc/shared/include/Buttons/InternalButton.h b/wpilibc/shared/include/Buttons/InternalButton.h
index fdad6f9..6beea7b 100644
--- a/wpilibc/shared/include/Buttons/InternalButton.h
+++ b/wpilibc/shared/include/Buttons/InternalButton.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __INTERNAL_BUTTON_H__
diff --git a/wpilibc/shared/include/Buttons/JoystickButton.h b/wpilibc/shared/include/Buttons/JoystickButton.h
index 028efea..b1163f0 100644
--- a/wpilibc/shared/include/Buttons/JoystickButton.h
+++ b/wpilibc/shared/include/Buttons/JoystickButton.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __JOYSTICK_BUTTON_H__
diff --git a/wpilibc/shared/include/Buttons/NetworkButton.h b/wpilibc/shared/include/Buttons/NetworkButton.h
index 9dcba58..b534e00 100644
--- a/wpilibc/shared/include/Buttons/NetworkButton.h
+++ b/wpilibc/shared/include/Buttons/NetworkButton.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __NETWORK_BUTTON_H__
diff --git a/wpilibc/shared/include/Buttons/PressedButtonScheduler.h b/wpilibc/shared/include/Buttons/PressedButtonScheduler.h
index 62ff7a8..7a2e477 100644
--- a/wpilibc/shared/include/Buttons/PressedButtonScheduler.h
+++ b/wpilibc/shared/include/Buttons/PressedButtonScheduler.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __PRESSED_BUTTON_SCHEDULER_H__
diff --git a/wpilibc/shared/include/Buttons/ReleasedButtonScheduler.h b/wpilibc/shared/include/Buttons/ReleasedButtonScheduler.h
index 2a29981..a9ee3c8 100644
--- a/wpilibc/shared/include/Buttons/ReleasedButtonScheduler.h
+++ b/wpilibc/shared/include/Buttons/ReleasedButtonScheduler.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __RELEASED_BUTTON_SCHEDULER_H__
diff --git a/wpilibc/shared/include/Buttons/ToggleButtonScheduler.h b/wpilibc/shared/include/Buttons/ToggleButtonScheduler.h
index d79b456..4c2b5eb 100644
--- a/wpilibc/shared/include/Buttons/ToggleButtonScheduler.h
+++ b/wpilibc/shared/include/Buttons/ToggleButtonScheduler.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __TOGGLE_BUTTON_SCHEDULER_H__
diff --git a/wpilibc/shared/include/Buttons/Trigger.h b/wpilibc/shared/include/Buttons/Trigger.h
index 3a05995..719b072 100644
--- a/wpilibc/shared/include/Buttons/Trigger.h
+++ b/wpilibc/shared/include/Buttons/Trigger.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __TRIGGER_H__
diff --git a/wpilibc/shared/include/CircularBuffer.h b/wpilibc/shared/include/CircularBuffer.h
new file mode 100644
index 0000000..e4c7739
--- /dev/null
+++ b/wpilibc/shared/include/CircularBuffer.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015-2016. 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 <vector>
+#include <cstddef>
+
+/**
+ * This is a simple circular buffer so we don't need to "bucket brigade" copy
+ * old values.
+ */
+template <class T>
+class CircularBuffer {
+ public:
+  CircularBuffer(size_t size);
+
+  void PushFront(T value);
+  void PushBack(T value);
+  T PopFront();
+  T PopBack();
+  void Reset();
+
+  T& operator[](size_t index);
+  const T& operator[](size_t index) const;
+
+ private:
+  std::vector<T> m_data;
+
+  // Index of element at front of buffer
+  size_t m_front = 0;
+
+  // Number of elements used in buffer
+  size_t m_length = 0;
+
+  size_t ModuloInc(size_t index);
+  size_t ModuloDec(size_t index);
+};
+
+#include "CircularBuffer.inc"
diff --git a/wpilibc/shared/include/CircularBuffer.inc b/wpilibc/shared/include/CircularBuffer.inc
new file mode 100644
index 0000000..c42dea8
--- /dev/null
+++ b/wpilibc/shared/include/CircularBuffer.inc
@@ -0,0 +1,123 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015-2016. 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 <algorithm>
+
+template <class T>
+CircularBuffer<T>::CircularBuffer(size_t size) : m_data(size, 0) {}
+
+/**
+ * Push new value onto front of the buffer. The value at the back is overwritten
+ * if the buffer is full.
+ */
+template <class T>
+void CircularBuffer<T>::PushFront(T value) {
+  if (m_data.size() == 0) {
+    return;
+  }
+
+  m_front = ModuloDec(m_front);
+
+  m_data[m_front] = value;
+
+  if (m_length < m_data.size()) {
+    m_length++;
+  }
+}
+
+/**
+ * Push new value onto back of the buffer. The value at the front is overwritten
+ * if the buffer is full.
+ */
+template <class T>
+void CircularBuffer<T>::PushBack(T value) {
+  if (m_data.size() == 0) {
+    return;
+  }
+
+  m_data[(m_front + m_length) % m_data.size()] = value;
+
+  if (m_length < m_data.size()) {
+    m_length++;
+  } else {
+    // Increment front if buffer is full to maintain size
+    m_front = ModuloInc(m_front);
+  }
+}
+
+/**
+ * Pop value at front of buffer.
+ */
+template <class T>
+T CircularBuffer<T>::PopFront() {
+  // If there are no elements in the buffer, do nothing
+  if (m_length == 0) {
+    return 0;
+  }
+
+  T& temp = m_data[m_front];
+  m_front = ModuloInc(m_front);
+  m_length--;
+  return temp;
+}
+
+/**
+ * Pop value at back of buffer.
+ */
+template <class T>
+T CircularBuffer<T>::PopBack() {
+  // If there are no elements in the buffer, do nothing
+  if (m_length == 0) {
+    return 0;
+  }
+
+  m_length--;
+  return m_data[(m_front + m_length) % m_data.size()];
+}
+
+template <class T>
+void CircularBuffer<T>::Reset() {
+  std::fill(m_data.begin(), m_data.end(), 0);
+  m_front = 0;
+  m_length = 0;
+}
+
+/**
+ * Returns element at index starting from front of buffer.
+ */
+template <class T>
+T& CircularBuffer<T>::operator[](size_t index) {
+  return m_data[(m_front + index) % m_data.size()];
+}
+
+/**
+ * Returns element at index starting from front of buffer.
+ */
+template <class T>
+const T& CircularBuffer<T>::operator[](size_t index) const {
+  return m_data[(m_front + index) % m_data.size()];
+}
+
+/**
+ * Increment an index modulo the length of the m_data buffer
+ */
+template <class T>
+size_t CircularBuffer<T>::ModuloInc(size_t index) {
+  return (index + 1) % m_data.size();
+}
+
+/**
+ * Decrement an index modulo the length of the m_data buffer
+ */
+template <class T>
+size_t CircularBuffer<T>::ModuloDec(size_t index) {
+  if (index == 0) {
+    return m_data.size() - 1;
+  } else {
+    return index - 1;
+  }
+}
diff --git a/wpilibc/shared/include/Commands/Command.h b/wpilibc/shared/include/Commands/Command.h
index 6ec5512..47fe7f1 100644
--- a/wpilibc/shared/include/Commands/Command.h
+++ b/wpilibc/shared/include/Commands/Command.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __COMMAND_H__
diff --git a/wpilibc/shared/include/Commands/CommandGroup.h b/wpilibc/shared/include/Commands/CommandGroup.h
index 7f289ca..309d591 100644
--- a/wpilibc/shared/include/Commands/CommandGroup.h
+++ b/wpilibc/shared/include/Commands/CommandGroup.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __COMMAND_GROUP_H__
diff --git a/wpilibc/shared/include/Commands/CommandGroupEntry.h b/wpilibc/shared/include/Commands/CommandGroupEntry.h
index 442a02c..fd9b387 100644
--- a/wpilibc/shared/include/Commands/CommandGroupEntry.h
+++ b/wpilibc/shared/include/Commands/CommandGroupEntry.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __COMMAND_GROUP_ENTRY_H__
diff --git a/wpilibc/shared/include/Commands/PIDCommand.h b/wpilibc/shared/include/Commands/PIDCommand.h
index d67c063..b9fb2ca 100644
--- a/wpilibc/shared/include/Commands/PIDCommand.h
+++ b/wpilibc/shared/include/Commands/PIDCommand.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __PID_COMMAND_H__
diff --git a/wpilibc/shared/include/Commands/PIDSubsystem.h b/wpilibc/shared/include/Commands/PIDSubsystem.h
index ff05514..fea1847 100644
--- a/wpilibc/shared/include/Commands/PIDSubsystem.h
+++ b/wpilibc/shared/include/Commands/PIDSubsystem.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __PID_SUBSYSTEM_H__
diff --git a/wpilibc/shared/include/Commands/PrintCommand.h b/wpilibc/shared/include/Commands/PrintCommand.h
index cbb3e5e..577252d 100644
--- a/wpilibc/shared/include/Commands/PrintCommand.h
+++ b/wpilibc/shared/include/Commands/PrintCommand.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __PRINT_COMMAND_H__
diff --git a/wpilibc/shared/include/Commands/Scheduler.h b/wpilibc/shared/include/Commands/Scheduler.h
index 065fbad..fc55256 100644
--- a/wpilibc/shared/include/Commands/Scheduler.h
+++ b/wpilibc/shared/include/Commands/Scheduler.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __SCHEDULER_H__
diff --git a/wpilibc/shared/include/Commands/StartCommand.h b/wpilibc/shared/include/Commands/StartCommand.h
index 8f53d14..4f97971 100644
--- a/wpilibc/shared/include/Commands/StartCommand.h
+++ b/wpilibc/shared/include/Commands/StartCommand.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __START_COMMAND_H__
diff --git a/wpilibc/shared/include/Commands/Subsystem.h b/wpilibc/shared/include/Commands/Subsystem.h
index 8762ec8..070af48 100644
--- a/wpilibc/shared/include/Commands/Subsystem.h
+++ b/wpilibc/shared/include/Commands/Subsystem.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __SUBSYSTEM_H__
diff --git a/wpilibc/shared/include/Commands/WaitCommand.h b/wpilibc/shared/include/Commands/WaitCommand.h
index 6db6dac..fa64b75 100644
--- a/wpilibc/shared/include/Commands/WaitCommand.h
+++ b/wpilibc/shared/include/Commands/WaitCommand.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __WAIT_COMMAND_H__
diff --git a/wpilibc/shared/include/Commands/WaitForChildren.h b/wpilibc/shared/include/Commands/WaitForChildren.h
index 858d243..5028cdb 100644
--- a/wpilibc/shared/include/Commands/WaitForChildren.h
+++ b/wpilibc/shared/include/Commands/WaitForChildren.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __WAIT_FOR_CHILDREN_H__
diff --git a/wpilibc/shared/include/Commands/WaitUntilCommand.h b/wpilibc/shared/include/Commands/WaitUntilCommand.h
index fd77f8e..2512a20 100644
--- a/wpilibc/shared/include/Commands/WaitUntilCommand.h
+++ b/wpilibc/shared/include/Commands/WaitUntilCommand.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __WAIT_UNTIL_COMMAND_H__
diff --git a/wpilibc/shared/include/Controller.h b/wpilibc/shared/include/Controller.h
index d852307..bad16d6 100644
--- a/wpilibc/shared/include/Controller.h
+++ b/wpilibc/shared/include/Controller.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 /**
diff --git a/wpilibc/shared/include/Error.h b/wpilibc/shared/include/Error.h
index f9e301d..a001145 100644
--- a/wpilibc/shared/include/Error.h
+++ b/wpilibc/shared/include/Error.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "Base.h"
diff --git a/wpilibc/shared/include/ErrorBase.h b/wpilibc/shared/include/ErrorBase.h
index 4730a29..756442d 100644
--- a/wpilibc/shared/include/ErrorBase.h
+++ b/wpilibc/shared/include/ErrorBase.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "Base.h"
diff --git a/wpilibc/shared/include/Filters/Filter.h b/wpilibc/shared/include/Filters/Filter.h
new file mode 100644
index 0000000..1ab193b
--- /dev/null
+++ b/wpilibc/shared/include/Filters/Filter.h
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015-2016. 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 <memory>
+#include "PIDSource.h"
+
+/**
+ * Interface for filters
+ */
+class Filter : public PIDSource {
+ public:
+  Filter(std::shared_ptr<PIDSource> source);
+  virtual ~Filter() = default;
+
+  // PIDSource interface
+  virtual void SetPIDSourceType(PIDSourceType pidSource) override;
+  PIDSourceType GetPIDSourceType() const;
+  virtual double PIDGet() override = 0;
+
+  /**
+   * Returns the current filter estimate without also inserting new data as
+   * PIDGet() would do.
+   *
+   * @return The current filter estimate
+   */
+  virtual double Get() const = 0;
+
+  /**
+   * Reset the filter state
+   */
+  virtual void Reset() = 0;
+
+ protected:
+  /**
+   * Calls PIDGet() of source
+   *
+   * @return Current value of source
+   */
+  double PIDGetSource();
+
+ private:
+  std::shared_ptr<PIDSource> m_source;
+};
diff --git a/wpilibc/shared/include/Filters/LinearDigitalFilter.h b/wpilibc/shared/include/Filters/LinearDigitalFilter.h
new file mode 100644
index 0000000..b6dbce7
--- /dev/null
+++ b/wpilibc/shared/include/Filters/LinearDigitalFilter.h
@@ -0,0 +1,100 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015-2016. 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 <initializer_list>
+#include <memory>
+#include <vector>
+#include "Filter.h"
+#include "CircularBuffer.h"
+
+/**
+ * This class implements a linear, digital filter. All types of FIR and IIR
+ * filters are supported. Static factory methods are provided to create commonly
+ * used types of filters.
+ *
+ * Filters are of the form:
+ *  y[n] = (b0*x[n] + b1*x[n-1] + ... + bP*x[n-P) - (a0*y[n-1] + a2*y[n-2] + ... + aQ*y[n-Q])
+ *
+ * Where:
+ *  y[n] is the output at time "n"
+ *  x[n] is the input at time "n"
+ *  y[n-1] is the output from the LAST time step ("n-1")
+ *  x[n-1] is the input from the LAST time step ("n-1")
+ *  b0...bP are the "feedforward" (FIR) gains
+ *  a0...aQ are the "feedback" (IIR) gains
+ * IMPORTANT! Note the "-" sign in front of the feedback term! This is a common
+ *            convention in signal processing.
+ *
+ * What can linear filters do? Basically, they can filter, or diminish, the
+ * effects of undesirable input frequencies. High frequencies, or rapid changes,
+ * can be indicative of sensor noise or be otherwise undesirable. A "low pass"
+ * filter smooths out the signal, reducing the impact of these high frequency
+ * components.  Likewise, a "high pass" filter gets rid of slow-moving signal
+ * components, letting you detect large changes more easily.
+ *
+ * Example FRC applications of filters:
+ *  - Getting rid of noise from an analog sensor input (note: the roboRIO's FPGA
+ *    can do this faster in hardware)
+ *  - Smoothing out joystick input to prevent the wheels from slipping or the
+ *    robot from tipping
+ *  - Smoothing motor commands so that unnecessary strain isn't put on
+ *    electrical or mechanical components
+ *  - If you use clever gains, you can make a PID controller out of this class!
+ *
+ * For more on filters, I highly recommend the following articles:
+ *  http://en.wikipedia.org/wiki/Linear_filter
+ *  http://en.wikipedia.org/wiki/Iir_filter
+ *  http://en.wikipedia.org/wiki/Fir_filter
+ *
+ * Note 1: PIDGet() should be called by the user on a known, regular period.
+ * You can set up a Notifier to do this (look at the WPILib PIDController
+ * class), or do it "inline" with code in a periodic function.
+ *
+ * Note 2: For ALL filters, gains are necessarily a function of frequency. If
+ * you make a filter that works well for you at, say, 100Hz, you will most
+ * definitely need to adjust the gains if you then want to run it at 200Hz!
+ * Combining this with Note 1 - the impetus is on YOU as a developer to make
+ * sure PIDGet() gets called at the desired, constant frequency!
+ */
+class LinearDigitalFilter : public Filter {
+ public:
+  LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                      std::initializer_list<double> ffGains,
+                      std::initializer_list<double> fbGains);
+  LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                      std::initializer_list<double> ffGains,
+                      const std::vector<double>& fbGains);
+  LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                      const std::vector<double>& ffGains,
+                      std::initializer_list<double> fbGains);
+  LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                      const std::vector<double>& ffGains,
+                      const std::vector<double>& fbGains);
+
+  // Static methods to create commonly used filters
+  static LinearDigitalFilter SinglePoleIIR(std::shared_ptr<PIDSource> source,
+                                           double timeConstant, double period);
+  static LinearDigitalFilter HighPass(std::shared_ptr<PIDSource> source,
+                                      double timeConstant, double period);
+  static LinearDigitalFilter MovingAverage(std::shared_ptr<PIDSource> source,
+                                           unsigned int taps);
+
+  // Filter interface
+  double Get() const override;
+  void Reset() override;
+
+  // PIDSource interface
+  double PIDGet() override;
+
+ private:
+  CircularBuffer<double> m_inputs;
+  CircularBuffer<double> m_outputs;
+  std::vector<double> m_inputGains;
+  std::vector<double> m_outputGains;
+};
diff --git a/wpilibc/shared/include/GenericHID.h b/wpilibc/shared/include/GenericHID.h
index bf1fe8e..17a959f 100644
--- a/wpilibc/shared/include/GenericHID.h
+++ b/wpilibc/shared/include/GenericHID.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include <stdint.h>
diff --git a/wpilibc/Athena/include/GyroBase.h b/wpilibc/shared/include/GyroBase.h
similarity index 80%
rename from wpilibc/Athena/include/GyroBase.h
rename to wpilibc/shared/include/GyroBase.h
index 6ed44aa..5d93fc4 100644
--- a/wpilibc/Athena/include/GyroBase.h
+++ b/wpilibc/shared/include/GyroBase.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SensorBase.h"
diff --git a/wpilibc/shared/include/HLUsageReporting.h b/wpilibc/shared/include/HLUsageReporting.h
index 5d8d34f..0da2b5c 100644
--- a/wpilibc/shared/include/HLUsageReporting.h
+++ b/wpilibc/shared/include/HLUsageReporting.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 class HLUsageReportingInterface {
diff --git a/wpilibc/shared/include/LiveWindow/LiveWindow.h b/wpilibc/shared/include/LiveWindow/LiveWindow.h
index 7b40f67..17817a9 100644
--- a/wpilibc/shared/include/LiveWindow/LiveWindow.h
+++ b/wpilibc/shared/include/LiveWindow/LiveWindow.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2012-2016. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 #ifndef _LIVE_WINDOW_H
 #define _LIVE_WINDOW_H
 
diff --git a/wpilibc/shared/include/LiveWindow/LiveWindowSendable.h b/wpilibc/shared/include/LiveWindow/LiveWindowSendable.h
index 4f2023a..16debcc 100644
--- a/wpilibc/shared/include/LiveWindow/LiveWindowSendable.h
+++ b/wpilibc/shared/include/LiveWindow/LiveWindowSendable.h
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) Patrick Plenefisch 2012. All Rights Reserved. */
+/* Copyright (c) FIRST 2012-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef LIVEWINDOWSENDABLE_H_
diff --git a/wpilibc/shared/include/LiveWindow/LiveWindowStatusListener.h b/wpilibc/shared/include/LiveWindow/LiveWindowStatusListener.h
index 4fa3eb7..88b373b 100644
--- a/wpilibc/shared/include/LiveWindow/LiveWindowStatusListener.h
+++ b/wpilibc/shared/include/LiveWindow/LiveWindowStatusListener.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2012-2016. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
 #ifndef _LIVE_WINDOW_STATUS_LISTENER_H
 #define _LIVE_WINDOW_STATUS_LISTENER_H
 
diff --git a/wpilibc/shared/include/Notifier.h b/wpilibc/shared/include/Notifier.h
deleted file mode 100644
index 056ed0a..0000000
--- a/wpilibc/shared/include/Notifier.h
+++ /dev/null
@@ -1,57 +0,0 @@
-/*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. 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 $(WIND_BASE)/WPILib.  */
-/*----------------------------------------------------------------------------*/
-#pragma once
-
-#include "ErrorBase.h"
-#include "HAL/cpp/priority_mutex.h"
-#include <thread>
-#include <atomic>
-
-typedef void (*TimerEventHandler)(void *param);
-
-class Notifier : public ErrorBase {
- public:
-  Notifier(TimerEventHandler handler, void *param = nullptr);
-  virtual ~Notifier();
-
-  Notifier(const Notifier&) = delete;
-  Notifier& operator=(const Notifier&) = delete;
-
-  void StartSingle(double delay);
-  void StartPeriodic(double period);
-  void Stop();
-
- private:
-  static Notifier *timerQueueHead;
-  static priority_recursive_mutex queueMutex;
-  static priority_mutex halMutex;
-  static void *m_notifier;
-  static std::atomic<int> refcount;
-
-  static void ProcessQueue(
-      uint32_t mask, void *params);  // process the timer queue on a timer event
-  static void
-  UpdateAlarm();  // update the FPGA alarm since the queue has changed
-  void InsertInQueue(
-      bool reschedule);         // insert this Notifier in the timer queue
-  void DeleteFromQueue();       // delete this Notifier from the timer queue
-  TimerEventHandler m_handler;  // address of the handler
-  void *m_param;                // a parameter to pass to the handler
-  double m_period = 0;              // the relative time (either periodic or single)
-  double m_expirationTime = 0;  // absolute expiration time for the current event
-  Notifier *m_nextEvent = nullptr;    // next Nofifier event
-  bool m_periodic = false;          // true if this is a periodic event
-  bool m_queued = false;            // indicates if this entry is queued
-  priority_mutex m_handlerMutex;  // held by interrupt manager task while
-                                    // handler call is in progress
-
-#ifdef FRC_SIMULATOR
-  static std::thread m_task;
-  static std::atomic<bool> m_stopped;
-#endif
-  static void Run();
-};
diff --git a/wpilibc/shared/include/PIDController.h b/wpilibc/shared/include/PIDController.h
index 301356c..5e74389 100644
--- a/wpilibc/shared/include/PIDController.h
+++ b/wpilibc/shared/include/PIDController.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "Base.h"
@@ -13,6 +14,7 @@
 #include "PIDSource.h"
 #include "Notifier.h"
 #include "HAL/cpp/priority_mutex.h"
+#include "Timer.h"
 
 #include <memory>
 
@@ -54,6 +56,7 @@
 
   virtual void SetSetpoint(float setpoint) override;
   virtual double GetSetpoint() const override;
+  double GetDeltaSetpoint() const;
 
   virtual float GetError() const;
   virtual float GetAvgError() const;
@@ -81,6 +84,7 @@
 
   std::shared_ptr<ITable> m_table;
   virtual void Calculate();
+  virtual double CalculateFeedForward();
 
  private:
   float m_P;              // factor for "proportional" control
@@ -93,7 +97,7 @@
   float m_minimumInput = 0;   // minimum input - limit setpoint to this
   bool m_continuous = false;      // do the endpoints wrap around? eg. Absolute encoder
   bool m_enabled = false;  // is the pid controller enabled
-  float m_prevInput = 0;  // the prior sensor input (used to compute velocity)
+  float m_prevError = 0;  // the prior error (used to compute velocity)
   double m_totalError = 0;  // the sum of the errors for use in the integral calc
   enum {
     kAbsoluteTolerance,
@@ -104,6 +108,7 @@
   // the percetage or absolute error that is considered on target.
   float m_tolerance = 0.05;
   float m_setpoint = 0;
+  float m_prevSetpoint = 0;
   float m_error = 0;
   float m_result = 0;
   float m_period;
@@ -113,13 +118,13 @@
   std::queue<double> m_buf;
   double m_bufTotal = 0;
 
-  mutable priority_mutex m_mutex;
+  mutable priority_recursive_mutex m_mutex;
 
   std::unique_ptr<Notifier> m_controlLoop;
+  Timer m_setpointTimer;
 
   void Initialize(float p, float i, float d, float f, PIDSource *source,
                   PIDOutput *output, float period = 0.05);
-  static void CallCalculate(void *controller);
 
   virtual std::shared_ptr<ITable> GetTable() const override;
   virtual std::string GetSmartDashboardType() const override;
diff --git a/wpilibc/shared/include/PIDInterface.h b/wpilibc/shared/include/PIDInterface.h
index 5d50199..efcc184 100644
--- a/wpilibc/shared/include/PIDInterface.h
+++ b/wpilibc/shared/include/PIDInterface.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "Base.h"
diff --git a/wpilibc/shared/include/PIDOutput.h b/wpilibc/shared/include/PIDOutput.h
index 40421d0..ad720dc 100644
--- a/wpilibc/shared/include/PIDOutput.h
+++ b/wpilibc/shared/include/PIDOutput.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "Base.h"
diff --git a/wpilibc/shared/include/PIDSource.h b/wpilibc/shared/include/PIDSource.h
index 8f46ea4..1a2be9c 100644
--- a/wpilibc/shared/include/PIDSource.h
+++ b/wpilibc/shared/include/PIDSource.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 enum class PIDSourceType { kDisplacement, kRate };
diff --git a/wpilibc/shared/include/Resource.h b/wpilibc/shared/include/Resource.h
index f7061c8..8d26442 100644
--- a/wpilibc/shared/include/Resource.h
+++ b/wpilibc/shared/include/Resource.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "ErrorBase.h"
diff --git a/wpilibc/shared/include/RobotState.h b/wpilibc/shared/include/RobotState.h
index 53bf32a..ce48ca0 100644
--- a/wpilibc/shared/include/RobotState.h
+++ b/wpilibc/shared/include/RobotState.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include <memory>
diff --git a/wpilibc/shared/include/SensorBase.h b/wpilibc/shared/include/SensorBase.h
index 8638b5e..51fd94c 100644
--- a/wpilibc/shared/include/SensorBase.h
+++ b/wpilibc/shared/include/SensorBase.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "ErrorBase.h"
diff --git a/wpilibc/shared/include/SmartDashboard/Sendable.h b/wpilibc/shared/include/SmartDashboard/Sendable.h
index 613c7f8..78206d0 100644
--- a/wpilibc/shared/include/SmartDashboard/Sendable.h
+++ b/wpilibc/shared/include/SmartDashboard/Sendable.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __SMART_DASHBOARD_DATA__
diff --git a/wpilibc/shared/include/SmartDashboard/SendableChooser.h b/wpilibc/shared/include/SmartDashboard/SendableChooser.h
index bfdf877..9560746 100644
--- a/wpilibc/shared/include/SmartDashboard/SendableChooser.h
+++ b/wpilibc/shared/include/SmartDashboard/SendableChooser.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __SENDABLE_CHOOSER_H__
diff --git a/wpilibc/shared/include/SmartDashboard/SmartDashboard.h b/wpilibc/shared/include/SmartDashboard/SmartDashboard.h
index a1cfb22..51e51d1 100644
--- a/wpilibc/shared/include/SmartDashboard/SmartDashboard.h
+++ b/wpilibc/shared/include/SmartDashboard/SmartDashboard.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef __SMART_DASHBOARD_H__
diff --git a/wpilibc/shared/include/Task.h b/wpilibc/shared/include/Task.h
index 7752d0d..2735f48 100644
--- a/wpilibc/shared/include/Task.h
+++ b/wpilibc/shared/include/Task.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "ErrorBase.h"
diff --git a/wpilibc/shared/include/Task.inc b/wpilibc/shared/include/Task.inc
index 3514b92..3c90aba 100644
--- a/wpilibc/shared/include/Task.inc
+++ b/wpilibc/shared/include/Task.inc
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/HAL.hpp"
 #include <atomic>
 
diff --git a/wpilibc/shared/include/Timer.h b/wpilibc/shared/include/Timer.h
index 60b9604..b3fe77d 100644
--- a/wpilibc/shared/include/Timer.h
+++ b/wpilibc/shared/include/Timer.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "Base.h"
diff --git a/wpilibc/shared/include/Utility.h b/wpilibc/shared/include/Utility.h
index 69edb63..89b9729 100644
--- a/wpilibc/shared/include/Utility.h
+++ b/wpilibc/shared/include/Utility.h
@@ -1,9 +1,10 @@
-/*---------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. 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 $(WIND_BASE)/WPILib. */
-/*---------------------------------------------------------------------------*/
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2016. 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
 
 /** @file
@@ -46,6 +47,6 @@
 
 uint16_t GetFPGAVersion();
 uint32_t GetFPGARevision();
-uint32_t GetFPGATime();
+uint64_t GetFPGATime();
 bool GetUserButton();
 std::string GetStackTrace(uint32_t offset);
diff --git a/wpilibc/shared/include/WPIErrors.h b/wpilibc/shared/include/WPIErrors.h
index 8346fdf..ccf6dae 100644
--- a/wpilibc/shared/include/WPIErrors.h
+++ b/wpilibc/shared/include/WPIErrors.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "stdint.h"
diff --git a/wpilibc/shared/include/interfaces/Accelerometer.h b/wpilibc/shared/include/interfaces/Accelerometer.h
index 528d120..12296ca 100644
--- a/wpilibc/shared/include/interfaces/Accelerometer.h
+++ b/wpilibc/shared/include/interfaces/Accelerometer.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 /**
diff --git a/wpilibc/shared/include/interfaces/Gyro.h b/wpilibc/shared/include/interfaces/Gyro.h
index 8317ca5..6766444 100644
--- a/wpilibc/shared/include/interfaces/Gyro.h
+++ b/wpilibc/shared/include/interfaces/Gyro.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 /**
diff --git a/wpilibc/shared/include/interfaces/Potentiometer.h b/wpilibc/shared/include/interfaces/Potentiometer.h
index d52892d..1c2e99a 100644
--- a/wpilibc/shared/include/interfaces/Potentiometer.h
+++ b/wpilibc/shared/include/interfaces/Potentiometer.h
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef INTERFACES_POTENTIOMETER_H
diff --git a/wpilibc/shared/src/Buttons/Button.cpp b/wpilibc/shared/src/Buttons/Button.cpp
index b57fd89..c4bd5ec 100644
--- a/wpilibc/shared/src/Buttons/Button.cpp
+++ b/wpilibc/shared/src/Buttons/Button.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Buttons/Button.h"
diff --git a/wpilibc/shared/src/Buttons/ButtonScheduler.cpp b/wpilibc/shared/src/Buttons/ButtonScheduler.cpp
index ddc9025..318fd5f 100644
--- a/wpilibc/shared/src/Buttons/ButtonScheduler.cpp
+++ b/wpilibc/shared/src/Buttons/ButtonScheduler.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Buttons/ButtonScheduler.h"
diff --git a/wpilibc/shared/src/Buttons/CancelButtonScheduler.cpp b/wpilibc/shared/src/Buttons/CancelButtonScheduler.cpp
index 1d2b6cc..52544e5 100644
--- a/wpilibc/shared/src/Buttons/CancelButtonScheduler.cpp
+++ b/wpilibc/shared/src/Buttons/CancelButtonScheduler.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Buttons/CancelButtonScheduler.h"
diff --git a/wpilibc/shared/src/Buttons/HeldButtonScheduler.cpp b/wpilibc/shared/src/Buttons/HeldButtonScheduler.cpp
index 04c8e3b..37de385 100644
--- a/wpilibc/shared/src/Buttons/HeldButtonScheduler.cpp
+++ b/wpilibc/shared/src/Buttons/HeldButtonScheduler.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Buttons/HeldButtonScheduler.h"
diff --git a/wpilibc/shared/src/Buttons/InternalButton.cpp b/wpilibc/shared/src/Buttons/InternalButton.cpp
index 8c9b22a..9e0e121 100644
--- a/wpilibc/shared/src/Buttons/InternalButton.cpp
+++ b/wpilibc/shared/src/Buttons/InternalButton.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Buttons/InternalButton.h"
diff --git a/wpilibc/shared/src/Buttons/JoystickButton.cpp b/wpilibc/shared/src/Buttons/JoystickButton.cpp
index c2bdf62..a7a31e6 100644
--- a/wpilibc/shared/src/Buttons/JoystickButton.cpp
+++ b/wpilibc/shared/src/Buttons/JoystickButton.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Buttons/JoystickButton.h"
diff --git a/wpilibc/shared/src/Buttons/NetworkButton.cpp b/wpilibc/shared/src/Buttons/NetworkButton.cpp
index 858703c..54604ed 100644
--- a/wpilibc/shared/src/Buttons/NetworkButton.cpp
+++ b/wpilibc/shared/src/Buttons/NetworkButton.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Buttons/NetworkButton.h"
diff --git a/wpilibc/shared/src/Buttons/PressedButtonScheduler.cpp b/wpilibc/shared/src/Buttons/PressedButtonScheduler.cpp
index 5a0c506..60792dc 100644
--- a/wpilibc/shared/src/Buttons/PressedButtonScheduler.cpp
+++ b/wpilibc/shared/src/Buttons/PressedButtonScheduler.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Buttons/PressedButtonScheduler.h"
diff --git a/wpilibc/shared/src/Buttons/ReleasedButtonScheduler.cpp b/wpilibc/shared/src/Buttons/ReleasedButtonScheduler.cpp
index e7131e6..dde271e 100644
--- a/wpilibc/shared/src/Buttons/ReleasedButtonScheduler.cpp
+++ b/wpilibc/shared/src/Buttons/ReleasedButtonScheduler.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Buttons/ReleasedButtonScheduler.h"
diff --git a/wpilibc/shared/src/Buttons/ToggleButtonScheduler.cpp b/wpilibc/shared/src/Buttons/ToggleButtonScheduler.cpp
index c4048d2..dc2f058 100644
--- a/wpilibc/shared/src/Buttons/ToggleButtonScheduler.cpp
+++ b/wpilibc/shared/src/Buttons/ToggleButtonScheduler.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Buttons/ToggleButtonScheduler.h"
diff --git a/wpilibc/shared/src/Buttons/Trigger.cpp b/wpilibc/shared/src/Buttons/Trigger.cpp
index 54a1eba..3f15b7e 100644
--- a/wpilibc/shared/src/Buttons/Trigger.cpp
+++ b/wpilibc/shared/src/Buttons/Trigger.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Buttons/Button.h"
diff --git a/wpilibc/shared/src/Commands/Command.cpp b/wpilibc/shared/src/Commands/Command.cpp
index 37effbe..f965712 100644
--- a/wpilibc/shared/src/Commands/Command.cpp
+++ b/wpilibc/shared/src/Commands/Command.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Commands/Command.h"
diff --git a/wpilibc/shared/src/Commands/CommandGroup.cpp b/wpilibc/shared/src/Commands/CommandGroup.cpp
index edb5ec9..91cf788 100644
--- a/wpilibc/shared/src/Commands/CommandGroup.cpp
+++ b/wpilibc/shared/src/Commands/CommandGroup.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Commands/CommandGroup.h"
diff --git a/wpilibc/shared/src/Commands/CommandGroupEntry.cpp b/wpilibc/shared/src/Commands/CommandGroupEntry.cpp
index c9f3fa4..0534a71 100644
--- a/wpilibc/shared/src/Commands/CommandGroupEntry.cpp
+++ b/wpilibc/shared/src/Commands/CommandGroupEntry.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Commands/CommandGroupEntry.h"
diff --git a/wpilibc/shared/src/Commands/PIDCommand.cpp b/wpilibc/shared/src/Commands/PIDCommand.cpp
index c6ac919..b6f426f 100644
--- a/wpilibc/shared/src/Commands/PIDCommand.cpp
+++ b/wpilibc/shared/src/Commands/PIDCommand.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Commands/PIDCommand.h"
diff --git a/wpilibc/shared/src/Commands/PIDSubsystem.cpp b/wpilibc/shared/src/Commands/PIDSubsystem.cpp
index b3d327f..e478073 100644
--- a/wpilibc/shared/src/Commands/PIDSubsystem.cpp
+++ b/wpilibc/shared/src/Commands/PIDSubsystem.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Commands/PIDSubsystem.h"
diff --git a/wpilibc/shared/src/Commands/PrintCommand.cpp b/wpilibc/shared/src/Commands/PrintCommand.cpp
index b5e8dc7..1d94694 100644
--- a/wpilibc/shared/src/Commands/PrintCommand.cpp
+++ b/wpilibc/shared/src/Commands/PrintCommand.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Commands/PrintCommand.h"
diff --git a/wpilibc/shared/src/Commands/Scheduler.cpp b/wpilibc/shared/src/Commands/Scheduler.cpp
index 0b796e3..955b337 100644
--- a/wpilibc/shared/src/Commands/Scheduler.cpp
+++ b/wpilibc/shared/src/Commands/Scheduler.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Commands/Scheduler.h"
diff --git a/wpilibc/shared/src/Commands/StartCommand.cpp b/wpilibc/shared/src/Commands/StartCommand.cpp
index 60db054..ca5f67b 100644
--- a/wpilibc/shared/src/Commands/StartCommand.cpp
+++ b/wpilibc/shared/src/Commands/StartCommand.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Commands/StartCommand.h"
diff --git a/wpilibc/shared/src/Commands/Subsystem.cpp b/wpilibc/shared/src/Commands/Subsystem.cpp
index 0b4b92f..7e3ef61 100644
--- a/wpilibc/shared/src/Commands/Subsystem.cpp
+++ b/wpilibc/shared/src/Commands/Subsystem.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Commands/Subsystem.h"
diff --git a/wpilibc/shared/src/Commands/WaitCommand.cpp b/wpilibc/shared/src/Commands/WaitCommand.cpp
index f4e4c00..8c5be65 100644
--- a/wpilibc/shared/src/Commands/WaitCommand.cpp
+++ b/wpilibc/shared/src/Commands/WaitCommand.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Commands/WaitCommand.h"
diff --git a/wpilibc/shared/src/Commands/WaitForChildren.cpp b/wpilibc/shared/src/Commands/WaitForChildren.cpp
index a3a129d..e08dfe0 100644
--- a/wpilibc/shared/src/Commands/WaitForChildren.cpp
+++ b/wpilibc/shared/src/Commands/WaitForChildren.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Commands/WaitForChildren.h"
diff --git a/wpilibc/shared/src/Commands/WaitUntilCommand.cpp b/wpilibc/shared/src/Commands/WaitUntilCommand.cpp
index ea0e664..17d6f3e 100644
--- a/wpilibc/shared/src/Commands/WaitUntilCommand.cpp
+++ b/wpilibc/shared/src/Commands/WaitUntilCommand.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Commands/WaitUntilCommand.h"
diff --git a/wpilibc/shared/src/Error.cpp b/wpilibc/shared/src/Error.cpp
index 1206361..5237a92 100644
--- a/wpilibc/shared/src/Error.cpp
+++ b/wpilibc/shared/src/Error.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Error.h"
@@ -66,24 +66,21 @@
 }
 
 void Error::Report() {
-  std::stringstream errorStream;
+  std::stringstream locStream;
+  locStream << m_function << " [";
 
-  errorStream << "Error on line " << m_lineNumber << " ";
-#if defined(_UNIX)
-	errorStream << "of " << basename(m_filename.c_str()) << ": ";
-#elif defined(_WIN32)
+#if defined(_WIN32)
 	const int MAX_DIR = 100;
 	char basename[MAX_DIR];
 	_splitpath_s(m_filename.c_str(), NULL, 0, basename, MAX_DIR, NULL, 0, NULL, 0);
-	errorStream << "of " << basename << ": ";
+	locStream << basename;
+#else
+	locStream << basename(m_filename.c_str());
 #endif
+  locStream << ":" << m_lineNumber << "]";
 
-	errorStream << m_message << std::endl;
-	errorStream << GetStackTrace(4);
-
-  std::string error = errorStream.str();
-
-  DriverStation::ReportError(error);
+  DriverStation::ReportError(true, m_code, m_message, locStream.str(),
+                             GetStackTrace(4));
 }
 
 void Error::Clear() {
diff --git a/wpilibc/shared/src/ErrorBase.cpp b/wpilibc/shared/src/ErrorBase.cpp
index 329c983..c1e41d8 100644
--- a/wpilibc/shared/src/ErrorBase.cpp
+++ b/wpilibc/shared/src/ErrorBase.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "ErrorBase.h"
diff --git a/wpilibc/shared/src/Filters/Filter.cpp b/wpilibc/shared/src/Filters/Filter.cpp
new file mode 100644
index 0000000..d6042d7
--- /dev/null
+++ b/wpilibc/shared/src/Filters/Filter.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015-2016. 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 "Filters/Filter.h"
+
+Filter::Filter(std::shared_ptr<PIDSource> source) {
+  m_source = source;
+}
+
+void Filter::SetPIDSourceType(PIDSourceType pidSource) {
+  m_source->SetPIDSourceType(pidSource);
+}
+
+PIDSourceType Filter::GetPIDSourceType() const {
+  return m_source->GetPIDSourceType();
+}
+
+double Filter::PIDGetSource() {
+  return m_source->PIDGet();
+}
diff --git a/wpilibc/shared/src/Filters/LinearDigitalFilter.cpp b/wpilibc/shared/src/Filters/LinearDigitalFilter.cpp
new file mode 100644
index 0000000..e4a5cff
--- /dev/null
+++ b/wpilibc/shared/src/Filters/LinearDigitalFilter.cpp
@@ -0,0 +1,166 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015-2016. 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 "Filters/LinearDigitalFilter.h"
+#include <cassert>
+#include <cmath>
+
+/**
+ * Create a linear FIR or IIR filter
+ *
+ * @param source The PIDSource object that is used to get values
+ * @param ffGains The "feed forward" or FIR gains
+ * @param fbGains The "feed back" or IIR gains
+ */
+LinearDigitalFilter::LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                                         std::initializer_list<double> ffGains,
+                                         std::initializer_list<double> fbGains) :
+    Filter(source), m_inputs(ffGains.size()), m_outputs(fbGains.size()),
+    m_inputGains(ffGains), m_outputGains(fbGains) {}
+
+/**
+ * Create a linear FIR or IIR filter
+ *
+ * @param source The PIDSource object that is used to get values
+ * @param ffGains The "feed forward" or FIR gains
+ * @param fbGains The "feed back" or IIR gains
+ */
+LinearDigitalFilter::LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                                         std::initializer_list<double> ffGains,
+                                         const std::vector<double>& fbGains) :
+    Filter(source), m_inputs(ffGains.size()), m_outputs(fbGains.size()),
+    m_inputGains(ffGains), m_outputGains(fbGains) {}
+
+/**
+ * Create a linear FIR or IIR filter
+ *
+ * @param source The PIDSource object that is used to get values
+ * @param ffGains The "feed forward" or FIR gains
+ * @param fbGains The "feed back" or IIR gains
+ */
+LinearDigitalFilter::LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                                         const std::vector<double>& ffGains,
+                                         std::initializer_list<double> fbGains) :
+    Filter(source), m_inputs(ffGains.size()), m_outputs(fbGains.size()),
+    m_inputGains(ffGains), m_outputGains(fbGains) {}
+
+/**
+ * Create a linear FIR or IIR filter
+ *
+ * @param source The PIDSource object that is used to get values
+ * @param ffGains The "feed forward" or FIR gains
+ * @param fbGains The "feed back" or IIR gains
+ */
+LinearDigitalFilter::LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                                         const std::vector<double>& ffGains,
+                                         const std::vector<double>& fbGains) :
+    Filter(source), m_inputs(ffGains.size()), m_outputs(fbGains.size()),
+    m_inputGains(ffGains), m_outputGains(fbGains) {}
+
+/**
+ * Creates a one-pole IIR low-pass filter of the form:
+ *   y[n] = (1-gain)*x[n] + gain*y[n-1]
+ * where gain = e^(-dt / T), T is the time constant in seconds
+ *
+ * This filter is stable for time constants greater than zero
+ *
+ * @param source The PIDSource object that is used to get values
+ * @param timeConstant The discrete-time time constant in seconds
+ * @param period The period in seconds between samples taken by the user
+ */
+LinearDigitalFilter LinearDigitalFilter::SinglePoleIIR(std::shared_ptr<PIDSource> source,
+                                                       double timeConstant,
+                                                       double period) {
+  double gain = std::exp(-period / timeConstant);
+  return LinearDigitalFilter(std::move(source), {1.0 - gain}, {-gain});
+}
+
+/**
+ * Creates a first-order high-pass filter of the form:
+ *   y[n] = gain*x[n] + (-gain)*x[n-1] + gain*y[n-1]
+ * where gain = e^(-dt / T), T is the time constant in seconds
+ *
+ * This filter is stable for time constants greater than zero
+ *
+ * @param source The PIDSource object that is used to get values
+ * @param timeConstant The discrete-time time constant in seconds
+ * @param period The period in seconds between samples taken by the user
+ */
+LinearDigitalFilter LinearDigitalFilter::HighPass(std::shared_ptr<PIDSource> source,
+                                                  double timeConstant,
+                                                  double period) {
+  double gain = std::exp(-period / timeConstant);
+  return LinearDigitalFilter(std::move(source), {gain, -gain}, {-gain});
+}
+
+/**
+ * Creates a K-tap FIR moving average filter of the form:
+ *   y[n] = 1/k * (x[k] + x[k-1] + ... + x[0])
+ *
+ * This filter is always stable.
+ *
+ * @param source The PIDSource object that is used to get values
+ * @param taps The number of samples to average over. Higher = smoother but
+ *        slower
+ */
+LinearDigitalFilter LinearDigitalFilter::MovingAverage(std::shared_ptr<PIDSource> source,
+                                                       unsigned int taps) {
+  assert(taps > 0);
+
+  std::vector<double> gains(taps, 1.0 / taps);
+  return LinearDigitalFilter(std::move(source), gains, {});
+}
+
+/**
+ * {@inheritDoc}
+ */
+double LinearDigitalFilter::Get() const {
+  double retVal = 0.0;
+
+  // Calculate the new value
+  for (unsigned int i = 0; i < m_inputGains.size(); i++) {
+    retVal += m_inputs[i] * m_inputGains[i];
+  }
+  for (unsigned int i = 0; i < m_outputGains.size(); i++) {
+    retVal -= m_outputs[i] * m_outputGains[i];
+  }
+
+  return retVal;
+}
+
+/**
+ * {@inheritDoc}
+ */
+void LinearDigitalFilter::Reset() {
+  m_inputs.Reset();
+  m_outputs.Reset();
+}
+
+/**
+ * Calculates the next value of the filter
+ *
+ * @return The filtered value at this step
+ */
+double LinearDigitalFilter::PIDGet() {
+  double retVal = 0.0;
+
+  // Rotate the inputs
+  m_inputs.PushFront(PIDGetSource());
+
+  // Calculate the new value
+  for (unsigned int i = 0; i < m_inputGains.size(); i++) {
+    retVal += m_inputs[i] * m_inputGains[i];
+  }
+  for (unsigned int i = 0; i < m_outputGains.size(); i++) {
+    retVal -= m_outputs[i] * m_outputGains[i];
+  }
+
+  // Rotate the outputs
+  m_outputs.PushFront(retVal);
+
+  return retVal;
+}
diff --git a/wpilibc/Athena/src/GyroBase.cpp b/wpilibc/shared/src/GyroBase.cpp
similarity index 82%
rename from wpilibc/Athena/src/GyroBase.cpp
rename to wpilibc/shared/src/GyroBase.cpp
index 4cc9056..f1044b7 100644
--- a/wpilibc/Athena/src/GyroBase.cpp
+++ b/wpilibc/shared/src/GyroBase.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "GyroBase.h"
diff --git a/wpilibc/shared/src/HLUsageReporting.cpp b/wpilibc/shared/src/HLUsageReporting.cpp
index bcbc6b6..07cf446 100644
--- a/wpilibc/shared/src/HLUsageReporting.cpp
+++ b/wpilibc/shared/src/HLUsageReporting.cpp
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HLUsageReporting.h"
 
diff --git a/wpilibc/shared/src/LiveWindow/LiveWindow.cpp b/wpilibc/shared/src/LiveWindow/LiveWindow.cpp
index 793ddcc..1dfd507 100644
--- a/wpilibc/shared/src/LiveWindow/LiveWindow.cpp
+++ b/wpilibc/shared/src/LiveWindow/LiveWindow.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2012-2016. 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 "LiveWindow/LiveWindow.h"
 #include "networktables/NetworkTable.h"
 #include <algorithm>
diff --git a/wpilibc/shared/src/LiveWindow/LiveWindowStatusListener.cpp b/wpilibc/shared/src/LiveWindow/LiveWindowStatusListener.cpp
index 021798d..31e5db6 100644
--- a/wpilibc/shared/src/LiveWindow/LiveWindowStatusListener.cpp
+++ b/wpilibc/shared/src/LiveWindow/LiveWindowStatusListener.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2012-2016. 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 "LiveWindow/LiveWindowStatusListener.h"
 #include "Commands/Scheduler.h"
 
diff --git a/wpilibc/shared/src/PIDSource.cpp b/wpilibc/shared/src/PIDSource.cpp
index b6b5200..4e44b69 100644
--- a/wpilibc/shared/src/PIDSource.cpp
+++ b/wpilibc/shared/src/PIDSource.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "PIDSource.h"
diff --git a/wpilibc/shared/src/Resource.cpp b/wpilibc/shared/src/Resource.cpp
index 7f9e476..a68122e 100644
--- a/wpilibc/shared/src/Resource.cpp
+++ b/wpilibc/shared/src/Resource.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Resource.h"
diff --git a/wpilibc/shared/src/RobotState.cpp b/wpilibc/shared/src/RobotState.cpp
index cb28208..f3db1da 100644
--- a/wpilibc/shared/src/RobotState.cpp
+++ b/wpilibc/shared/src/RobotState.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "RobotState.h"
 
 #include "Base.h"
diff --git a/wpilibc/shared/src/SmartDashboard/SendableChooser.cpp b/wpilibc/shared/src/SmartDashboard/SendableChooser.cpp
index 255cc3a..cc6543f 100644
--- a/wpilibc/shared/src/SmartDashboard/SendableChooser.cpp
+++ b/wpilibc/shared/src/SmartDashboard/SendableChooser.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "SmartDashboard/SendableChooser.h"
diff --git a/wpilibc/shared/src/SmartDashboard/SmartDashboard.cpp b/wpilibc/shared/src/SmartDashboard/SmartDashboard.cpp
index bee0c03..9fbf605 100644
--- a/wpilibc/shared/src/SmartDashboard/SmartDashboard.cpp
+++ b/wpilibc/shared/src/SmartDashboard/SmartDashboard.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2011. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2011-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "SmartDashboard/SmartDashboard.h"
diff --git a/wpilibc/shared/src/interfaces/Potentiometer.cpp b/wpilibc/shared/src/interfaces/Potentiometer.cpp
index 3856090..9ac097b 100644
--- a/wpilibc/shared/src/interfaces/Potentiometer.cpp
+++ b/wpilibc/shared/src/interfaces/Potentiometer.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2015. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2015-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include <interfaces/Potentiometer.h>
diff --git a/wpilibc/simulation.gradle b/wpilibc/simulation.gradle
index c010a05..7da3216dc6 100644
--- a/wpilibc/simulation.gradle
+++ b/wpilibc/simulation.gradle
@@ -1,23 +1,96 @@
-publishing {
-    publications {
-        wpilibcSim(MavenPublication) {
-            artifact wpilibcSimZip
-            groupId 'edu.wpi.first.wpilibc.simulation'
-            artifactId 'WPILibCSim'
-            version '0.1.0'
-        }
+import org.apache.tools.ant.taskdefs.condition.Os
+
+  //cmake wrapper tasks
+task setupCmake(type: Exec) {
+    description = 'create build directory for cmake to use'
+    group = 'WPILib Simulation'
+    workingDir '..'
+    commandLine 'mkdir', '-p', 'build'
+}
+
+task cmake(type: Exec, dependsOn: setupCmake) {
+    description = 'run cmake in the build directory to generate makefiles'
+    group = 'WPILib Simulation'
+    workingDir '../build'
+    if (Os.isFamily(Os.FAMILY_WINDOWS)) {
+        commandLine '../configure.bat',
+            "-DNTCORE_INCLUDE_DIR=$netTablesInclude",
+            "-DNTCORE_LIBDIR=$netLibDesktopLocation",
+            "-DSIMULATION_INSTALL_DIR=$simulationInstallDir"
+    }
+    else {
+        commandLine 'cmake', '..',
+            "-DNTCORE_INCLUDE_DIR=$netTablesInclude",
+            "-DNTCORE_LIBDIR=$netLibDesktopLocation",
+            "-DSIMULATION_INSTALL_DIR=$simulationInstallDir"
     }
 }
 
-task wpilibcSimZip(type: Zip) {
-    description 'Creates the include zip file for wpilibc'
-    group 'WPILib'
-    baseName 'WPILibCSim'
-    destinationDir = project.buildDir
-    into 'sim/include'
-    from "${simulation}/include"
-    from "${shared}/include"
-    from '../build/simulation/gz_msgs/generated'
-    from netTablesInclude
-    from '../hal/include'
+task frc_gazebo_plugins(type: Exec, dependsOn: cmake) {
+    description = 'build Gazebo plugins with cmake'
+    group = 'WPILib Simulation'
+    workingDir '../build'
+    if (Os.isFamily(Os.FAMILY_WINDOWS)) {
+        commandLine 'nmake', 'frc_gazebo_plugins'
+    }
+    else {
+        commandLine 'make', 'frc_gazebo_plugins'
+    }
 }
+
+task gz_msgs(type: Exec, dependsOn: cmake) {
+    description = 'build gz_msgs library with cmake'
+    group = 'WPILib Simulation'
+      workingDir '../build'
+      if (Os.isFamily(Os.FAMILY_WINDOWS)) {
+          commandLine 'nmake', 'gz_msgs'
+      }
+      else {
+          commandLine 'make', 'gz_msgs'
+      }
+}
+
+task wpilibcSim(type: Exec, dependsOn: ['cmake', ':unzipNetworkTables']) {
+    description = 'build WPILib C++ for simulation with cmake'
+    group = 'WPILib Simulation'
+    workingDir '../build'
+    if (Os.isFamily(Os.FAMILY_WINDOWS)) {
+        commandLine 'nmake', 'wpilibcSim'
+    }
+    else {
+        commandLine 'make', 'wpilibcSim'
+    }
+}
+
+task allcsim(dependsOn: [wpilibcSim, gz_msgs, frc_gazebo_plugins]){
+    description = 'wrapper task to build all c++ simulation tasks'
+    group = 'WPILib Simulation'
+}
+
+task wpilibcSimCopy(type: Copy, dependsOn: allcsim) {
+    description = 'copy headers and ntcore library to make simulation zip'
+    group = 'WPILib Simulation'
+    into "$simulationInstallDir"
+
+    from ("$netTablesInclude"){
+        into "include"
+    }
+
+    from ("../hal/include"){
+        into "include"
+    }
+
+    from ("simulation/include"){
+        into "include"
+    }
+
+    from ("shared/include"){
+        into "include"
+    }
+
+    from ("$netLibDesktopLocation/libntcore.so") {
+        into "lib"
+    }
+}
+
+build.dependsOn allcsim
diff --git a/wpilibc/simulation/CMakeLists.txt b/wpilibc/simulation/CMakeLists.txt
index 1241fd3..39a7c6d 100644
--- a/wpilibc/simulation/CMakeLists.txt
+++ b/wpilibc/simulation/CMakeLists.txt
@@ -1,60 +1,26 @@
 cmake_minimum_required(VERSION 2.8)
-project(WPILibSim)
+cmake_policy(SET CMP0015 NEW)
+project(wpilibcSim)
 
-if (WIN32)
-  #temporary until we build dlls
-  add_definitions(-DBUILDING_STATIC_LIBS)
-
-  # XXX: should be set via CMake variables in configure.bat
-  set(PTHREAD_INCLUDE_DIR "C:/Users/peter/gz-ws/pthread-w32/include")
-  set(PTHREAD_LIBRARY "C:/Users/peter/gz-ws/pthread-w32/libs/x64/pthreadVC2.lib")
-endif()
-
-get_filename_component(HAL_API_INCLUDES ../../hal/include REALPATH)
-get_filename_component(NWT_API_INCLUDES ../../networktables/cpp/include REALPATH)
-
-
-# also on windows use sprintf_s instead of snprintf
-# TODO: find a more permenenant solution
-if (WIN32)
-  add_definitions(-Dsnprintf=sprintf_s)
-endif()
-
-file(GLOB_RECURSE COM_SRC_FILES ../wpilibC++/src/*.cpp)
-
+file(GLOB_RECURSE COM_SRC_FILES ../shared/src/*.cpp
+  src/*.cpp)
 
 set (INCLUDE_FOLDERS include
-  ../wpilibC++/include
-  ../../networktables/ntcore/include
+  ../shared/include
   ../../hal/include
+  ${NTCORE_INCLUDE_DIR}
   ${GZ_MSGS_INCLUDE_DIR}
   ${Boost_INCLUDE_DIR}
   ${GAZEBO_INCLUDE_DIRS})
 
-if (WIN32)
-  #these paths will be fixed when a more permenant windows development solution is found
-  set(INCLUDE_FOLDERS ${INCLUDE_FOLDERS}
-    C:/Users/peter/gz-ws/protobuf-2.6.0-win64-vc12/src
-    C:/Users/peter/gz-ws/sdformat/src/win/tinyxml
-    C:/Users/peter/gz-ws/FreeImage-vc12-x64-release-debug/Source
-    C:/Users/peter/gz-ws/tbb43_20141023oss/include
-    ${PTHREAD_INCLUDE_DIR})
-endif()
-
 include_directories(${INCLUDE_FOLDERS})
 
-link_directories(${GAZEBO_LIBRARY_DIRS})
+link_directories(${NTCORE_LIBDIR})
 
-if (WIN32)
-  add_library(WPILibSim ${SRC_FILES} ${COM_SRC_FILES})
-else()
-  add_library(WPILibSim SHARED ${SRC_FILES} ${COM_SRC_FILES})
-endif()
+add_library(${PROJECT_NAME} SHARED ${SRC_FILES} ${COM_SRC_FILES})
 
-target_link_libraries(WPILibSim gz_msgs ntcore ${PTHREAD_LIBRARY} ${Boost_LIBRARIES} ${GAZEBO_LIBRARIES} ${CMAKE_THREAD_LIBS_INIT}  -fPIC) # NetworkTables
+target_link_libraries(${PROJECT_NAME} ntcore)
 
-if (WIN32)
-  set_target_properties(${project}  PROPERTIES LINK_FLAGS "/DEBUG")
-endif()
-
-#copy to eclipse plugin
+set_target_properties(${PROJECT_NAME}
+  PROPERTIES
+  LIBRARY_OUTPUT_DIRECTORY ${SIMULATION_INSTALL_DIR}/lib)
diff --git a/wpilibc/simulation/include/AnalogGyro.h b/wpilibc/simulation/include/AnalogGyro.h
new file mode 100644
index 0000000..e117330
--- /dev/null
+++ b/wpilibc/simulation/include/AnalogGyro.h
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2016. 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 "GyroBase.h"
+#include "simulation/SimGyro.h"
+
+#include <memory>
+
+class AnalogInput;
+class AnalogModule;
+
+/**
+ * Use a rate gyro to return the robots heading relative to a starting position.
+ * The AnalogGyro class tracks the robots heading based on the starting position. As the robot
+ * rotates the new heading is computed by integrating the rate of rotation returned
+ * by the sensor. When the class is instantiated, it does a short calibration routine
+ * where it samples the gyro while at rest to determine the default offset. This is
+ * subtracted from each sample to determine the heading. This gyro class must be used
+ * with a channel that is assigned one of the Analog accumulators from the FPGA. See
+ * AnalogInput for the current accumulator assignments.
+ */
+class AnalogGyro : public GyroBase
+{
+public:
+	static const uint32_t kOversampleBits;
+	static const uint32_t kAverageBits;
+	static const float kSamplesPerSecond;
+	static const float kCalibrationSampleTime;
+	static const float kDefaultVoltsPerDegreePerSecond;
+
+	explicit AnalogGyro(uint32_t channel);
+	virtual ~AnalogGyro() = default;
+	float GetAngle() const;
+	void Calibrate() override;
+	double GetRate() const;
+	void Reset();
+
+private:
+	void InitAnalogGyro(int channel);
+
+	SimGyro* impl;
+
+	std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/simulation/include/AnalogInput.h b/wpilibc/simulation/include/AnalogInput.h
index 59a3a85..8e857b4 100644
--- a/wpilibc/simulation/include/AnalogInput.h
+++ b/wpilibc/simulation/include/AnalogInput.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "simulation/SimFloatInput.h"
diff --git a/wpilibc/simulation/include/AnalogPotentiometer.h b/wpilibc/simulation/include/AnalogPotentiometer.h
index 786f36f..2dbcb3e 100644
--- a/wpilibc/simulation/include/AnalogPotentiometer.h
+++ b/wpilibc/simulation/include/AnalogPotentiometer.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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"
diff --git a/wpilibc/simulation/include/Counter.h b/wpilibc/simulation/include/Counter.h
index 338efc0..2accacf 100644
--- a/wpilibc/simulation/include/Counter.h
+++ b/wpilibc/simulation/include/Counter.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "HAL/HAL.hpp"
diff --git a/wpilibc/simulation/include/CounterBase.h b/wpilibc/simulation/include/CounterBase.h
index 3352c29..683b681 100644
--- a/wpilibc/simulation/include/CounterBase.h
+++ b/wpilibc/simulation/include/CounterBase.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 /**
diff --git a/wpilibc/simulation/include/DigitalInput.h b/wpilibc/simulation/include/DigitalInput.h
index 1482e9c..92c4742 100644
--- a/wpilibc/simulation/include/DigitalInput.h
+++ b/wpilibc/simulation/include/DigitalInput.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "simulation/SimDigitalInput.h"
diff --git a/wpilibc/simulation/include/DoubleSolenoid.h b/wpilibc/simulation/include/DoubleSolenoid.h
index 122a439..ca38f1d 100644
--- a/wpilibc/simulation/include/DoubleSolenoid.h
+++ b/wpilibc/simulation/include/DoubleSolenoid.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "simulation/SimContinuousOutput.h"
diff --git a/wpilibc/simulation/include/DriverStation.h b/wpilibc/simulation/include/DriverStation.h
index f15985c..b96f1a7 100644
--- a/wpilibc/simulation/include/DriverStation.h
+++ b/wpilibc/simulation/include/DriverStation.h
@@ -1,112 +1,146 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
+#include "simulation/gz_msgs/msgs.h"
+
+#ifdef _WIN32
+  // Ensure that Winsock2.h is included before Windows.h, which can get
+  // pulled in by anybody (e.g., Boost).
+  #include <Winsock2.h>
+#endif
+
+#include <gazebo/transport/transport.hh>
 #include "SensorBase.h"
 #include "RobotState.h"
-#include "HAL/HAL.hpp"
-#include "HAL/cpp/Semaphore.hpp"
-#include "HAL/cpp/priority_mutex.h"
-#include "HAL/cpp/priority_condition_variable.h"
+#include <mutex>
 #include <condition_variable>
 
-struct HALControlWord;
+struct HALCommonControlData;
 class AnalogInput;
 
+using namespace gazebo;
+
 /**
- * Provide access to the network communication data to / from the Driver
- * Station.
+ * Provide access to the network communication data to / from the Driver Station.
  */
-class DriverStation : public SensorBase, public RobotStateInterface {
- public:
-  enum Alliance { kRed, kBlue, kInvalid };
+class DriverStation : public SensorBase, public RobotStateInterface
+{
+public:
+	enum Alliance
+	{
+		kRed,
+		kBlue,
+		kInvalid
+	};
 
-  virtual ~DriverStation();
-  static DriverStation &GetInstance();
-  static void ReportError(std::string error);
+	virtual ~DriverStation() = default;
+	static DriverStation &GetInstance();
+	static void ReportError(std::string error);
+	static void ReportWarning(std::string error);
+	static void ReportError(bool is_error, int32_t code, const std::string& error, const std::string& location, const std::string& stack);
 
-  static const uint32_t kJoystickPorts = 6;
+	static const uint32_t kBatteryChannel = 7;
+	static const uint32_t kJoystickPorts = 4;
+	static const uint32_t kJoystickAxes = 6;
 
-  float GetStickAxis(uint32_t stick, uint32_t axis);
-  int GetStickPOV(uint32_t stick, uint32_t pov);
-  uint32_t GetStickButtons(uint32_t stick) const;
-  bool GetStickButton(uint32_t stick, uint8_t button);
+	float GetStickAxis(uint32_t stick, uint32_t axis);
+	bool GetStickButton(uint32_t stick, uint32_t button);
+	short GetStickButtons(uint32_t stick);
 
-  int GetStickAxisCount(uint32_t stick) const;
-  int GetStickPOVCount(uint32_t stick) const;
-  int GetStickButtonCount(uint32_t stick) const;
+	float GetAnalogIn(uint32_t channel);
+	bool GetDigitalIn(uint32_t channel);
+	void SetDigitalOut(uint32_t channel, bool value);
+	bool GetDigitalOut(uint32_t channel);
 
-  bool GetJoystickIsXbox(uint32_t stick) const;
-  int GetJoystickType(uint32_t stick) const;
-  std::string GetJoystickName(uint32_t stick) const;
-  int GetJoystickAxisType(uint32_t stick, uint8_t axis) const;
+	bool IsEnabled() const;
+	bool IsDisabled() const;
+	bool IsAutonomous() const;
+	bool IsOperatorControl() const;
+	bool IsTest() const;
+	bool IsFMSAttached() const;
 
-  bool IsEnabled() const override;
-  bool IsDisabled() const override;
-  bool IsAutonomous() const override;
-  bool IsOperatorControl() const override;
-  bool IsTest() const override;
-  bool IsDSAttached() const;
-  bool IsNewControlData() const;
-  bool IsFMSAttached() const;
-  bool IsSysActive() const;
-  bool IsSysBrownedOut() const;
+	uint32_t GetPacketNumber() const;
+	Alliance GetAlliance() const;
+	uint32_t GetLocation() const;
+	void WaitForData();
+	double GetMatchTime() const;
+	float GetBatteryVoltage() const;
+	uint16_t GetTeamNumber() const;
 
-  Alliance GetAlliance() const;
-  uint32_t GetLocation() const;
-  void WaitForData();
-  double GetMatchTime() const;
-  float GetBatteryVoltage() const;
 
-  /** Only to be used to tell the Driver Station what code you claim to be
-   * executing
-   *   for diagnostic purposes only
-   * @param entering If true, starting disabled code; if false, leaving disabled
-   * code */
-  void InDisabled(bool entering) { m_userInDisabled = entering; }
-  /** Only to be used to tell the Driver Station what code you claim to be
-   * executing
-   *   for diagnostic purposes only
-   * @param entering If true, starting autonomous code; if false, leaving
-   * autonomous code */
-  void InAutonomous(bool entering) { m_userInAutonomous = entering; }
-  /** Only to be used to tell the Driver Station what code you claim to be
-   * executing
-   *   for diagnostic purposes only
-   * @param entering If true, starting teleop code; if false, leaving teleop
-   * code */
-  void InOperatorControl(bool entering) { m_userInTeleop = entering; }
-  /** Only to be used to tell the Driver Station what code you claim to be
-   * executing
-   *   for diagnostic purposes only
-   * @param entering If true, starting test code; if false, leaving test code */
-  void InTest(bool entering) { m_userInTest = entering; }
 
- protected:
-  DriverStation();
+	void IncrementUpdateNumber()
+	{
+		m_updateNumber++;
+	}
 
-  void GetData();
+	/** Only to be used to tell the Driver Station what code you claim to be executing
+	 *   for diagnostic purposes only
+	 * @param entering If true, starting disabled code; if false, leaving disabled code */
+	void InDisabled(bool entering)
+	{
+		m_userInDisabled = entering;
+	}
+	/** Only to be used to tell the Driver Station what code you claim to be executing
+	 *   for diagnostic purposes only
+	 * @param entering If true, starting autonomous code; if false, leaving autonomous code */
+	void InAutonomous(bool entering)
+	{
+		m_userInAutonomous = entering;
+	}
+	/** Only to be used to tell the Driver Station what code you claim to be executing
+	*   for diagnostic purposes only
+	* @param entering If true, starting teleop code; if false, leaving teleop code */
+	void InOperatorControl(bool entering)
+	{
+		m_userInTeleop = entering;
+	}
+	/** Only to be used to tell the Driver Station what code you claim to be executing
+	*   for diagnostic purposes only
+	* @param entering If true, starting test code; if false, leaving test code */
+	void InTest(bool entering)
+	{
+		m_userInTest = entering;
+	}
 
- private:
-  static DriverStation *m_instance;
-  void ReportJoystickUnpluggedError(std::string message);
-  void Run();
+protected:
+	DriverStation();
 
-  HALJoystickAxes m_joystickAxes[kJoystickPorts];
-  HALJoystickPOVs m_joystickPOVs[kJoystickPorts];
-  HALJoystickButtons m_joystickButtons[kJoystickPorts];
-  HALJoystickDescriptor m_joystickDescriptor[kJoystickPorts];
-  mutable Semaphore m_newControlData{Semaphore::kEmpty};
-  mutable priority_condition_variable m_packetDataAvailableCond;
-  priority_mutex m_packetDataAvailableMutex;
-  std::condition_variable_any m_waitForDataCond;
-  priority_mutex m_waitForDataMutex;
-  bool m_userInDisabled = false;
-  bool m_userInAutonomous = false;
-  bool m_userInTeleop = false;
-  bool m_userInTest = false;
-  double m_nextMessageTime = 0;
+private:
+	static void InitTask(DriverStation *ds);
+	static DriverStation *m_instance;
+	static uint8_t m_updateNumber;
+	///< TODO: Get rid of this and use the semaphore signaling
+	static const float kUpdatePeriod;
+
+    void stateCallback(const msgs::ConstDriverStationPtr &msg);
+    void joystickCallback(const msgs::ConstFRCJoystickPtr &msg, int i);
+    void joystickCallback0(const msgs::ConstFRCJoystickPtr &msg);
+    void joystickCallback1(const msgs::ConstFRCJoystickPtr &msg);
+    void joystickCallback2(const msgs::ConstFRCJoystickPtr &msg);
+    void joystickCallback3(const msgs::ConstFRCJoystickPtr &msg);
+    void joystickCallback4(const msgs::ConstFRCJoystickPtr &msg);
+    void joystickCallback5(const msgs::ConstFRCJoystickPtr &msg);
+
+	uint8_t m_digitalOut = 0;
+	std::condition_variable m_waitForDataCond;
+	std::mutex m_waitForDataMutex;
+  mutable std::recursive_mutex m_stateMutex;
+	std::recursive_mutex m_joystickMutex;
+	double m_approxMatchTimeOffset = 0;
+	bool m_userInDisabled = false;
+	bool m_userInAutonomous = false;
+	bool m_userInTeleop = false;
+	bool m_userInTest = false;
+
+    transport::SubscriberPtr stateSub;
+    transport::SubscriberPtr joysticksSub[6];
+    msgs::DriverStationPtr state;
+    msgs::FRCJoystickPtr joysticks[6];
 };
diff --git a/wpilibc/simulation/include/Encoder.h b/wpilibc/simulation/include/Encoder.h
index 89b1b3a..22b8657 100644
--- a/wpilibc/simulation/include/Encoder.h
+++ b/wpilibc/simulation/include/Encoder.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "simulation/SimEncoder.h"
diff --git a/wpilibc/simulation/include/Gyro.h b/wpilibc/simulation/include/Gyro.h
deleted file mode 100644
index 7e4e40a..0000000
--- a/wpilibc/simulation/include/Gyro.h
+++ /dev/null
@@ -1,60 +0,0 @@
-/*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. 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 $(WIND_BASE)/WPILib.  */
-/*----------------------------------------------------------------------------*/
-#pragma once
-
-#include "SensorBase.h"
-#include "PIDSource.h"
-#include "LiveWindow/LiveWindowSendable.h"
-#include "simulation/SimGyro.h"
-
-#include <memory>
-
-class AnalogInput;
-class AnalogModule;
-
-/**
- * Use a rate gyro to return the robots heading relative to a starting position.
- * The Gyro class tracks the robots heading based on the starting position. As the robot
- * rotates the new heading is computed by integrating the rate of rotation returned
- * by the sensor. When the class is instantiated, it does a short calibration routine
- * where it samples the gyro while at rest to determine the default offset. This is
- * subtracted from each sample to determine the heading. This gyro class must be used
- * with a channel that is assigned one of the Analog accumulators from the FPGA. See
- * AnalogInput for the current accumulator assignments.
- */
-class Gyro : public SensorBase, public PIDSource, public LiveWindowSendable
-{
-public:
-	static const uint32_t kOversampleBits;
-	static const uint32_t kAverageBits;
-	static const float kSamplesPerSecond;
-	static const float kCalibrationSampleTime;
-	static const float kDefaultVoltsPerDegreePerSecond;
-
-	explicit Gyro(uint32_t channel);
-	virtual ~Gyro() = default;
-	virtual float GetAngle() const;
-	virtual double GetRate() const;
-	virtual void Reset();
-
-	// PIDSource interface
-	void SetPIDSourceType(PIDSourceType pidSource) override;
-	double PIDGet() override;
-
-	void UpdateTable() override;
-	void StartLiveWindowMode() override;
-	void StopLiveWindowMode() override;
-	std::string GetSmartDashboardType() const override;
-	void InitTable(std::shared_ptr<ITable> subTable) override;
-	std::shared_ptr<ITable> GetTable() const override;
-
-private:
-	void InitGyro(int channel);
-
-	SimGyro* impl;
-
-	std::shared_ptr<ITable> m_table;
-};
diff --git a/wpilibc/simulation/include/IterativeRobot.h b/wpilibc/simulation/include/IterativeRobot.h
index 7c9104d..8a4cd4d 100644
--- a/wpilibc/simulation/include/IterativeRobot.h
+++ b/wpilibc/simulation/include/IterativeRobot.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "Timer.h"
diff --git a/wpilibc/simulation/include/Jaguar.h b/wpilibc/simulation/include/Jaguar.h
index 1f522d9..27325af 100644
--- a/wpilibc/simulation/include/Jaguar.h
+++ b/wpilibc/simulation/include/Jaguar.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SafePWM.h"
diff --git a/wpilibc/simulation/include/Joystick.h b/wpilibc/simulation/include/Joystick.h
index 0922359..e4e46da 100644
--- a/wpilibc/simulation/include/Joystick.h
+++ b/wpilibc/simulation/include/Joystick.h
@@ -1,16 +1,14 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #ifndef JOYSTICK_H_
 #define JOYSTICK_H_
 
-#include <cstdint>
 #include <memory>
-#include <vector>
 #include "GenericHID.h"
 #include "ErrorBase.h"
 
@@ -18,101 +16,64 @@
 
 /**
  * Handle input from standard Joysticks connected to the Driver Station.
- * This class handles standard input that comes from the Driver Station. Each
- * time a value is requested
- * the most recent value is returned. There is a single class instance for each
- * joystick and the mapping
+ * This class handles standard input that comes from the Driver Station. Each time a value is requested
+ * the most recent value is returned. There is a single class instance for each joystick and the mapping
  * of ports to hardware buttons depends on the code in the driver station.
  */
-class Joystick : public GenericHID, public ErrorBase {
- public:
-  static const uint32_t kDefaultXAxis = 0;
-  static const uint32_t kDefaultYAxis = 1;
-  static const uint32_t kDefaultZAxis = 2;
-  static const uint32_t kDefaultTwistAxis = 2;
-  static const uint32_t kDefaultThrottleAxis = 3;
-  typedef enum {
-    kXAxis,
-    kYAxis,
-    kZAxis,
-    kTwistAxis,
-    kThrottleAxis,
-    kNumAxisTypes
-  } AxisType;
-  static const uint32_t kDefaultTriggerButton = 1;
-  static const uint32_t kDefaultTopButton = 2;
-  typedef enum { kTriggerButton, kTopButton, kNumButtonTypes } ButtonType;
-  typedef enum { kLeftRumble, kRightRumble } RumbleType;
-  typedef enum {
-    kUnknown = -1,
-    kXInputUnknown = 0,
-    kXInputGamepad = 1,
-    kXInputWheel = 2,
-    kXInputArcadeStick = 3,
-    kXInputFlightStick = 4,
-    kXInputDancePad = 5,
-    kXInputGuitar = 6,
-    kXInputGuitar2 = 7,
-    kXInputDrumKit = 8,
-    kXInputGuitar3 = 11,
-    kXInputArcadePad = 19,
-    kHIDJoystick = 20,
-    kHIDGamepad = 21,
-    kHIDDriving = 22,
-    kHIDFlight = 23,
-    kHID1stPerson = 24
-  } HIDType;
-  explicit Joystick(uint32_t port);
-  Joystick(uint32_t port, uint32_t numAxisTypes, uint32_t numButtonTypes);
-  virtual ~Joystick() = default;
+class Joystick : public GenericHID, public ErrorBase
+{
+public:
+	static const uint32_t kDefaultXAxis = 1;
+	static const uint32_t kDefaultYAxis = 2;
+	static const uint32_t kDefaultZAxis = 3;
+	static const uint32_t kDefaultTwistAxis = 4;
+	static const uint32_t kDefaultThrottleAxis = 3;
+	typedef enum
+	{
+		kXAxis, kYAxis, kZAxis, kTwistAxis, kThrottleAxis, kNumAxisTypes
+	} AxisType;
+	static const uint32_t kDefaultTriggerButton = 1;
+	static const uint32_t kDefaultTopButton = 2;
+	typedef enum
+	{
+		kTriggerButton, kTopButton, kNumButtonTypes
+	} ButtonType;
 
-  Joystick(const Joystick&) = delete;
-  Joystick& operator=(const Joystick&) = delete;
+	explicit Joystick(uint32_t port);
+	Joystick(uint32_t port, uint32_t numAxisTypes, uint32_t numButtonTypes);
+	virtual ~Joystick() = default;
 
-  uint32_t GetAxisChannel(AxisType axis) const;
-  void SetAxisChannel(AxisType axis, uint32_t channel);
+    Joystick(const Joystick&) = delete;
+    Joystick& operator=(const Joystick&) = delete;
 
-  virtual float GetX(JoystickHand hand = kRightHand) const override;
-  virtual float GetY(JoystickHand hand = kRightHand) const override;
-  virtual float GetZ() const override;
-  virtual float GetTwist() const override;
-  virtual float GetThrottle() const override;
-  virtual float GetAxis(AxisType axis) const;
-  float GetRawAxis(uint32_t axis) const override;
+	uint32_t GetAxisChannel(AxisType axis);
+	void SetAxisChannel(AxisType axis, uint32_t channel);
 
-  virtual bool GetTrigger(JoystickHand hand = kRightHand) const override;
-  virtual bool GetTop(JoystickHand hand = kRightHand) const override;
-  virtual bool GetBumper(JoystickHand hand = kRightHand) const override;
-  virtual bool GetRawButton(uint32_t button) const override;
-  virtual int GetPOV(uint32_t pov = 0) const override;
-  bool GetButton(ButtonType button) const;
-  static Joystick *GetStickForPort(uint32_t port);
+	virtual float GetX(JoystickHand hand = kRightHand) const override;
+	virtual float GetY(JoystickHand hand = kRightHand) const override;
+	virtual float GetZ() const override;
+	virtual float GetTwist() const override;
+	virtual float GetThrottle() const override;
+	virtual float GetAxis(AxisType axis) const;
+	float GetRawAxis(uint32_t axis) const override;
 
-  virtual float GetMagnitude() const;
-  virtual float GetDirectionRadians() const;
-  virtual float GetDirectionDegrees() const;
+	virtual bool GetTrigger(JoystickHand hand = kRightHand) const override;
+	virtual bool GetTop(JoystickHand hand = kRightHand) const override;
+	virtual bool GetBumper(JoystickHand hand = kRightHand) const override;
+	virtual bool GetRawButton(uint32_t button) const override;
+	virtual int GetPOV(uint32_t pov = 1) const override;
+	bool GetButton(ButtonType button) const;
+	static Joystick* GetStickForPort(uint32_t port);
 
-  bool GetIsXbox() const;
-  Joystick::HIDType GetType() const;
-  std::string GetName() const;
-  int GetAxisType(uint8_t axis) const;
+	virtual float GetMagnitude() const;
+	virtual float GetDirectionRadians() const;
+	virtual float GetDirectionDegrees() const;
 
-  int GetAxisCount() const;
-  int GetButtonCount() const;
-  int GetPOVCount() const;
-
-  void SetRumble(RumbleType type, float value);
-  void SetOutput(uint8_t outputNumber, bool value);
-  void SetOutputs(uint32_t value);
-
- private:
-  DriverStation &m_ds;
-  uint32_t m_port;
-  ::std::vector<uint32_t> m_axes;
-  ::std::vector<uint32_t> m_buttons;
-  uint32_t m_outputs = 0;
-  uint16_t m_leftRumble = 0;
-  uint16_t m_rightRumble = 0;
+private:
+	DriverStation &m_ds;
+	uint32_t m_port;
+	std::unique_ptr<uint32_t[]> m_axes;
+	std::unique_ptr<uint32_t[]> m_buttons;
 };
 
 #endif
diff --git a/wpilibc/simulation/include/MotorSafety.h b/wpilibc/simulation/include/MotorSafety.h
index c718806..82c77d8 100644
--- a/wpilibc/simulation/include/MotorSafety.h
+++ b/wpilibc/simulation/include/MotorSafety.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #define DEFAULT_SAFETY_EXPIRATION 0.1
diff --git a/wpilibc/simulation/include/MotorSafetyHelper.h b/wpilibc/simulation/include/MotorSafetyHelper.h
index bbe7658..f124605 100644
--- a/wpilibc/simulation/include/MotorSafetyHelper.h
+++ b/wpilibc/simulation/include/MotorSafetyHelper.h
@@ -1,9 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "ErrorBase.h"
diff --git a/wpilibc/simulation/include/Notifier.h b/wpilibc/simulation/include/Notifier.h
new file mode 100644
index 0000000..0160aa4
--- /dev/null
+++ b/wpilibc/simulation/include/Notifier.h
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2016. 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 <atomic>
+#include <functional>
+#include <list>
+#include <thread>
+
+#include "ErrorBase.h"
+#include "HAL/cpp/priority_mutex.h"
+
+typedef std::function<void()> TimerEventHandler;
+
+class Notifier : public ErrorBase {
+ public:
+  explicit Notifier(TimerEventHandler handler);
+
+  template <typename Callable, typename Arg, typename... Args>
+  Notifier(Callable&& f, Arg&& arg, Args&&... args)
+      : Notifier(std::bind(std::forward<Callable>(f),
+                           std::forward<Arg>(arg),
+                           std::forward<Args>(args)...)) {}
+  virtual ~Notifier();
+
+  Notifier(const Notifier&) = delete;
+  Notifier& operator=(const Notifier&) = delete;
+
+  void StartSingle(double delay);
+  void StartPeriodic(double period);
+  void Stop();
+
+ private:
+  static std::list<Notifier*> timerQueue;
+  static priority_recursive_mutex queueMutex;
+  static priority_mutex halMutex;
+  static void *m_notifier;
+  static std::atomic<int> refcount;
+
+  // Process the timer queue on a timer event
+  static void ProcessQueue(uint32_t mask, void *params);
+
+  // Update the FPGA alarm since the queue has changed
+  static void UpdateAlarm();
+
+  // Insert the Notifier in the timer queue
+  void InsertInQueue(bool reschedule);
+
+  // Delete this Notifier from the timer queue
+  void DeleteFromQueue();
+
+  // Address of the handler
+  TimerEventHandler m_handler;
+  // The relative time (either periodic or single)
+  double m_period = 0;
+  // Absolute expiration time for the current event
+  double m_expirationTime = 0;
+  // True if this is a periodic event
+  bool m_periodic = false;
+  // Indicates if this entry is queued
+  bool m_queued = false;
+  // Held by interrupt manager task while handler call is in progress
+  priority_mutex m_handlerMutex;
+  static std::thread m_task;
+  static std::atomic<bool> m_stopped;
+  static void Run();
+};
diff --git a/wpilibc/simulation/include/PWM.h b/wpilibc/simulation/include/PWM.h
index 52007fb..bc0b7da 100644
--- a/wpilibc/simulation/include/PWM.h
+++ b/wpilibc/simulation/include/PWM.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SensorBase.h"
diff --git a/wpilibc/simulation/include/Relay.h b/wpilibc/simulation/include/Relay.h
index abc9ad5..5a1c680 100644
--- a/wpilibc/simulation/include/Relay.h
+++ b/wpilibc/simulation/include/Relay.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "MotorSafety.h"
diff --git a/wpilibc/simulation/include/RobotBase.h b/wpilibc/simulation/include/RobotBase.h
index a88dbb2..ff9c015 100644
--- a/wpilibc/simulation/include/RobotBase.h
+++ b/wpilibc/simulation/include/RobotBase.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "Base.h"
@@ -47,6 +49,7 @@
     RobotBase& operator=(const RobotBase&) = delete;
 
 	DriverStation &m_ds;
+  transport::SubscriberPtr time_sub;
 
 private:
 	static RobotBase *m_instance;
diff --git a/wpilibc/simulation/include/RobotDrive.h b/wpilibc/simulation/include/RobotDrive.h
index a181e46..8e9f8ca 100644
--- a/wpilibc/simulation/include/RobotDrive.h
+++ b/wpilibc/simulation/include/RobotDrive.h
@@ -1,12 +1,15 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "ErrorBase.h"
 #include <stdlib.h>
+#include <memory>
 #include "MotorSafety.h"
 #include "MotorSafetyHelper.h"
 
@@ -37,11 +40,17 @@
 			uint32_t frontRightMotorChannel, uint32_t rearRightMotorChannel);
 	RobotDrive(SpeedController *leftMotor, SpeedController *rightMotor);
 	RobotDrive(SpeedController &leftMotor, SpeedController &rightMotor);
+	RobotDrive(std::shared_ptr<SpeedController> leftMotor,
+			   std::shared_ptr<SpeedController> rightMotor);
 	RobotDrive(SpeedController *frontLeftMotor, SpeedController *rearLeftMotor,
 			SpeedController *frontRightMotor, SpeedController *rearRightMotor);
 	RobotDrive(SpeedController &frontLeftMotor, SpeedController &rearLeftMotor,
 			SpeedController &frontRightMotor, SpeedController &rearRightMotor);
-	virtual ~RobotDrive();
+	RobotDrive(std::shared_ptr<SpeedController> frontLeftMotor,
+			  std::shared_ptr<SpeedController> rearLeftMotor,
+			  std::shared_ptr<SpeedController> frontRightMotor,
+			  std::shared_ptr<SpeedController> rearRightMotor);
+	virtual ~RobotDrive() = default;
 
     RobotDrive(const RobotDrive&) = delete;
     RobotDrive& operator=(const RobotDrive&) = delete;
@@ -85,14 +94,14 @@
 
 	static const int32_t kMaxNumberOfMotors = 4;
 
-	int32_t m_invertedMotors[kMaxNumberOfMotors];
+	int32_t m_invertedMotors[kMaxNumberOfMotors] = {1,1,1,1};
 	float m_sensitivity = 0.5;
 	double m_maxOutput = 1.0;
 	bool m_deleteSpeedControllers;
-	SpeedController *m_frontLeftMotor = nullptr;
-	SpeedController *m_frontRightMotor = nullptr;
-	SpeedController *m_rearLeftMotor = nullptr;
-	SpeedController *m_rearRightMotor = nullptr;
+	std::shared_ptr<SpeedController> m_frontLeftMotor;
+	std::shared_ptr<SpeedController> m_frontRightMotor;
+	std::shared_ptr<SpeedController> m_rearLeftMotor;
+	std::shared_ptr<SpeedController> m_rearRightMotor;
 	// FIXME: MotorSafetyHelper *m_safetyHelper;
 
 private:
diff --git a/wpilibc/simulation/include/SafePWM.h b/wpilibc/simulation/include/SafePWM.h
index 577d853..4787cee 100644
--- a/wpilibc/simulation/include/SafePWM.h
+++ b/wpilibc/simulation/include/SafePWM.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "MotorSafety.h"
diff --git a/wpilibc/simulation/include/SampleRobot.h b/wpilibc/simulation/include/SampleRobot.h
index 38cb37d..a87bb4e 100644
--- a/wpilibc/simulation/include/SampleRobot.h
+++ b/wpilibc/simulation/include/SampleRobot.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "RobotBase.h"
diff --git a/wpilibc/simulation/include/Solenoid.h b/wpilibc/simulation/include/Solenoid.h
index b91da6e..4f6ac3a 100644
--- a/wpilibc/simulation/include/Solenoid.h
+++ b/wpilibc/simulation/include/Solenoid.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "simulation/SimContinuousOutput.h"
diff --git a/wpilibc/simulation/include/SpeedController.h b/wpilibc/simulation/include/SpeedController.h
index 96b6b17..e665d06 100644
--- a/wpilibc/simulation/include/SpeedController.h
+++ b/wpilibc/simulation/include/SpeedController.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "PIDOutput.h"
diff --git a/wpilibc/simulation/include/Talon.h b/wpilibc/simulation/include/Talon.h
index 4b7794a..d56d5ba 100644
--- a/wpilibc/simulation/include/Talon.h
+++ b/wpilibc/simulation/include/Talon.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SafePWM.h"
diff --git a/wpilibc/simulation/include/Victor.h b/wpilibc/simulation/include/Victor.h
index b629bb4..ef3646e 100644
--- a/wpilibc/simulation/include/Victor.h
+++ b/wpilibc/simulation/include/Victor.h
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #pragma once
 
 #include "SafePWM.h"
diff --git a/wpilibc/simulation/include/WPILib.h b/wpilibc/simulation/include/WPILib.h
index b3477d4..d4e9bf2 100644
--- a/wpilibc/simulation/include/WPILib.h
+++ b/wpilibc/simulation/include/WPILib.h
@@ -47,7 +47,7 @@
 #include "Counter.h"
 #include "DigitalInput.h"
 #include "Encoder.h"
-#include "Gyro.h"
+#include "AnalogGyro.h"
 #include "GenericHID.h"
 #include "Joystick.h"
 #include "PIDController.h"
diff --git a/wpilibc/simulation/include/simulation/MainNode.h b/wpilibc/simulation/include/simulation/MainNode.h
index a76ef50..416c7a5 100644
--- a/wpilibc/simulation/include/simulation/MainNode.h
+++ b/wpilibc/simulation/include/simulation/MainNode.h
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014-2016. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
 
 #ifndef _SIM_MAIN_NODE_H
 #define _SIM_MAIN_NODE_H
@@ -39,10 +45,16 @@
 	transport::NodePtr main;
 private:
 	MainNode() {
-		gazebo::client::setup();
-		main = transport::NodePtr(new transport::Node());
-		main->Init("frc");
-		gazebo::transport::run();
+		bool success = gazebo::client::setup();
+
+    if (success){
+  		main = transport::NodePtr(new transport::Node());
+  		main->Init("frc");
+   		gazebo::transport::run();
+    }
+    else {
+      std::cout << "An error has occured setting up gazebo_client!" << std::endl;
+    }
 	}
 };
 
diff --git a/wpilibc/simulation/include/simulation/SimContinuousOutput.h b/wpilibc/simulation/include/simulation/SimContinuousOutput.h
index 06a28e9..2c0d5da 100644
--- a/wpilibc/simulation/include/simulation/SimContinuousOutput.h
+++ b/wpilibc/simulation/include/simulation/SimContinuousOutput.h
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014-2016. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
 
 
 #ifndef _SIM_SPEED_CONTROLLER_H
diff --git a/wpilibc/simulation/include/simulation/SimDigitalInput.h b/wpilibc/simulation/include/simulation/SimDigitalInput.h
index c85c19f..ca14b0f 100644
--- a/wpilibc/simulation/include/simulation/SimDigitalInput.h
+++ b/wpilibc/simulation/include/simulation/SimDigitalInput.h
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014-2016. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
 
 
 #ifndef _SIM_DIGITAL_INPUT_H
diff --git a/wpilibc/simulation/include/simulation/SimEncoder.h b/wpilibc/simulation/include/simulation/SimEncoder.h
index 9f37723..254cbe4 100644
--- a/wpilibc/simulation/include/simulation/SimEncoder.h
+++ b/wpilibc/simulation/include/simulation/SimEncoder.h
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014-2016. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
 
 
 #ifndef _SIM_ENCODER_H
diff --git a/wpilibc/simulation/include/simulation/SimFloatInput.h b/wpilibc/simulation/include/simulation/SimFloatInput.h
index 6271b96..bdc1c4c 100644
--- a/wpilibc/simulation/include/simulation/SimFloatInput.h
+++ b/wpilibc/simulation/include/simulation/SimFloatInput.h
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014-2016. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
 
 
 #ifndef _SIM_FLOAT_INPUT_H
diff --git a/wpilibc/simulation/include/simulation/SimGyro.h b/wpilibc/simulation/include/simulation/SimGyro.h
index fcb81f6..85d9d27 100644
--- a/wpilibc/simulation/include/simulation/SimGyro.h
+++ b/wpilibc/simulation/include/simulation/SimGyro.h
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014-2016. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
 
 
 #ifndef _SIM_GYRO_H
diff --git a/wpilibc/simulation/include/simulation/simTime.h b/wpilibc/simulation/include/simulation/simTime.h
index 20fe0c5..bd87ffa 100644
--- a/wpilibc/simulation/include/simulation/simTime.h
+++ b/wpilibc/simulation/include/simulation/simTime.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014-2016. 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
 
 
diff --git a/wpilibc/simulation/src/AnalogGyro.cpp b/wpilibc/simulation/src/AnalogGyro.cpp
new file mode 100644
index 0000000..32196a8
--- /dev/null
+++ b/wpilibc/simulation/src/AnalogGyro.cpp
@@ -0,0 +1,89 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2016. 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 "Timer.h"
+#include "WPIErrors.h"
+#include "LiveWindow/LiveWindow.h"
+
+const uint32_t AnalogGyro::kOversampleBits = 10;
+const uint32_t AnalogGyro::kAverageBits = 0;
+const float AnalogGyro::kSamplesPerSecond = 50.0;
+const float AnalogGyro::kCalibrationSampleTime = 5.0;
+const float AnalogGyro::kDefaultVoltsPerDegreePerSecond = 0.007;
+
+/**
+ * Initialize the gyro.
+ * Calibrate the gyro by running for a number of samples and computing the center value for this
+ * part. Then use the center value as the Accumulator center value for subsequent measurements.
+ * It's important to make sure that the robot is not moving while the centering calculations are
+ * in progress, this is typically done when the robot is first turned on while it's sitting at
+ * rest before the competition starts.
+ */
+void AnalogGyro::InitAnalogGyro(int channel)
+{
+	SetPIDSourceType(PIDSourceType::kDisplacement);
+
+	char buffer[50];
+	int n = sprintf(buffer, "analog/%d", channel);
+	impl = new SimGyro(buffer);
+
+	LiveWindow::GetInstance()->AddSensor("AnalogGyro", channel, this);
+}
+
+/**
+ * AnalogGyro constructor with only a channel..
+ *
+ * @param channel The analog channel the gyro is connected to.
+ */
+AnalogGyro::AnalogGyro(uint32_t channel)
+{
+    InitAnalogGyro(channel);
+}
+
+/**
+ * Reset the gyro.
+ * Resets the gyro to a heading of zero. This can be used if there is significant
+ * drift in the gyro and it needs to be recalibrated after it has been running.
+ */
+void AnalogGyro::Reset()
+{
+    impl->Reset();
+}
+
+void AnalogGyro::Calibrate(){
+	Reset();
+}
+
+/**
+ * Return the actual angle in degrees that the robot is currently facing.
+ *
+ * The angle is based on the current accumulator value corrected by the oversampling rate, the
+ * gyro type and the A/D calibration values.
+ * The angle is continuous, that is can go beyond 360 degrees. This make algorithms that wouldn't
+ * want to see a discontinuity in the gyro output as it sweeps past 0 on the second time around.
+ *
+ * @return the current heading of the robot in degrees. This heading is based on integration
+ * of the returned rate from the gyro.
+ */
+float AnalogGyro::GetAngle() const
+{
+    return impl->GetAngle();
+}
+
+
+/**
+ * Return the rate of rotation of the gyro
+ *
+ * The rate is based on the most recent reading of the gyro analog value
+ *
+ * @return the current rate in degrees per second
+ */
+double AnalogGyro::GetRate() const
+{
+    return impl->GetVelocity();
+}
diff --git a/wpilibc/simulation/src/AnalogInput.cpp b/wpilibc/simulation/src/AnalogInput.cpp
index 71c48c5..7979edf 100644
--- a/wpilibc/simulation/src/AnalogInput.cpp
+++ b/wpilibc/simulation/src/AnalogInput.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "AnalogInput.h"
diff --git a/wpilibc/simulation/src/AnalogPotentiometer.cpp b/wpilibc/simulation/src/AnalogPotentiometer.cpp
index fa312c1..c71fda9 100644
--- a/wpilibc/simulation/src/AnalogPotentiometer.cpp
+++ b/wpilibc/simulation/src/AnalogPotentiometer.cpp
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "AnalogPotentiometer.h"
 
diff --git a/wpilibc/simulation/src/DigitalInput.cpp b/wpilibc/simulation/src/DigitalInput.cpp
index e7ae36d..5911fb3 100644
--- a/wpilibc/simulation/src/DigitalInput.cpp
+++ b/wpilibc/simulation/src/DigitalInput.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "DigitalInput.h"
diff --git a/wpilibc/simulation/src/DoubleSolenoid.cpp b/wpilibc/simulation/src/DoubleSolenoid.cpp
index d1d0917..6180fb4 100644
--- a/wpilibc/simulation/src/DoubleSolenoid.cpp
+++ b/wpilibc/simulation/src/DoubleSolenoid.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "DoubleSolenoid.h"
diff --git a/wpilibc/simulation/src/DriverStation.cpp b/wpilibc/simulation/src/DriverStation.cpp
index 39802ab..274cb18 100644
--- a/wpilibc/simulation/src/DriverStation.cpp
+++ b/wpilibc/simulation/src/DriverStation.cpp
@@ -1,227 +1,82 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "DriverStation.h"
-#include "AnalogInput.h"
 #include "Timer.h"
-#include "NetworkCommunication/FRCComm.h"
-#include "MotorSafetyHelper.h"
+#include "simulation/MainNode.h"
+//#include "MotorSafetyHelper.h"
 #include "Utility.h"
 #include "WPIErrors.h"
 #include <string.h>
 #include "Log.hpp"
+#include "boost/mem_fn.hpp"
 
 // set the logging level
 TLogLevel dsLogLevel = logDEBUG;
-const double JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL = 1.0;
 
 #define DS_LOG(level) \
-  if (level > dsLogLevel) ; \
-  else Log().Get(level)
+    if (level > dsLogLevel) ; \
+    else Log().Get(level)
 
+const uint32_t DriverStation::kBatteryChannel;
 const uint32_t DriverStation::kJoystickPorts;
+const uint32_t DriverStation::kJoystickAxes;
+const float DriverStation::kUpdatePeriod = 0.02;
+uint8_t DriverStation::m_updateNumber = 0;
 
 /**
- * DriverStation constructor.
+ * DriverStation contructor.
  *
  * This is only called once the first time GetInstance() is called
  */
 DriverStation::DriverStation() {
-  // All joysticks should default to having zero axes, povs and buttons, so
-  // uninitialized memory doesn't get sent to speed controllers.
-  for (unsigned int i = 0; i < kJoystickPorts; i++) {
-    m_joystickAxes[i].count = 0;
-    m_joystickPOVs[i].count = 0;
-    m_joystickButtons[i].count = 0;
-    m_joystickDescriptor[i].isXbox = 0;
-    m_joystickDescriptor[i].type = -1;
-    m_joystickDescriptor[i].name[0] = '\0';
-  }
-  // Register that semaphore with the network communications task.
-  // It will signal when new packet data is available.
-  HALSetNewDataSem(m_packetDataAvailableCond.native_handle());
+	state = msgs::DriverStationPtr(new msgs::DriverStation());
+	stateSub = MainNode::Subscribe("~/ds/state",
+		                   &DriverStation::stateCallback, this);
+	// TODO: for loop + boost bind
+	joysticks[0] = msgs::FRCJoystickPtr(new msgs::FRCJoystick());
+	joysticksSub[0] =  MainNode::Subscribe("~/ds/joysticks/0",
+		                           &DriverStation::joystickCallback0, this);
+	joysticks[1] = msgs::FRCJoystickPtr(new msgs::FRCJoystick());
+	joysticksSub[1] =  MainNode::Subscribe("~/ds/joysticks/1",
+		                           &DriverStation::joystickCallback1, this);
+	joysticks[2] = msgs::FRCJoystickPtr(new msgs::FRCJoystick());
+	joysticksSub[2] =  MainNode::Subscribe("~/ds/joysticks/2",
+		                           &DriverStation::joystickCallback2, this);
+	joysticks[3] = msgs::FRCJoystickPtr(new msgs::FRCJoystick());
+	joysticksSub[3] =  MainNode::Subscribe("~/ds/joysticks/5",
+	                                   &DriverStation::joystickCallback3, this);
+	joysticks[4] = msgs::FRCJoystickPtr(new msgs::FRCJoystick());
+	joysticksSub[4] =  MainNode::Subscribe("~/ds/joysticks/4",
+	                                   &DriverStation::joystickCallback4, this);
+	joysticks[5] = msgs::FRCJoystickPtr(new msgs::FRCJoystick());
+	joysticksSub[5] =  MainNode::Subscribe("~/ds/joysticks/5",
+	                                   &DriverStation::joystickCallback5, this);
 
-  AddToSingletonList();
-
-}
-
-void DriverStation::Run() {
-  int period = 0;
-  while (true) {
-    {
-      std::unique_lock<priority_mutex> lock(m_packetDataAvailableMutex);
-      m_packetDataAvailableCond.wait(lock);
-    }
-    GetData();
-    m_waitForDataCond.notify_all();
-
-    if (++period >= 4) {
-      MotorSafetyHelper::CheckMotors();
-      period = 0;
-    }
-    if (m_userInDisabled) HALNetworkCommunicationObserveUserProgramDisabled();
-    if (m_userInAutonomous) HALNetworkCommunicationObserveUserProgramAutonomous();
-    if (m_userInTeleop) HALNetworkCommunicationObserveUserProgramTeleop();
-    if (m_userInTest) HALNetworkCommunicationObserveUserProgramTest();
-  }
+	AddToSingletonList();
 }
 
 /**
- * Return a reference to the singleton DriverStation.
- * @return Pointer to the DS instance
+ * Return a pointer to the singleton DriverStation.
  */
-DriverStation &DriverStation::GetInstance() {
-  static DriverStation instance;
-  return instance;
+DriverStation& DriverStation::GetInstance()
+{
+	static DriverStation instance;
+	return instance;
 }
 
 /**
- * Copy data from the DS task for the user.
- * If no new data exists, it will just be returned, otherwise
- * the data will be copied from the DS polling loop.
- */
-void DriverStation::GetData() {
-  // Get the status of all of the joysticks
-  for (uint8_t stick = 0; stick < kJoystickPorts; stick++) {
-    HALGetJoystickAxes(stick, &m_joystickAxes[stick]);
-    HALGetJoystickPOVs(stick, &m_joystickPOVs[stick]);
-    HALGetJoystickButtons(stick, &m_joystickButtons[stick]);
-    HALGetJoystickDescriptor(stick, &m_joystickDescriptor[stick]);
-  }
-  m_newControlData.give();
-}
-
-/**
- * Read the battery voltage.
+ * Read the battery voltage. Hardcoded to 12 volts for Simulation.
  *
- * @return The battery voltage in Volts.
+ * @return The battery voltage.
  */
-float DriverStation::GetBatteryVoltage() const {
-  int32_t status = 0;
-  float voltage = getVinVoltage(&status);
-  wpi_setErrorWithContext(status, "getVinVoltage");
-
-  return voltage;
-}
-
-/**
- * Reports errors related to unplugged joysticks
- * Throttles the errors so that they don't overwhelm the DS
- */
-void DriverStation::ReportJoystickUnpluggedError(std::string message) {
-  double currentTime = Timer::GetFPGATimestamp();
-  if (currentTime > m_nextMessageTime) {
-    ReportError(message);
-    m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL;
-  }
-}
-
-/**
- * Returns the number of axes on a given joystick port
- *
- * @param stick The joystick port number
- * @return The number of axes on the indicated joystick
- */
-int DriverStation::GetStickAxisCount(uint32_t stick) const {
-  if (stick >= kJoystickPorts) {
-    wpi_setWPIError(BadJoystickIndex);
-    return 0;
-  }
-  HALJoystickAxes joystickAxes;
-  HALGetJoystickAxes(stick, &joystickAxes);
-  return joystickAxes.count;
-}
-
-/**
- * Returns the name of the joystick at the given port
- *
- * @param stick The joystick port number
- * @return The name of the joystick at the given port
- */
-std::string DriverStation::GetJoystickName(uint32_t stick) const {
-  if (stick >= kJoystickPorts) {
-    wpi_setWPIError(BadJoystickIndex);
-  }
-  std::string retVal(m_joystickDescriptor[0].name);
-  return retVal;
-}
-
-/**
- * Returns the type of joystick at a given port
- *
- * @param stick The joystick port number
- * @return The HID type of joystick at the given port
- */
-int DriverStation::GetJoystickType(uint32_t stick) const {
-  if (stick >= kJoystickPorts) {
-    wpi_setWPIError(BadJoystickIndex);
-    return -1;
-  }
-  return (int)m_joystickDescriptor[stick].type;
-}
-
-/**
- * Returns a boolean indicating if the controller is an xbox controller.
- *
- * @param stick The joystick port number
- * @return A boolean that is true if the controller is an xbox controller.
- */
-bool DriverStation::GetJoystickIsXbox(uint32_t stick) const {
-  if (stick >= kJoystickPorts) {
-    wpi_setWPIError(BadJoystickIndex);
-    return false;
-  }
-  return (bool)m_joystickDescriptor[stick].isXbox;
-}
-
-/**
- * Returns the types of Axes on a given joystick port
- *
- * @param stick The joystick port number and the target axis
- * @return What type of axis the axis is reporting to be
- */
-int DriverStation::GetJoystickAxisType(uint32_t stick, uint8_t axis) const {
-  if (stick >= kJoystickPorts) {
-    wpi_setWPIError(BadJoystickIndex);
-    return -1;
-  }
-  return m_joystickDescriptor[stick].axisTypes[axis];
-}
-
-/**
- * Returns the number of POVs on a given joystick port
- *
- * @param stick The joystick port number
- * @return The number of POVs on the indicated joystick
- */
-int DriverStation::GetStickPOVCount(uint32_t stick) const {
-  if (stick >= kJoystickPorts) {
-    wpi_setWPIError(BadJoystickIndex);
-    return 0;
-  }
-  HALJoystickPOVs joystickPOVs;
-  HALGetJoystickPOVs(stick, &joystickPOVs);
-  return joystickPOVs.count;
-}
-
-/**
- * Returns the number of buttons on a given joystick port
- *
- * @param stick The joystick port number
- * @return The number of buttons on the indicated joystick
- */
-int DriverStation::GetStickButtonCount(uint32_t stick) const {
-  if (stick >= kJoystickPorts) {
-    wpi_setWPIError(BadJoystickIndex);
-    return 0;
-  }
-  HALJoystickButtons joystickButtons;
-  HALGetJoystickButtons(stick, &joystickButtons);
-  return joystickButtons.count;
+float DriverStation::GetBatteryVoltage() const
+{
+	return 12.0; // 12 volts all the time!
 }
 
 /**
@@ -232,287 +87,310 @@
  * @param axis The analog axis value to read from the joystick.
  * @return The value of the axis on the joystick.
  */
-float DriverStation::GetStickAxis(uint32_t stick, uint32_t axis) {
-  if (stick >= kJoystickPorts) {
-    wpi_setWPIError(BadJoystickIndex);
-    return 0;
-  }
+float DriverStation::GetStickAxis(uint32_t stick, uint32_t axis)
+{
+	if (axis < 0 || axis > (kJoystickAxes - 1))
+	{
+		wpi_setWPIError(BadJoystickAxis);
+		return 0.0;
+	}
+	if (stick < 0 || stick > 5)
+	{
+		wpi_setWPIError(BadJoystickIndex);
+		return 0.0;
+	}
 
-  if (axis >= m_joystickAxes[stick].count) {
-    if (axis >= kMaxJoystickAxes) {
-      wpi_setWPIError(BadJoystickAxis);
-    }
-    else {
-      ReportJoystickUnpluggedError(
-          "WARNING: Joystick Axis missing, check if all controllers are "
-          "plugged in\n");
-    }
-    return 0.0f;
-  }
-
-  int8_t value = m_joystickAxes[stick].axes[axis];
-
-  if (value < 0) {
-    return value / 128.0f;
-  } else {
-    return value / 127.0f;
-  }
+	std::unique_lock<std::recursive_mutex> lock(m_joystickMutex);
+	if (joysticks[stick] == nullptr || axis >= joysticks[stick]->axes().size())
+	{
+		return 0.0;
+	}
+	return joysticks[stick]->axes(axis);
 }
 
 /**
- * Get the state of a POV on the joystick.
+ * The state of a specific button (1 - 12) on the joystick.
+ * This method only works in simulation, but is more efficient than GetStickButtons.
  *
- * @return the angle of the POV in degrees, or -1 if the POV is not pressed.
+ * @param stick The joystick to read.
+ * @param button The button number to check.
+ * @return If the button is pressed.
  */
-int DriverStation::GetStickPOV(uint32_t stick, uint32_t pov) {
-  if (stick >= kJoystickPorts) {
-    wpi_setWPIError(BadJoystickIndex);
-    return -1;
-  }
+bool DriverStation::GetStickButton(uint32_t stick, uint32_t button)
+{
+    if (stick < 0 || stick >= 6)
+	{
+		wpi_setWPIErrorWithContext(ParameterOutOfRange, "stick must be between 0 and 5");
+		return false;
+	}
 
-  if (pov >= m_joystickPOVs[stick].count) {
-    if (pov >= kMaxJoystickPOVs) {
-      wpi_setWPIError(BadJoystickAxis);
-    }
-    else {
-      ReportJoystickUnpluggedError(
-          "WARNING: Joystick POV missing, check if all controllers are plugged "
-          "in\n");
-    }
-    return -1;
-  }
-
-  return m_joystickPOVs[stick].povs[pov];
+	std::unique_lock<std::recursive_mutex> lock(m_joystickMutex);
+	if (joysticks[stick] == nullptr || button >= joysticks[stick]->buttons().size())
+	{
+		return false;
+	}
+	return joysticks[stick]->buttons(button-1);
 }
 
 /**
  * The state of the buttons on the joystick.
+ * 12 buttons (4 msb are unused) from the joystick.
  *
  * @param stick The joystick to read.
  * @return The state of the buttons on the joystick.
  */
-uint32_t DriverStation::GetStickButtons(uint32_t stick) const {
-  if (stick >= kJoystickPorts) {
-    wpi_setWPIError(BadJoystickIndex);
-    return 0;
-  }
+short DriverStation::GetStickButtons(uint32_t stick)
+{
+    if (stick < 0 || stick >= 6)
+	{
+		wpi_setWPIErrorWithContext(ParameterOutOfRange, "stick must be between 0 and 5");
+		return false;
+	}
+	short btns = 0, btnid;
 
-  return m_joystickButtons[stick].buttons;
+	std::unique_lock<std::recursive_mutex> lock(m_joystickMutex);
+	msgs::FRCJoystickPtr joy = joysticks[stick];
+	for (btnid = 0; btnid < joy->buttons().size() && btnid < 12; btnid++)
+	{
+		if (joysticks[stick]->buttons(btnid))
+		{
+			btns |= (1 << btnid);
+		}
+	}
+	return btns;
 }
 
+// 5V divided by 10 bits
+#define kDSAnalogInScaling ((float)(5.0 / 1023.0))
+
 /**
- * The state of one joystick button. Button indexes begin at 1.
+ * Get an analog voltage from the Driver Station.
+ * The analog values are returned as voltage values for the Driver Station analog inputs.
+ * These inputs are typically used for advanced operator interfaces consisting of potentiometers
+ * or resistor networks representing values on a rotary switch.
  *
- * @param stick The joystick to read.
- * @param button The button index, beginning at 1.
- * @return The state of the joystick button.
+ * @param channel The analog input channel on the driver station to read from. Valid range is 1 - 4.
+ * @return The analog voltage on the input.
  */
-bool DriverStation::GetStickButton(uint32_t stick, uint8_t button) {
-  if (stick >= kJoystickPorts) {
-    wpi_setWPIError(BadJoystickIndex);
-    return false;
-  }
-
-  if (button > m_joystickButtons[stick].count) {
-    ReportJoystickUnpluggedError(
-        "WARNING: Joystick Button missing, check if all controllers are "
-        "plugged in\n");
-    return false;
-  }
-  if (button == 0) {
-    ReportJoystickUnpluggedError(
-        "ERROR: Button indexes begin at 1 in WPILib for C++ and Java");
-    return false;
-  }
-  return ((0x1 << (button - 1)) & m_joystickButtons[stick].buttons) != 0;
+float DriverStation::GetAnalogIn(uint32_t channel)
+{
+	wpi_setWPIErrorWithContext(UnsupportedInSimulation, "GetAnalogIn");
+	return 0.0;
 }
 
 /**
- * Check if the DS has enabled the robot
- * @return True if the robot is enabled and the DS is connected
+ * Get values from the digital inputs on the Driver Station.
+ * Return digital values from the Drivers Station. These values are typically used for buttons
+ * and switches on advanced operator interfaces.
+ * @param channel The digital input to get. Valid range is 1 - 8.
  */
-bool DriverStation::IsEnabled() const {
-  HALControlWord controlWord;
-  memset(&controlWord, 0, sizeof(controlWord));
-  HALGetControlWord(&controlWord);
-  return controlWord.enabled && controlWord.dsAttached;
+bool DriverStation::GetDigitalIn(uint32_t channel)
+{
+	wpi_setWPIErrorWithContext(UnsupportedInSimulation, "GetDigitalIn");
+	return false;
 }
 
 /**
- * Check if the robot is disabled
- * @return True if the robot is explicitly disabled or the DS is not connected
+ * Set a value for the digital outputs on the Driver Station.
+ *
+ * Control digital outputs on the Drivers Station. These values are typically used for
+ * giving feedback on a custom operator station such as LEDs.
+ *
+ * @param channel The digital output to set. Valid range is 1 - 8.
+ * @param value The state to set the digital output.
  */
-bool DriverStation::IsDisabled() const {
-  HALControlWord controlWord;
-  memset(&controlWord, 0, sizeof(controlWord));
-  HALGetControlWord(&controlWord);
-  return !(controlWord.enabled && controlWord.dsAttached);
+void DriverStation::SetDigitalOut(uint32_t channel, bool value)
+{
+    wpi_setWPIErrorWithContext(UnsupportedInSimulation, "SetDigitalOut");
 }
 
 /**
- * Check if the DS is commanding autonomous mode
- * @return True if the robot is being commanded to be in autonomous mode
+ * Get a value that was set for the digital outputs on the Driver Station.
+ * @param channel The digital ouput to monitor. Valid range is 1 through 8.
+ * @return A digital value being output on the Drivers Station.
  */
-bool DriverStation::IsAutonomous() const {
-  HALControlWord controlWord;
-  memset(&controlWord, 0, sizeof(controlWord));
-  HALGetControlWord(&controlWord);
-  return controlWord.autonomous;
+bool DriverStation::GetDigitalOut(uint32_t channel)
+{
+	wpi_setWPIErrorWithContext(UnsupportedInSimulation, "GetDigitalOut");
+	return false;
 }
 
-/**
- * Check if the DS is commanding teleop mode
- * @return True if the robot is being commanded to be in teleop mode
- */
-bool DriverStation::IsOperatorControl() const {
-  HALControlWord controlWord;
-  memset(&controlWord, 0, sizeof(controlWord));
-  HALGetControlWord(&controlWord);
-  return !(controlWord.autonomous || controlWord.test);
+bool DriverStation::IsEnabled() const
+{
+	std::unique_lock<std::recursive_mutex> lock(m_stateMutex);
+    return state != nullptr ? state->enabled() : false;
 }
 
-/**
- * Check if the DS is commanding test mode
- * @return True if the robot is being commanded to be in test mode
- */
-bool DriverStation::IsTest() const {
-  HALControlWord controlWord;
-  HALGetControlWord(&controlWord);
-  return controlWord.test;
+bool DriverStation::IsDisabled() const
+{
+    return !IsEnabled();
 }
 
-/**
- * Check if the DS is attached
- * @return True if the DS is connected to the robot
- */
-bool DriverStation::IsDSAttached() const {
-  HALControlWord controlWord;
-  memset(&controlWord, 0, sizeof(controlWord));
-  HALGetControlWord(&controlWord);
-  return controlWord.dsAttached;
+bool DriverStation::IsAutonomous() const
+{
+	std::unique_lock<std::recursive_mutex> lock(m_stateMutex);
+    return state != nullptr ?
+      state->state() == msgs::DriverStation_State_AUTO : false;
 }
 
-/**
- * @return always true in simulation
- */
-bool DriverStation::IsSysActive() const {
-  return true;
+bool DriverStation::IsOperatorControl() const
+{
+    return !(IsAutonomous() || IsTest());
 }
 
-/**
- * @return always false in simulation
- */
-bool DriverStation::IsSysBrownedOut() const {
-  return false;
-}
-
-/**
- * Has a new control packet from the driver station arrived since the last time
- * this function was called?
- * Warning: If you call this function from more than one place at the same time,
- * you will not get the get the intended behaviour.
- * @return True if the control data has been updated since the last call.
- */
-bool DriverStation::IsNewControlData() const {
-  return m_newControlData.tryTake() == false;
+bool DriverStation::IsTest() const
+{
+	std::unique_lock<std::recursive_mutex> lock(m_stateMutex);
+    return state != nullptr ?
+      state->state() == msgs::DriverStation_State_TEST : false;
 }
 
 /**
  * Is the driver station attached to a Field Management System?
- * @return True if the robot is competing on a field being controlled by a Field
- * Management System
+ * Note: This does not work with the Blue DS.
+ * @return True if the robot is competing on a field being controlled by a Field Management System
  */
-bool DriverStation::IsFMSAttached() const {
-  HALControlWord controlWord;
-  HALGetControlWord(&controlWord);
-  return controlWord.fmsAttached;
+bool DriverStation::IsFMSAttached() const
+{
+    return false; // No FMS in simulation
 }
 
 /**
  * Return the alliance that the driver station says it is on.
  * This could return kRed or kBlue
- * @return The Alliance enum (kRed, kBlue or kInvalid)
+ * @return The Alliance enum
  */
-DriverStation::Alliance DriverStation::GetAlliance() const {
-  HALAllianceStationID allianceStationID;
-  HALGetAllianceStation(&allianceStationID);
-  switch (allianceStationID) {
-    case kHALAllianceStationID_red1:
-    case kHALAllianceStationID_red2:
-    case kHALAllianceStationID_red3:
-      return kRed;
-    case kHALAllianceStationID_blue1:
-    case kHALAllianceStationID_blue2:
-    case kHALAllianceStationID_blue3:
-      return kBlue;
-    default:
-      return kInvalid;
-  }
+DriverStation::Alliance DriverStation::GetAlliance() const
+{
+	// if (m_controlData->dsID_Alliance == 'R') return kRed;
+	// if (m_controlData->dsID_Alliance == 'B') return kBlue;
+	// wpi_assert(false);
+    return kInvalid; // TODO: Support alliance colors
 }
 
 /**
  * Return the driver station location on the field
  * This could return 1, 2, or 3
- * @return The location of the driver station (1-3, 0 for invalid)
+ * @return The location of the driver station
  */
-uint32_t DriverStation::GetLocation() const {
-  HALAllianceStationID allianceStationID;
-  HALGetAllianceStation(&allianceStationID);
-  switch (allianceStationID) {
-    case kHALAllianceStationID_red1:
-    case kHALAllianceStationID_blue1:
-      return 1;
-    case kHALAllianceStationID_red2:
-    case kHALAllianceStationID_blue2:
-      return 2;
-    case kHALAllianceStationID_red3:
-    case kHALAllianceStationID_blue3:
-      return 3;
-    default:
-      return 0;
-  }
+uint32_t DriverStation::GetLocation() const
+{
+    return -1; // TODO: Support locations
 }
 
 /**
  * Wait until a new packet comes from the driver station
  * This blocks on a semaphore, so the waiting is efficient.
- * This is a good way to delay processing until there is new driver station data
- * to act on
+ * This is a good way to delay processing until there is new driver station data to act on
  */
-void DriverStation::WaitForData() {
-  std::unique_lock<priority_mutex> lock(m_waitForDataMutex);
-  m_waitForDataCond.wait(lock);
+void DriverStation::WaitForData()
+{
+	std::unique_lock<std::mutex> lock(m_waitForDataMutex);
+	m_waitForDataCond.wait(lock);
 }
 
 /**
  * Return the approximate match time
- * The FMS does not send an official match time to the robots, but does send an
- * approximate match time.
- * The value will count down the time remaining in the current period (auto or
- * teleop).
- * Warning: This is not an official time (so it cannot be used to dispute ref
- * calls or guarantee that a function
- * will trigger before the match ends)
- * The Practice Match function of the DS approximates the behaviour seen on the
- * field.
- * @return Time remaining in current match period (auto or teleop)
+ * The FMS does not currently send the official match time to the robots
+ * This returns the time since the enable signal sent from the Driver Station
+ * At the beginning of autonomous, the time is reset to 0.0 seconds
+ * At the beginning of teleop, the time is reset to +15.0 seconds
+ * If the robot is disabled, this returns 0.0 seconds
+ * Warning: This is not an official time (so it cannot be used to argue with referees)
+ * @return Match time in seconds since the beginning of autonomous
  */
-double DriverStation::GetMatchTime() const {
-  float matchTime;
-  HALGetMatchTime(&matchTime);
-  return (double)matchTime;
+double DriverStation::GetMatchTime() const
+{
+	if (m_approxMatchTimeOffset < 0.0)
+		return 0.0;
+	return Timer::GetFPGATimestamp() - m_approxMatchTimeOffset;
 }
 
 /**
  * Report an error to the DriverStation messages window.
  * The error is also printed to the program console.
  */
-void DriverStation::ReportError(std::string error) {
-  std::cout << error << std::endl;
+void DriverStation::ReportError(std::string error)
+{
+	std::cout << error << std::endl;
+}
 
-  HALControlWord controlWord;
-  HALGetControlWord(&controlWord);
-  if (controlWord.dsAttached) {
-    HALSetErrorData(error.c_str(), error.size(), 0);
-  }
+/**
+ * Report a warning to the DriverStation messages window.
+ * The warning is also printed to the program console.
+ */
+void DriverStation::ReportWarning(std::string error)
+{
+	std::cout << error << std::endl;
+}
+
+/**
+ * Report an error to the DriverStation messages window.
+ * The error is also printed to the program console.
+ */
+void DriverStation::ReportError(bool is_error, int32_t code,
+                                const std::string& error,
+                                const std::string& location,
+                                const std::string& stack)
+{
+	if (!location.empty())
+		std::cout << (is_error ? "Error" : "Warning") << " at " << location << ": ";
+	std::cout << error << std::endl;
+	if (!stack.empty())
+		std::cout << stack << std::endl;
+}
+
+/**
+ * Return the team number that the Driver Station is configured for
+ * @return The team number
+ */
+uint16_t DriverStation::GetTeamNumber() const
+{
+    return 348;
+}
+
+void DriverStation::stateCallback(const msgs::ConstDriverStationPtr &msg)
+{
+    {
+  		std::unique_lock<std::recursive_mutex> lock(m_stateMutex);
+    	*state = *msg;
+  	}
+    m_waitForDataCond.notify_all();
+}
+
+void DriverStation::joystickCallback(const msgs::ConstFRCJoystickPtr &msg,
+                                     int i)
+{
+	std::unique_lock<std::recursive_mutex> lock(m_joystickMutex);
+    *(joysticks[i]) = *msg;
+}
+
+void DriverStation::joystickCallback0(const msgs::ConstFRCJoystickPtr &msg)
+{
+    joystickCallback(msg, 0);
+}
+
+void DriverStation::joystickCallback1(const msgs::ConstFRCJoystickPtr &msg)
+{
+    joystickCallback(msg, 1);
+}
+
+void DriverStation::joystickCallback2(const msgs::ConstFRCJoystickPtr &msg)
+{
+    joystickCallback(msg, 2);
+}
+
+void DriverStation::joystickCallback3(const msgs::ConstFRCJoystickPtr &msg)
+{
+    joystickCallback(msg, 3);
+}
+
+void DriverStation::joystickCallback4(const msgs::ConstFRCJoystickPtr &msg)
+{
+    joystickCallback(msg, 4);
+}
+
+void DriverStation::joystickCallback5(const msgs::ConstFRCJoystickPtr &msg)
+{
+    joystickCallback(msg, 5);
 }
diff --git a/wpilibc/simulation/src/Encoder.cpp b/wpilibc/simulation/src/Encoder.cpp
index 790868e..565a8eb 100644
--- a/wpilibc/simulation/src/Encoder.cpp
+++ b/wpilibc/simulation/src/Encoder.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Encoder.h"
diff --git a/wpilibc/simulation/src/Gyro.cpp b/wpilibc/simulation/src/Gyro.cpp
deleted file mode 100644
index a28bb9b..0000000
--- a/wpilibc/simulation/src/Gyro.cpp
+++ /dev/null
@@ -1,133 +0,0 @@
-/*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. 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 $(WIND_BASE)/WPILib.  */
-/*----------------------------------------------------------------------------*/
-
-#include "Gyro.h"
-#include "Timer.h"
-#include "WPIErrors.h"
-#include "LiveWindow/LiveWindow.h"
-
-const uint32_t Gyro::kOversampleBits = 10;
-const uint32_t Gyro::kAverageBits = 0;
-const float Gyro::kSamplesPerSecond = 50.0;
-const float Gyro::kCalibrationSampleTime = 5.0;
-const float Gyro::kDefaultVoltsPerDegreePerSecond = 0.007;
-
-/**
- * Initialize the gyro.
- * Calibrate the gyro by running for a number of samples and computing the center value for this
- * part. Then use the center value as the Accumulator center value for subsequent measurements.
- * It's important to make sure that the robot is not moving while the centering calculations are
- * in progress, this is typically done when the robot is first turned on while it's sitting at
- * rest before the competition starts.
- */
-void Gyro::InitGyro(int channel)
-{
-	SetPIDSourceType(PIDSourceType::kDisplacement);
-
-	char buffer[50];
-	int n = sprintf(buffer, "analog/%d", channel);
-	impl = new SimGyro(buffer);
-
-	LiveWindow::GetInstance()->AddSensor("Gyro", channel, this);
-}
-
-/**
- * Gyro constructor with only a channel..
- *
- * @param channel The analog channel the gyro is connected to.
- */
-Gyro::Gyro(uint32_t channel)
-{
-    InitGyro(channel);
-}
-
-/**
- * Reset the gyro.
- * Resets the gyro to a heading of zero. This can be used if there is significant
- * drift in the gyro and it needs to be recalibrated after it has been running.
- */
-void Gyro::Reset()
-{
-    impl->Reset();
-}
-
-/**
- * Return the actual angle in degrees that the robot is currently facing.
- *
- * The angle is based on the current accumulator value corrected by the oversampling rate, the
- * gyro type and the A/D calibration values.
- * The angle is continuous, that is can go beyond 360 degrees. This make algorithms that wouldn't
- * want to see a discontinuity in the gyro output as it sweeps past 0 on the second time around.
- *
- * @return the current heading of the robot in degrees. This heading is based on integration
- * of the returned rate from the gyro.
- */
-float Gyro::GetAngle() const
-{
-    return impl->GetAngle();
-}
-
-
-/**
- * Return the rate of rotation of the gyro
- *
- * The rate is based on the most recent reading of the gyro analog value
- *
- * @return the current rate in degrees per second
- */
-double Gyro::GetRate() const
-{
-    return impl->GetVelocity();
-}
-
-void Gyro::SetPIDSourceType(PIDSourceType pidSource)
-{
-    m_pidSource = pidSource;
-}
-
-/**
- * Get the angle in degrees for the PIDSource base object.
- *
- * @return The angle in degrees.
- */
-double Gyro::PIDGet()
-{
-	switch(GetPIDSourceType()){
-	case PIDSourceType::kRate:
-		return GetRate();
-	case PIDSourceType::kDisplacement:
-		return GetAngle();
-	default:
-		return 0;
-	}
-}
-
-void Gyro::UpdateTable() {
-	if (m_table != nullptr) {
-		m_table->PutNumber("Value", GetAngle());
-	}
-}
-
-void Gyro::StartLiveWindowMode() {
-
-}
-
-void Gyro::StopLiveWindowMode() {
-
-}
-
-std::string Gyro::GetSmartDashboardType() const {
-	return "Gyro";
-}
-
-void Gyro::InitTable(std::shared_ptr<ITable> subTable) {
-	m_table = subTable;
-	UpdateTable();
-}
-
-std::shared_ptr<ITable> Gyro::GetTable() const {
-	return m_table;
-}
diff --git a/wpilibc/simulation/src/IterativeRobot.cpp b/wpilibc/simulation/src/IterativeRobot.cpp
index f2511df..d78e9f3 100644
--- a/wpilibc/simulation/src/IterativeRobot.cpp
+++ b/wpilibc/simulation/src/IterativeRobot.cpp
@@ -1,8 +1,10 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
+
 #include "IterativeRobot.h"
 
 #include "DriverStation.h"
diff --git a/wpilibc/simulation/src/Jaguar.cpp b/wpilibc/simulation/src/Jaguar.cpp
index fab109d..148f629 100644
--- a/wpilibc/simulation/src/Jaguar.cpp
+++ b/wpilibc/simulation/src/Jaguar.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 
diff --git a/wpilibc/simulation/src/Joystick.cpp b/wpilibc/simulation/src/Joystick.cpp
index a7a299c..3c32e86 100644
--- a/wpilibc/simulation/src/Joystick.cpp
+++ b/wpilibc/simulation/src/Joystick.cpp
@@ -1,16 +1,15 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Joystick.h"
 #include "DriverStation.h"
-//#include "NetworkCommunication/UsageReporting.h"
 #include "WPIErrors.h"
 #include <math.h>
-#include <string.h>
+#include <memory>
 
 const uint32_t Joystick::kDefaultXAxis;
 const uint32_t Joystick::kDefaultYAxis;
@@ -26,21 +25,19 @@
  * Construct an instance of a joystick.
  * The joystick index is the usb port on the drivers station.
  *
- * @param port The port on the driver station that the joystick is plugged into
- * (0-5).
+ * @param port The port on the driver station that the joystick is plugged into.
  */
 Joystick::Joystick(uint32_t port)
-    : Joystick(port, kNumAxisTypes, kNumButtonTypes) {
-  m_axes[kXAxis] = kDefaultXAxis;
-  m_axes[kYAxis] = kDefaultYAxis;
-  m_axes[kZAxis] = kDefaultZAxis;
-  m_axes[kTwistAxis] = kDefaultTwistAxis;
-  m_axes[kThrottleAxis] = kDefaultThrottleAxis;
+	: Joystick(port, kNumAxisTypes, kNumButtonTypes)
+{
+	m_axes[kXAxis] = kDefaultXAxis;
+	m_axes[kYAxis] = kDefaultYAxis;
+	m_axes[kZAxis] = kDefaultZAxis;
+	m_axes[kTwistAxis] = kDefaultTwistAxis;
+	m_axes[kThrottleAxis] = kDefaultThrottleAxis;
 
-  m_buttons[kTriggerButton] = kDefaultTriggerButton;
-  m_buttons[kTopButton] = kDefaultTopButton;
-
-  HALReport(HALUsageReporting::kResourceType_Joystick, port);
+	m_buttons[kTriggerButton] = kDefaultTriggerButton;
+	m_buttons[kTopButton] = kDefaultTopButton;
 }
 
 /**
@@ -53,108 +50,111 @@
  * @param numAxisTypes The number of axis types in the enum.
  * @param numButtonTypes The number of button types in the enum.
  */
-Joystick::Joystick(uint32_t port, uint32_t numAxisTypes,
-                   uint32_t numButtonTypes)
-    : m_ds(DriverStation::GetInstance()),
-      m_port(port),
-      m_axes(numAxisTypes),
-      m_buttons(numButtonTypes) {
-  if (!joySticksInitialized) {
-    for (auto& joystick : joysticks) joystick = nullptr;
-    joySticksInitialized = true;
-  }
-  if (m_port >= DriverStation::kJoystickPorts) {
-    wpi_setWPIError(BadJoystickIndex);
-  } else {
-    joysticks[m_port] = this;
-  }
+Joystick::Joystick(uint32_t port, uint32_t numAxisTypes, uint32_t numButtonTypes)
+	: m_port (port),
+    m_ds(DriverStation::GetInstance())
+{
+	if ( !joySticksInitialized )
+	{
+		for (unsigned i = 0; i < DriverStation::kJoystickPorts; i++)
+			joysticks[i] = nullptr;
+		joySticksInitialized = true;
+	}
+	joysticks[m_port] = this;
+
+	m_axes = std::make_unique<uint32_t[]>(numAxisTypes);
+	m_buttons = std::make_unique<uint32_t[]>(numButtonTypes);
 }
 
-Joystick *Joystick::GetStickForPort(uint32_t port) {
-  Joystick *stick = joysticks[port];
-  if (stick == nullptr) {
-    stick = new Joystick(port);
-    joysticks[port] = stick;
-  }
-  return stick;
+Joystick * Joystick::GetStickForPort(uint32_t port)
+{
+	Joystick *stick = joysticks[port];
+	if (stick == nullptr)
+	{
+		stick = new Joystick(port);
+		joysticks[port] = stick;
+	}
+	return stick;
 }
 
 /**
  * Get the X value of the joystick.
  * This depends on the mapping of the joystick connected to the current port.
- * @param hand This parameter is ignored for the Joystick class and is only here
- * to complete the GenericHID interface.
  */
-float Joystick::GetX(JoystickHand hand) const {
-  return GetRawAxis(m_axes[kXAxis]);
+float Joystick::GetX(JoystickHand hand) const
+{
+	return GetRawAxis(m_axes[kXAxis]);
 }
 
 /**
  * Get the Y value of the joystick.
  * This depends on the mapping of the joystick connected to the current port.
- * @param hand This parameter is ignored for the Joystick class and is only here
- * to complete the GenericHID interface.
  */
-float Joystick::GetY(JoystickHand hand) const {
-  return GetRawAxis(m_axes[kYAxis]);
+float Joystick::GetY(JoystickHand hand) const
+{
+	return GetRawAxis(m_axes[kYAxis]);
 }
 
 /**
  * Get the Z value of the current joystick.
  * This depends on the mapping of the joystick connected to the current port.
  */
-float Joystick::GetZ() const { return GetRawAxis(m_axes[kZAxis]); }
+float Joystick::GetZ() const
+{
+	return GetRawAxis(m_axes[kZAxis]);
+}
 
 /**
  * Get the twist value of the current joystick.
  * This depends on the mapping of the joystick connected to the current port.
  */
-float Joystick::GetTwist() const { return GetRawAxis(m_axes[kTwistAxis]); }
+float Joystick::GetTwist() const
+{
+	return GetRawAxis(m_axes[kTwistAxis]);
+}
 
 /**
  * Get the throttle value of the current joystick.
  * This depends on the mapping of the joystick connected to the current port.
  */
-float Joystick::GetThrottle() const {
-  return GetRawAxis(m_axes[kThrottleAxis]);
+float Joystick::GetThrottle() const
+{
+	return GetRawAxis(m_axes[kThrottleAxis]);
 }
 
 /**
  * Get the value of the axis.
  *
- * @param axis The axis to read, starting at 0.
+ * @param axis The axis to read [1-6].
  * @return The value of the axis.
  */
-float Joystick::GetRawAxis(uint32_t axis) const {
-  return m_ds.GetStickAxis(m_port, axis);
+float Joystick::GetRawAxis(uint32_t axis) const
+{
+	return m_ds.GetStickAxis(m_port, axis);
 }
 
 /**
  * For the current joystick, return the axis determined by the argument.
  *
- * This is for cases where the joystick axis is returned programatically,
- * otherwise one of the
+ * This is for cases where the joystick axis is returned programatically, otherwise one of the
  * previous functions would be preferable (for example GetX()).
  *
  * @param axis The axis to read.
  * @return The value of the axis.
  */
-float Joystick::GetAxis(AxisType axis) const {
-  switch (axis) {
-    case kXAxis:
-      return this->GetX();
-    case kYAxis:
-      return this->GetY();
-    case kZAxis:
-      return this->GetZ();
-    case kTwistAxis:
-      return this->GetTwist();
-    case kThrottleAxis:
-      return this->GetThrottle();
-    default:
-      wpi_setWPIError(BadJoystickAxis);
-      return 0.0;
-  }
+float Joystick::GetAxis(AxisType axis) const
+{
+	switch(axis)
+	{
+		case kXAxis: return this->GetX();
+		case kYAxis: return this->GetY();
+		case kZAxis: return this->GetZ();
+		case kTwistAxis: return this->GetTwist();
+		case kThrottleAxis: return this->GetThrottle();
+		default:
+			wpi_setWPIError(BadJoystickAxis);
+			return 0.0;
+	}
 }
 
 /**
@@ -162,12 +162,12 @@
  *
  * Look up which button has been assigned to the trigger and read its state.
  *
- * @param hand This parameter is ignored for the Joystick class and is only here
- * to complete the GenericHID interface.
+ * @param hand This parameter is ignored for the Joystick class and is only here to complete the GenericHID interface.
  * @return The state of the trigger.
  */
-bool Joystick::GetTrigger(JoystickHand hand) const {
-  return GetRawButton(m_buttons[kTriggerButton]);
+bool Joystick::GetTrigger(JoystickHand hand) const
+{
+	return GetRawButton(m_buttons[kTriggerButton]);
 }
 
 /**
@@ -175,45 +175,45 @@
  *
  * Look up which button has been assigned to the top and read its state.
  *
- * @param hand This parameter is ignored for the Joystick class and is only here
- * to complete the GenericHID interface.
+ * @param hand This parameter is ignored for the Joystick class and is only here to complete the GenericHID interface.
  * @return The state of the top button.
  */
-bool Joystick::GetTop(JoystickHand hand) const {
-  return GetRawButton(m_buttons[kTopButton]);
+bool Joystick::GetTop(JoystickHand hand) const
+{
+	return GetRawButton(m_buttons[kTopButton]);
 }
 
 /**
  * This is not supported for the Joystick.
  * This method is only here to complete the GenericHID interface.
  */
-bool Joystick::GetBumper(JoystickHand hand) const {
-  // Joysticks don't have bumpers.
-  return false;
+bool Joystick::GetBumper(JoystickHand hand) const
+{
+	// Joysticks don't have bumpers.
+	return false;
 }
 
 /**
- * Get the button value (starting at button 1)
+ * Get the button value for buttons 1 through 12.
  *
- * The buttons are returned in a single 16 bit value with one bit representing
- * the state
+ * The buttons are returned in a single 16 bit value with one bit representing the state
  * of each button. The appropriate button is returned as a boolean value.
  *
- * @param button The button number to be read (starting at 1)
+ * @param button The button number to be read.
  * @return The state of the button.
  **/
-bool Joystick::GetRawButton(uint32_t button) const {
-  return m_ds.GetStickButton(m_port, button);
+bool Joystick::GetRawButton(uint32_t button) const
+{
+    return m_ds.GetStickButton(m_port, button);
 }
 
 /**
- * Get the state of a POV on the joystick.
- *
- * @param pov The index of the POV to read (starting at 0)
- * @return the angle of the POV in degrees, or -1 if the POV is not pressed.
- */
+* Get the state of a POV on the joystick.
+*
+* @return the angle of the POV in degrees, or -1 if the POV is not pressed.
+*/
 int Joystick::GetPOV(uint32_t pov) const {
-  return m_ds.GetStickPOV(m_port, pov);
+	return 0; // TODO
 }
 
 /**
@@ -224,75 +224,27 @@
  * @param button The type of button to read.
  * @return The state of the button.
  */
-bool Joystick::GetButton(ButtonType button) const {
-  switch (button) {
-    case kTriggerButton:
-      return GetTrigger();
-    case kTopButton:
-      return GetTop();
-    default:
-      return false;
-  }
+bool Joystick::GetButton(ButtonType button) const
+{
+	switch (button)
+	{
+	case kTriggerButton: return GetTrigger();
+	case kTopButton: return GetTop();
+	default:
+		return false;
+	}
 }
 
 /**
- * Get the number of axis for a joystick
- *
- * @return the number of axis for the current joystick
- */
-int Joystick::GetAxisCount() const { return m_ds.GetStickAxisCount(m_port); }
-
-/**
- * Get the value of isXbox for the joystick.
- *
- * @return A boolean that is true if the joystick is an xbox controller.
- */
-bool Joystick::GetIsXbox() const { return m_ds.GetJoystickIsXbox(m_port); }
-
-/**
- * Get the HID type of the controller.
- *
- * @return the HID type of the controller.
- */
-Joystick::HIDType Joystick::GetType() const {
-  return static_cast<HIDType>(m_ds.GetJoystickType(m_port));
-}
-
-/**
- * Get the name of the joystick.
- *
- * @return the name of the controller.
- */
-std::string Joystick::GetName() const { return m_ds.GetJoystickName(m_port); }
-
-// int Joystick::GetAxisType(uint8_t axis) const
-//{
-//	return m_ds.GetJoystickAxisType(m_port, axis);
-//}
-
-/**
-  * Get the number of axis for a joystick
-  *
-* @return the number of buttons on the current joystick
- */
-int Joystick::GetButtonCount() const {
-  return m_ds.GetStickButtonCount(m_port);
-}
-
-/**
- * Get the number of axis for a joystick
- *
- * @return then umber of POVs for the current joystick
- */
-int Joystick::GetPOVCount() const { return m_ds.GetStickPOVCount(m_port); }
-
-/**
  * Get the channel currently associated with the specified axis.
  *
  * @param axis The axis to look up the channel for.
  * @return The channel fr the axis.
  */
-uint32_t Joystick::GetAxisChannel(AxisType axis) const { return m_axes[axis]; }
+uint32_t Joystick::GetAxisChannel(AxisType axis)
+{
+	return m_axes[axis];
+}
 
 /**
  * Set the channel associated with a specified axis.
@@ -300,8 +252,9 @@
  * @param axis The axis to set the channel for.
  * @param channel The channel to set the axis to.
  */
-void Joystick::SetAxisChannel(AxisType axis, uint32_t channel) {
-  m_axes[axis] = channel;
+void Joystick::SetAxisChannel(AxisType axis, uint32_t channel)
+{
+	m_axes[axis] = channel;
 }
 
 /**
@@ -311,7 +264,7 @@
  * @return The magnitude of the direction vector
  */
 float Joystick::GetMagnitude() const {
-  return sqrt(pow(GetX(), 2) + pow(GetY(), 2));
+	return sqrt(pow(GetX(),2) + pow(GetY(),2) );
 }
 
 /**
@@ -320,58 +273,19 @@
  *
  * @return The direction of the vector in radians
  */
-float Joystick::GetDirectionRadians() const { return atan2(GetX(), -GetY()); }
+float Joystick::GetDirectionRadians() const {
+	return atan2(GetX(), -GetY());
+}
 
 /**
  * Get the direction of the vector formed by the joystick and its origin
  * in degrees
  *
- * uses acos(-1) to represent Pi due to absence of readily accessible Pi
+ * uses acos(-1) to represent Pi due to absence of readily accessable Pi
  * constant in C++
  *
  * @return The direction of the vector in degrees
  */
 float Joystick::GetDirectionDegrees() const {
-  return (180 / acos(-1)) * GetDirectionRadians();
-}
-
-/**
- * Set the rumble output for the joystick. The DS currently supports 2 rumble
- * values,
- * left rumble and right rumble
- * @param type Which rumble value to set
- * @param value The normalized value (0 to 1) to set the rumble to
- */
-void Joystick::SetRumble(RumbleType type, float value) {
-  if (value < 0)
-    value = 0;
-  else if (value > 1)
-    value = 1;
-  if (type == kLeftRumble)
-    m_leftRumble = value * 65535;
-  else
-    m_rightRumble = value * 65535;
-  HALSetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
-}
-
-/**
- * Set a single HID output value for the joystick.
- * @param outputNumber The index of the output to set (1-32)
- * @param value The value to set the output to
- */
-
-void Joystick::SetOutput(uint8_t outputNumber, bool value) {
-  m_outputs =
-      (m_outputs & ~(1 << (outputNumber - 1))) | (value << (outputNumber - 1));
-
-  HALSetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
-}
-
-/**
- * Set all HID output values for the joystick.
- * @param value The 32 bit output value (1 bit for each output)
- */
-void Joystick::SetOutputs(uint32_t value) {
-  m_outputs = value;
-  HALSetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
+	return (180/acos(-1))*GetDirectionRadians();
 }
diff --git a/wpilibc/simulation/src/MotorSafetyHelper.cpp b/wpilibc/simulation/src/MotorSafetyHelper.cpp
index 87f5352..47db177 100644
--- a/wpilibc/simulation/src/MotorSafetyHelper.cpp
+++ b/wpilibc/simulation/src/MotorSafetyHelper.cpp
@@ -1,8 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.
- */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "MotorSafetyHelper.h"
diff --git a/wpilibc/simulation/src/Notifier.cpp b/wpilibc/simulation/src/Notifier.cpp
index 25daaf0..eb19487 100644
--- a/wpilibc/simulation/src/Notifier.cpp
+++ b/wpilibc/simulation/src/Notifier.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Notifier.h"
@@ -9,7 +10,7 @@
 #include "Utility.h"
 #include "WPIErrors.h"
 
-Notifier *Notifier::timerQueueHead = nullptr;
+std::list<Notifier*> Notifier::timerQueue;
 priority_recursive_mutex Notifier::queueMutex;
 std::atomic<int> Notifier::refcount{0};
 std::thread Notifier::m_task;
@@ -20,16 +21,14 @@
  * @param handler The handler is called at the notification time which is set
  * using StartSingle or StartPeriodic.
  */
-Notifier::Notifier(TimerEventHandler handler, void *param)
+Notifier::Notifier(TimerEventHandler handler)
 {
 	if (handler == nullptr)
 		wpi_setWPIErrorWithContext(NullParameter, "handler must not be nullptr");
 	m_handler = handler;
-	m_param = param;
 	m_periodic = false;
 	m_expirationTime = 0;
 	m_period = 0;
-	m_nextEvent = nullptr;
 	m_queued = false;
 	{
 		std::lock_guard<priority_recursive_mutex> sync(queueMutex);
@@ -89,13 +88,20 @@
 		{
 			std::lock_guard<priority_recursive_mutex> sync(queueMutex);
 			double currentTime = GetClock();
-			current = timerQueueHead;
-			if (current == nullptr || current->m_expirationTime > currentTime)
+
+			if (timerQueue.empty())
+			{
+				break;
+			}
+			current = timerQueue.front();
+			if (current->m_expirationTime > currentTime)
 			{
 				break;		// no more timer events to process
 			}
-			// need to process this entry
-			timerQueueHead = current->m_nextEvent;
+			// remove next entry before processing it
+			timerQueue.pop_front();
+
+			current->m_queued = false;
 			if (current->m_periodic)
 			{
 				// if periodic, requeue the event
@@ -112,7 +118,7 @@
 			current->m_handlerMutex.lock();
 		}
 
-		current->m_handler(current->m_param);	// call the event handler
+		current->m_handler();	// call the event handler
 		current->m_handlerMutex.unlock();
 	}
 	// reschedule the first item in the queue
@@ -139,32 +145,34 @@
 	{
 		m_expirationTime = GetClock() + m_period;
 	}
-	if (timerQueueHead == nullptr || timerQueueHead->m_expirationTime >= this->m_expirationTime)
+
+	// Attempt to insert new entry into queue
+	for (auto i = timerQueue.begin(); i != timerQueue.end(); i++)
 	{
-		// the queue is empty or greater than the new entry
-		// the new entry becomes the first element
-		this->m_nextEvent = timerQueueHead;
-		timerQueueHead = this;
+		if ((*i)->m_expirationTime > m_expirationTime)
+		{
+			timerQueue.insert(i, this);
+			m_queued = true;
+		}
+	}
+
+	/* If the new entry wasn't queued, either the queue was empty or the first
+	 * element was greater than the new entry.
+	 */
+	if (!m_queued)
+	{
+		timerQueue.push_front(this);
+
 		if (!reschedule)
 		{
-			// since the first element changed, update alarm, unless we already plan to
+			/* Since the first element changed, update alarm, unless we already
+			 * plan to
+			 */
 			UpdateAlarm();
 		}
+
+		m_queued = true;
 	}
-	else
-	{
-		for (Notifier **npp = &(timerQueueHead->m_nextEvent); ; npp = &(*npp)->m_nextEvent)
-		{
-			Notifier *n = *npp;
-			if (n == nullptr || n->m_expirationTime > this->m_expirationTime)
-			{
-				*npp = this;
-				this->m_nextEvent = n;
-				break;
-			}
-		}
-	}
-	m_queued = true;
 }
 
 /**
@@ -179,23 +187,16 @@
 	if (m_queued)
 	{
 		m_queued = false;
-		wpi_assert(timerQueueHead != nullptr);
-		if (timerQueueHead == this)
+		wpi_assert(!timerQueue.empty());
+		if (timerQueue.front() == this)
 		{
 			// remove the first item in the list - update the alarm
-			timerQueueHead = this->m_nextEvent;
+			timerQueue.pop_front();
 			UpdateAlarm();
 		}
 		else
 		{
-			for (Notifier *n = timerQueueHead; n != nullptr; n = n->m_nextEvent)
-			{
-				if (n->m_nextEvent == this)
-				{
-					// this element is the next element from *n from the queue
-					n->m_nextEvent = this->m_nextEvent;	// point around this one
-				}
-			}
+			timerQueue.remove(this);
 		}
 	}
 }
@@ -249,9 +250,19 @@
 void Notifier::Run() {
     while (!m_stopped) {
         Notifier::ProcessQueue(0, nullptr);
-        if (timerQueueHead != nullptr)
+        bool isEmpty;
         {
-            Wait(timerQueueHead->m_expirationTime - GetClock());
+            std::lock_guard<priority_recursive_mutex> sync(queueMutex);
+            isEmpty = timerQueue.empty();
+        }
+        if (!isEmpty)
+        {
+            double expirationTime;
+            {
+                std::lock_guard<priority_recursive_mutex> sync(queueMutex);
+                expirationTime = timerQueue.front()->m_expirationTime;
+            }
+            Wait(expirationTime - GetClock());
         }
         else
         {
diff --git a/wpilibc/simulation/src/PIDController.cpp b/wpilibc/simulation/src/PIDController.cpp
index 03beb5c..d3c18b5 100644
--- a/wpilibc/simulation/src/PIDController.cpp
+++ b/wpilibc/simulation/src/PIDController.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "PIDController.h"
@@ -74,7 +75,7 @@
 	m_enabled = false;
 	m_setpoint = 0;
 
-	m_prevInput = 0;
+	m_prevError = 0;
 	m_totalError = 0;
 	m_tolerance = .05;
 
@@ -84,7 +85,7 @@
 	m_pidOutput = output;
 	m_period = period;
 
-	m_controlLoop = std::make_unique<Notifier>(PIDController::CallCalculate, this);
+	m_controlLoop = std::make_unique<Notifier>(&PIDController::Calculate, this);
 	m_controlLoop->StartPeriodic(m_period);
 
 	static int32_t instances = 0;
@@ -98,30 +99,16 @@
 }
 
 /**
- * Call the Calculate method as a non-static method. This avoids having to prepend
- * all local variables in that method with the class pointer. This way the "this"
- * pointer will be set up and class variables can be called more easily.
- * This method is static and called by the Notifier class.
- * @param controller the address of the PID controller object to use in the background loop
+ * Read the input, calculate the output accordingly, and write to the output.
+ * This should only be called by the Notifier.
  */
-void PIDController::CallCalculate(void *controller)
-{
-	PIDController *control = (PIDController*) controller;
-	control->Calculate();
-}
-
- /**
-  * Read the input, calculate the output accordingly, and write to the output.
-  * This should only be called by the Notifier indirectly through CallCalculate
-  * and is created during initialization.
-  */
 void PIDController::Calculate()
 {
 	bool enabled;
 	PIDSource *pidInput;
 
 	{
-		std::lock_guard<priority_mutex> lock(m_mutex);
+		std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 		if (m_pidInput == 0) return;
 		if (m_pidOutput == 0) return;
 		enabled = m_enabled;
@@ -135,7 +122,7 @@
 		PIDOutput *pidOutput;
 
 		{
-			std::lock_guard<priority_mutex> sync(m_mutex);
+			std::lock_guard<priority_recursive_mutex> sync(m_mutex);
 			m_error = m_setpoint - input;
 			if (m_continuous)
 			{
@@ -168,7 +155,8 @@
                 }
               }
 
-              m_result = m_D * m_error + m_P * m_totalError + m_setpoint * m_F;
+              m_result = m_D * m_error + m_P * m_totalError +
+                         CalculateFeedForward();
             }
             else {
               if (m_I != 0) {
@@ -186,9 +174,10 @@
                 }
               }
 
-              m_result = m_P * m_error + m_I * m_totalError + m_D * (m_prevInput - input) + m_setpoint * m_F;
+              m_result = m_P * m_error + m_I * m_totalError +
+                         m_D * (m_error - m_prevError) + CalculateFeedForward();
             }
-			m_prevInput = input;
+			m_prevError = m_error;
 
 			if (m_result > m_maximumOutput) m_result = m_maximumOutput;
 			else if (m_result < m_minimumOutput) m_result = m_minimumOutput;
@@ -202,6 +191,33 @@
 }
 
 /**
+ * Calculate the feed forward term
+ *
+ * Both of the provided feed forward calculations are velocity feed forwards.
+ * If a different feed forward calculation is desired, the user can override
+ * this function and provide his or her own. This function  does no
+ * synchronization because the PIDController class only calls it in synchronized
+ * code, so be careful if calling it oneself.
+ *
+ * If a velocity PID controller is being used, the F term should be set to 1
+ * over the maximum setpoint for the output. If a position PID controller is
+ * being used, the F term should be set to 1 over the maximum speed for the
+ * output measured in setpoint units per this controller's update period (see
+ * the default period in this class's constructor).
+ */
+double PIDController::CalculateFeedForward() {
+  if (m_pidInput->GetPIDSourceType() == PIDSourceType::kRate) {
+    return m_F * GetSetpoint();
+  }
+  else {
+    double temp = m_F * GetDeltaSetpoint();
+    m_prevSetpoint = m_setpoint;
+    m_setpointTimer.Reset();
+    return temp;
+  }
+}
+
+/**
  * Set the PID Controller gain parameters.
  * Set the proportional, integral, and differential coefficients.
  * @param p Proportional coefficient
@@ -211,7 +227,7 @@
 void PIDController::SetPID(double p, double i, double d)
 {
 	{
-		std::lock_guard<priority_mutex> lock(m_mutex);
+		std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 		m_P = p;
 		m_I = i;
 		m_D = d;
@@ -235,7 +251,7 @@
 void PIDController::SetPID(double p, double i, double d, double f)
 {
 	{
-		std::lock_guard<priority_mutex> lock(m_mutex);
+		std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 		m_P = p;
 		m_I = i;
 		m_D = d;
@@ -256,7 +272,7 @@
  */
 double PIDController::GetP() const
 {
-	std::lock_guard<priority_mutex> lock(m_mutex);
+	std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 	return m_P;
 }
 
@@ -266,7 +282,7 @@
  */
 double PIDController::GetI() const
 {
-	std::lock_guard<priority_mutex> lock(m_mutex);
+	std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 	return m_I;
 }
 
@@ -276,7 +292,7 @@
  */
 double PIDController::GetD() const
 {
-	std::lock_guard<priority_mutex> lock(m_mutex);
+	std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 	return m_D;
 }
 
@@ -286,7 +302,7 @@
  */
 double PIDController::GetF() const
 {
-	std::lock_guard<priority_mutex> lock(m_mutex);
+	std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 	return m_F;
 }
 
@@ -297,7 +313,7 @@
  */
 float PIDController::Get() const
 {
-	std::lock_guard<priority_mutex> lock(m_mutex);
+	std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 	return m_result;
 }
 
@@ -310,7 +326,7 @@
  */
 void PIDController::SetContinuous(bool continuous)
 {
-	std::lock_guard<priority_mutex> lock(m_mutex);
+	std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 	m_continuous = continuous;
 }
 
@@ -323,7 +339,7 @@
 void PIDController::SetInputRange(float minimumInput, float maximumInput)
 {
 	{
-		std::lock_guard<priority_mutex> lock(m_mutex);
+		std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 		m_minimumInput = minimumInput;
 		m_maximumInput = maximumInput;
 	}
@@ -339,7 +355,7 @@
  */
 void PIDController::SetOutputRange(float minimumOutput, float maximumOutput)
 {
-	std::lock_guard<priority_mutex> lock(m_mutex);
+	std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 	m_minimumOutput = minimumOutput;
 	m_maximumOutput = maximumOutput;
 }
@@ -351,7 +367,8 @@
 void PIDController::SetSetpoint(float setpoint)
 {
 	{
-		std::lock_guard<priority_mutex> lock(m_mutex);
+		std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+
 		if (m_maximumInput > m_minimumInput)
 		{
 			if (setpoint > m_maximumInput)
@@ -378,11 +395,21 @@
  */
 double PIDController::GetSetpoint() const
 {
-	std::lock_guard<priority_mutex> lock(m_mutex);
+	std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 	return m_setpoint;
 }
 
 /**
+ * Returns the change in setpoint over time of the PIDController
+ * @return the change in setpoint over time
+ */
+double PIDController::GetDeltaSetpoint() const
+{
+	std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+	return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get();
+}
+
+/**
  * Retruns the current difference of the input from the setpoint
  * @return the current error
  */
@@ -390,7 +417,7 @@
 {
 	double pidInput;
 	{
-		std::lock_guard<priority_mutex> lock(m_mutex);
+		std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 		pidInput = m_pidInput->PIDGet();
 	}
 	return GetSetpoint() - pidInput;
@@ -420,7 +447,7 @@
 float PIDController::GetAvgError() const {
   float avgError = 0;
   {
-    std::lock_guard<priority_mutex> sync(m_mutex);
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
     // Don't divide by zero.
     if (m_buf.size()) avgError = m_bufTotal / m_buf.size();
   }
@@ -434,7 +461,7 @@
  */
 void PIDController::SetTolerance(float percent)
 {
-	std::lock_guard<priority_mutex> lock(m_mutex);
+	std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 	m_toleranceType = kPercentTolerance;
 	m_tolerance = percent;
 }
@@ -446,7 +473,7 @@
  */
 void PIDController::SetPercentTolerance(float percent)
 {
-	std::lock_guard<priority_mutex> lock(m_mutex);
+	std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 	m_toleranceType = kPercentTolerance;
 	m_tolerance = percent;
 }
@@ -458,7 +485,7 @@
  */
 void PIDController::SetAbsoluteTolerance(float absTolerance)
 {
-	std::lock_guard<priority_mutex> lock(m_mutex);
+	std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 	m_toleranceType = kAbsoluteTolerance;
 	m_tolerance = absTolerance;
 }
@@ -473,6 +500,7 @@
  * @param bufLength Number of previous cycles to average. Defaults to 1.
  */
 void PIDController::SetToleranceBuffer(unsigned bufLength) {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
   m_bufLength = bufLength;
 
   // Cut the buffer down to size if needed.
@@ -491,9 +519,9 @@
  */
 bool PIDController::OnTarget() const
 {
+	std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+	if (m_buf.size() == 0) return false;
 	double error = GetError();
-
-	std::lock_guard<priority_mutex> sync(m_mutex);
 	switch (m_toleranceType) {
 	case kPercentTolerance:
 		return fabs(error) < m_tolerance / 100 * (m_maximumInput - m_minimumInput);
@@ -513,7 +541,7 @@
 void PIDController::Enable()
 {
 	{
-		std::lock_guard<priority_mutex> lock(m_mutex);
+		std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 		m_enabled = true;
 	}
 
@@ -528,7 +556,7 @@
 void PIDController::Disable()
 {
 	{
-		std::lock_guard<priority_mutex> lock(m_mutex);
+		std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 		m_pidOutput->PIDWrite(0);
 		m_enabled = false;
 	}
@@ -543,7 +571,7 @@
  */
 bool PIDController::IsEnabled() const
 {
-	std::lock_guard<priority_mutex> lock(m_mutex);
+	std::lock_guard<priority_recursive_mutex> lock(m_mutex);
 	return m_enabled;
 }
 
@@ -554,8 +582,8 @@
 {
 	Disable();
 
-	std::lock_guard<priority_mutex> lock(m_mutex);
-	m_prevInput = 0;
+	std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+	m_prevError = 0;
 	m_totalError = 0;
 	m_result = 0;
 }
diff --git a/wpilibc/simulation/src/PWM.cpp b/wpilibc/simulation/src/PWM.cpp
index dfb8bd9..19b30c3 100644
--- a/wpilibc/simulation/src/PWM.cpp
+++ b/wpilibc/simulation/src/PWM.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "PWM.h"
diff --git a/wpilibc/simulation/src/Relay.cpp b/wpilibc/simulation/src/Relay.cpp
index f35d782..7582b52 100644
--- a/wpilibc/simulation/src/Relay.cpp
+++ b/wpilibc/simulation/src/Relay.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Relay.h"
diff --git a/wpilibc/simulation/src/RobotBase.cpp b/wpilibc/simulation/src/RobotBase.cpp
index 1fa5ac7..d5afb7f 100644
--- a/wpilibc/simulation/src/RobotBase.cpp
+++ b/wpilibc/simulation/src/RobotBase.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "RobotBase.h"
@@ -34,7 +35,7 @@
 RobotBase::RobotBase() : m_ds(DriverStation::GetInstance())
 {
 	RobotState::SetImplementation(DriverStation::GetInstance());
-	transport::SubscriberPtr time_pub = MainNode::Subscribe("time", &wpilib::internal::time_callback);
+	time_sub = MainNode::Subscribe("~/time", &wpilib::internal::time_callback);
 }
 
 /**
diff --git a/wpilibc/simulation/src/RobotDrive.cpp b/wpilibc/simulation/src/RobotDrive.cpp
index 852d0bf..b6216d0 100644
--- a/wpilibc/simulation/src/RobotDrive.cpp
+++ b/wpilibc/simulation/src/RobotDrive.cpp
@@ -1,15 +1,15 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "RobotDrive.h"
-
 //#include "CANJaguar.h"
 #include "GenericHID.h"
 #include "Joystick.h"
-#include "Jaguar.h"
+#include "Talon.h"
 #include "Utility.h"
 #include "WPIErrors.h"
 #include <math.h>
@@ -19,6 +19,10 @@
 
 const int32_t RobotDrive::kMaxNumberOfMotors;
 
+static auto make_shared_nodelete(SpeedController *ptr) {
+	return std::shared_ptr<SpeedController>(ptr, NullDeleter<SpeedController>());
+}
+
 /*
  * Driving functions
  * These functions provide an interface to multiple motors that is used for C programming
@@ -39,19 +43,15 @@
 /** Constructor for RobotDrive with 2 motors specified with channel numbers.
  * Set up parameters for a two wheel drive system where the
  * left and right motor pwm channels are specified in the call.
- * This call assumes Jaguars for controlling the motors.
+ * This call assumes Talosn for controlling the motors.
  * @param leftMotorChannel The PWM channel number that drives the left motor.
  * @param rightMotorChannel The PWM channel number that drives the right motor.
  */
 RobotDrive::RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel)
 {
 	InitRobotDrive();
-	m_rearLeftMotor = new Jaguar(leftMotorChannel);
-	m_rearRightMotor = new Jaguar(rightMotorChannel);
-	for (int32_t i=0; i < kMaxNumberOfMotors; i++)
-	{
-		m_invertedMotors[i] = 1;
-	}
+	m_rearLeftMotor = std::make_shared<Talon>(leftMotorChannel);
+	m_rearRightMotor = std::make_shared<Talon>(rightMotorChannel);
 	SetLeftRightMotorOutputs(0.0, 0.0);
 	m_deleteSpeedControllers = true;
 }
@@ -60,7 +60,7 @@
  * Constructor for RobotDrive with 4 motors specified with channel numbers.
  * Set up parameters for a four wheel drive system where all four motor
  * pwm channels are specified in the call.
- * This call assumes Jaguars for controlling the motors.
+ * This call assumes Talons for controlling the motors.
  * @param frontLeftMotor Front left motor channel number
  * @param rearLeftMotor Rear Left motor channel number
  * @param frontRightMotor Front right motor channel number
@@ -70,14 +70,10 @@
 		uint32_t frontRightMotor, uint32_t rearRightMotor)
 {
 	InitRobotDrive();
-	m_rearLeftMotor = new Jaguar(rearLeftMotor);
-	m_rearRightMotor = new Jaguar(rearRightMotor);
-	m_frontLeftMotor = new Jaguar(frontLeftMotor);
-	m_frontRightMotor = new Jaguar(frontRightMotor);
-	for (int32_t i=0; i < kMaxNumberOfMotors; i++)
-	{
-		m_invertedMotors[i] = 1;
-	}
+	m_rearLeftMotor = std::make_shared<Talon>(rearLeftMotor);
+	m_rearRightMotor = std::make_shared<Talon>(rearRightMotor);
+	m_frontLeftMotor = std::make_shared<Talon>(frontLeftMotor);
+	m_frontRightMotor = std::make_shared<Talon>(frontRightMotor);
 	SetLeftRightMotorOutputs(0.0, 0.0);
 	m_deleteSpeedControllers = true;
 }
@@ -90,34 +86,36 @@
  * @param leftMotor The left SpeedController object used to drive the robot.
  * @param rightMotor the right SpeedController object used to drive the robot.
  */
-RobotDrive::RobotDrive(SpeedController *leftMotor, SpeedController *rightMotor)
-{
+RobotDrive::RobotDrive(SpeedController *leftMotor,
+                       SpeedController *rightMotor) {
 	InitRobotDrive();
-	if (leftMotor == nullptr || rightMotor == nullptr)
-	{
+	if (leftMotor == nullptr || rightMotor == nullptr) {
 		wpi_setWPIError(NullParameter);
 		m_rearLeftMotor = m_rearRightMotor = nullptr;
 		return;
 	}
-	m_rearLeftMotor = leftMotor;
-	m_rearRightMotor = rightMotor;
-	for (int32_t i=0; i < kMaxNumberOfMotors; i++)
-	{
-		m_invertedMotors[i] = 1;
-	}
-	m_deleteSpeedControllers = false;
+	m_rearLeftMotor = make_shared_nodelete(leftMotor);
+	m_rearRightMotor = make_shared_nodelete(rightMotor);
 }
 
-RobotDrive::RobotDrive(SpeedController &leftMotor, SpeedController &rightMotor)
-{
+//TODO: Change to rvalue references & move syntax.
+RobotDrive::RobotDrive(SpeedController &leftMotor,
+                       SpeedController &rightMotor) {
 	InitRobotDrive();
-	m_rearLeftMotor = &leftMotor;
-	m_rearRightMotor = &rightMotor;
-	for (int32_t i=0; i < kMaxNumberOfMotors; i++)
-	{
-		m_invertedMotors[i] = 1;
+	m_rearLeftMotor = make_shared_nodelete(&leftMotor);
+	m_rearRightMotor = make_shared_nodelete(&rightMotor);
+}
+
+RobotDrive::RobotDrive(std::shared_ptr<SpeedController> leftMotor,
+                       std::shared_ptr<SpeedController> rightMotor) {
+	InitRobotDrive();
+	if (leftMotor == nullptr || rightMotor == nullptr) {
+		wpi_setWPIError(NullParameter);
+		m_rearLeftMotor = m_rearRightMotor = nullptr;
+	return;
 	}
-	m_deleteSpeedControllers = false;
+	m_rearLeftMotor = leftMotor;
+	m_rearRightMotor = rightMotor;
 }
 
 /**
@@ -128,12 +126,40 @@
  * @param rearRightMotor The back right SpeedController object used to drive the robot.
  * @param frontRightMotor The front right SpeedController object used to drive the robot.
  */
-RobotDrive::RobotDrive(SpeedController *frontLeftMotor, SpeedController *rearLeftMotor,
-						SpeedController *frontRightMotor, SpeedController *rearRightMotor)
-{
+RobotDrive::RobotDrive(SpeedController *frontLeftMotor,
+                       SpeedController *rearLeftMotor,
+                       SpeedController *frontRightMotor,
+                       SpeedController *rearRightMotor) {
 	InitRobotDrive();
-	if (frontLeftMotor == nullptr || rearLeftMotor == nullptr || frontRightMotor == nullptr || rearRightMotor == nullptr)
-	{
+	if (frontLeftMotor == nullptr || rearLeftMotor == nullptr ||
+	  frontRightMotor == nullptr || rearRightMotor == nullptr) {
+		wpi_setWPIError(NullParameter);
+		return;
+	}
+	m_frontLeftMotor = make_shared_nodelete(frontLeftMotor);
+	m_rearLeftMotor = make_shared_nodelete(rearLeftMotor);
+	m_frontRightMotor = make_shared_nodelete(frontRightMotor);
+	m_rearRightMotor = make_shared_nodelete(rearRightMotor);
+}
+
+RobotDrive::RobotDrive(SpeedController &frontLeftMotor,
+                       SpeedController &rearLeftMotor,
+                       SpeedController &frontRightMotor,
+                       SpeedController &rearRightMotor) {
+	InitRobotDrive();
+	m_frontLeftMotor = make_shared_nodelete(&frontLeftMotor);
+	m_rearLeftMotor = make_shared_nodelete(&rearLeftMotor);
+	m_frontRightMotor = make_shared_nodelete(&frontRightMotor);
+	m_rearRightMotor = make_shared_nodelete(&rearRightMotor);
+}
+
+RobotDrive::RobotDrive(std::shared_ptr<SpeedController> frontLeftMotor,
+                       std::shared_ptr<SpeedController> rearLeftMotor,
+                       std::shared_ptr<SpeedController> frontRightMotor,
+                       std::shared_ptr<SpeedController> rearRightMotor) {
+	InitRobotDrive();
+	if (frontLeftMotor == nullptr || rearLeftMotor == nullptr ||
+	  frontRightMotor == nullptr || rearRightMotor == nullptr) {
 		wpi_setWPIError(NullParameter);
 		return;
 	}
@@ -141,42 +167,6 @@
 	m_rearLeftMotor = rearLeftMotor;
 	m_frontRightMotor = frontRightMotor;
 	m_rearRightMotor = rearRightMotor;
-	for (int32_t i=0; i < kMaxNumberOfMotors; i++)
-	{
-		m_invertedMotors[i] = 1;
-	}
-	m_deleteSpeedControllers = false;
-}
-
-RobotDrive::RobotDrive(SpeedController &frontLeftMotor, SpeedController &rearLeftMotor,
-						SpeedController &frontRightMotor, SpeedController &rearRightMotor)
-{
-	InitRobotDrive();
-	m_frontLeftMotor = &frontLeftMotor;
-	m_rearLeftMotor = &rearLeftMotor;
-	m_frontRightMotor = &frontRightMotor;
-	m_rearRightMotor = &rearRightMotor;
-	for (int32_t i=0; i < kMaxNumberOfMotors; i++)
-	{
-		m_invertedMotors[i] = 1;
-	}
-	m_deleteSpeedControllers = false;
-}
-
-/**
- * RobotDrive destructor.
- * Deletes motor objects that were not passed in and created internally only.
- **/
-RobotDrive::~RobotDrive()
-{
-	if (m_deleteSpeedControllers)
-	{
-		delete m_frontLeftMotor;
-		delete m_rearLeftMotor;
-		delete m_frontRightMotor;
-		delete m_rearRightMotor;
-	}
-	// FIXME: delete m_safetyHelper;
 }
 
 /**
diff --git a/wpilibc/simulation/src/SafePWM.cpp b/wpilibc/simulation/src/SafePWM.cpp
index 8ba0b68..57bd729 100644
--- a/wpilibc/simulation/src/SafePWM.cpp
+++ b/wpilibc/simulation/src/SafePWM.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "SafePWM.h"
diff --git a/wpilibc/simulation/src/SampleRobot.cpp b/wpilibc/simulation/src/SampleRobot.cpp
index b8f3181..21dcbfa 100644
--- a/wpilibc/simulation/src/SampleRobot.cpp
+++ b/wpilibc/simulation/src/SampleRobot.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "SampleRobot.h"
diff --git a/wpilibc/simulation/src/SensorBase.cpp b/wpilibc/simulation/src/SensorBase.cpp
index fa3086f..de18bcf 100644
--- a/wpilibc/simulation/src/SensorBase.cpp
+++ b/wpilibc/simulation/src/SensorBase.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "SensorBase.h"
diff --git a/wpilibc/simulation/src/Solenoid.cpp b/wpilibc/simulation/src/Solenoid.cpp
index 387194d..a9f4e9b 100644
--- a/wpilibc/simulation/src/Solenoid.cpp
+++ b/wpilibc/simulation/src/Solenoid.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Solenoid.h"
diff --git a/wpilibc/simulation/src/Talon.cpp b/wpilibc/simulation/src/Talon.cpp
index 0e9505d..9a6d806 100644
--- a/wpilibc/simulation/src/Talon.cpp
+++ b/wpilibc/simulation/src/Talon.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Talon.h"
diff --git a/wpilibc/simulation/src/Timer.cpp b/wpilibc/simulation/src/Timer.cpp
index b4734db..8bef9f2 100644
--- a/wpilibc/simulation/src/Timer.cpp
+++ b/wpilibc/simulation/src/Timer.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Timer.h"
diff --git a/wpilibc/simulation/src/Utility.cpp b/wpilibc/simulation/src/Utility.cpp
index b0710f1..4b49725 100644
--- a/wpilibc/simulation/src/Utility.cpp
+++ b/wpilibc/simulation/src/Utility.cpp
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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.                                                               */
+/*----------------------------------------------------------------------------*/
 
 /* Copyright (c) FIRST 2008. All Rights Reserved.							  */
 /* Open Source Software - may be modified and shared by FRC teams. The code   */
@@ -16,7 +22,7 @@
 #include <cstdio>
 #include <cstdlib>
 #include <cstring>
-#if defined(UNIX)
+#if not defined(_WIN32)
 	#include <execinfo.h>
 	#include <cxxabi.h>
 #endif
@@ -58,29 +64,27 @@
  * This allows breakpoints to be set on an assert.
  * The users don't call this, but instead use the wpi_assert macros in Utility.h.
  */
-bool wpi_assert_impl(bool conditionValue, const std::string &conditionText,
-                     const std::string &message, const std::string &fileName,
-                     uint32_t lineNumber, const std::string &funcName) {
+bool wpi_assert_impl(bool conditionValue, const char *conditionText,
+                     const char *message, const char *fileName,
+                     uint32_t lineNumber, const char *funcName) {
   if (!conditionValue) {
-    // Error string buffer
-    std::stringstream error;
+    std::stringstream errorStream;
 
-    // If an error message was specified, include it
-    // Build error string
-    if (message.size()) {
-      error << "Assertion failed: \"" << message << "\", \"" << conditionText
-            << "\" failed in " << funcName + "() in " << fileName << " at line "
-            << lineNumber;
+    errorStream << "Assertion \"" << conditionText << "\" ";
+    errorStream << "on line " << lineNumber << " ";
+    errorStream << "of " << basename(fileName) << " ";
+
+    if (message[0] != '\0') {
+      errorStream << "failed: " << message << std::endl;
     } else {
-      error << "Assertion failed: \"" << conditionText << "\" in " << funcName
-            << "() in " << fileName << " at line " << lineNumber;
+      errorStream << "failed." << std::endl;
     }
 
     // Print to console and send to remote dashboard
-    std::cout << "\n\n>>>>" << error.str();
-
+    std::cout << "\n\n>>>>" << errorStream.str();
     wpi_handleTracing();
   }
+
   return conditionValue;
 }
 
@@ -161,13 +165,13 @@
  *
  * @return The current time in microseconds according to the FPGA (since FPGA reset).
  */
-uint32_t GetFPGATime()
+uint64_t GetFPGATime()
 {
 	return wpilib::internal::simTime * 1e6;
 }
 
 //TODO: implement symbol demangling and backtrace on windows
-#if defined(UNIX)
+#if not defined(_WIN32)
 
 /**
  * Demangle a C++ symbol, used for printing stack traces.
diff --git a/wpilibc/simulation/src/Victor.cpp b/wpilibc/simulation/src/Victor.cpp
index 54ba61f..72e33bc 100644
--- a/wpilibc/simulation/src/Victor.cpp
+++ b/wpilibc/simulation/src/Victor.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2008. All Rights Reserved.							  */
+/* Copyright (c) FIRST 2008-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include "Victor.h"
diff --git a/wpilibc/simulation/src/simulation/SimEncoder.cpp b/wpilibc/simulation/src/simulation/SimEncoder.cpp
index b72b8f1..0b5ed20 100644
--- a/wpilibc/simulation/src/simulation/SimEncoder.cpp
+++ b/wpilibc/simulation/src/simulation/SimEncoder.cpp
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "simulation/SimEncoder.h"
 #include "simulation/MainNode.h"
diff --git a/wpilibc/simulation/src/simulation/SimGyro.cpp b/wpilibc/simulation/src/simulation/SimGyro.cpp
index c173c05..c93434d 100644
--- a/wpilibc/simulation/src/simulation/SimGyro.cpp
+++ b/wpilibc/simulation/src/simulation/SimGyro.cpp
@@ -1,3 +1,9 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "simulation/SimGyro.h"
 #include "simulation/MainNode.h"
diff --git a/wpilibcIntegrationTests/include/TestBench.h b/wpilibcIntegrationTests/include/TestBench.h
index bd3d288..eb1ef63 100644
--- a/wpilibcIntegrationTests/include/TestBench.h
+++ b/wpilibcIntegrationTests/include/TestBench.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
@@ -58,9 +58,19 @@
   /* PDP channels */
   static const uint32_t kJaguarPDPChannel = 6;
   static const uint32_t kVictorPDPChannel = 8;
-  static const uint32_t kTalonPDPChannel = 11;
+  static const uint32_t kTalonPDPChannel = 10;
 
   /* PCM channels */
   static const int32_t kSolenoidChannel1 = 0;
   static const int32_t kSolenoidChannel2 = 1;
+
+  /* Filter constants */
+  static constexpr double kFilterStep = 0.005;
+  static constexpr double kFilterTime = 2.0;
+  static constexpr double kSinglePoleIIRTimeConstant = 0.015915;
+  static constexpr double kSinglePoleIIRExpectedOutput = -3.2172003;
+  static constexpr double kHighPassTimeConstant = 0.006631;
+  static constexpr double kHighPassExpectedOutput = 10.074717;
+  static constexpr int kMovAvgTaps = 6;
+  static constexpr double kMovAvgExpectedOutput = -10.191644;
 };
diff --git a/wpilibcIntegrationTests/include/command/MockCommand.h b/wpilibcIntegrationTests/include/command/MockCommand.h
index e52a6fc..421d5eb 100644
--- a/wpilibcIntegrationTests/include/command/MockCommand.h
+++ b/wpilibcIntegrationTests/include/command/MockCommand.h
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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>
diff --git a/wpilibcIntegrationTests/src/AnalogLoopTest.cpp b/wpilibcIntegrationTests/src/AnalogLoopTest.cpp
index e8bc1e5..8e4e139 100644
--- a/wpilibcIntegrationTests/src/AnalogLoopTest.cpp
+++ b/wpilibcIntegrationTests/src/AnalogLoopTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/AnalogPotentiometerTest.cpp b/wpilibcIntegrationTests/src/AnalogPotentiometerTest.cpp
index 70ca4e8..07934ae 100644
--- a/wpilibcIntegrationTests/src/AnalogPotentiometerTest.cpp
+++ b/wpilibcIntegrationTests/src/AnalogPotentiometerTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/BuiltInAccelerometerTest.cpp b/wpilibcIntegrationTests/src/BuiltInAccelerometerTest.cpp
index d6563e0..f8bee87 100644
--- a/wpilibcIntegrationTests/src/BuiltInAccelerometerTest.cpp
+++ b/wpilibcIntegrationTests/src/BuiltInAccelerometerTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/CANJaguarTest.cpp b/wpilibcIntegrationTests/src/CANJaguarTest.cpp
index f1b8e5d..6f897ea 100644
--- a/wpilibcIntegrationTests/src/CANJaguarTest.cpp
+++ b/wpilibcIntegrationTests/src/CANJaguarTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/CANTalonTest.cpp b/wpilibcIntegrationTests/src/CANTalonTest.cpp
index 2584f3f..515c840 100644
--- a/wpilibcIntegrationTests/src/CANTalonTest.cpp
+++ b/wpilibcIntegrationTests/src/CANTalonTest.cpp
@@ -1,7 +1,8 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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 $(WIND_BASE)/WPILib.  */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
 /*----------------------------------------------------------------------------*/
 
 #include <CANTalon.h>
@@ -67,3 +68,9 @@
   talon.Disable();
   EXPECT_NEAR(talon.Get(), 500, 1000);
 }
+
+TEST(CANTalonTest, GetFaults) {
+  CANTalon talon(deviceId);
+  EXPECT_EQ(talon.GetFaults(),0);
+  EXPECT_EQ(talon.GetStickyFaults(),0);
+}
diff --git a/wpilibcIntegrationTests/src/CircularBufferTest.cpp b/wpilibcIntegrationTests/src/CircularBufferTest.cpp
new file mode 100644
index 0000000..5a9cd4c
--- /dev/null
+++ b/wpilibcIntegrationTests/src/CircularBufferTest.cpp
@@ -0,0 +1,90 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015-2016. 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 <CircularBuffer.h>
+#include "gtest/gtest.h"
+#include <array>
+
+static const std::array<double, 10> values = {751.848, 766.366, 342.657,
+                                              234.252, 716.126, 132.344,
+                                              445.697, 22.727, 421.125,
+                                              799.913};
+
+static const std::array<double, 8> pushFrontOut = {799.913, 421.125, 22.727,
+                                                   445.697, 132.344, 716.126,
+                                                   234.252, 342.657};
+
+static const std::array<double, 8> pushBackOut = {342.657, 234.252, 716.126,
+                                                  132.344, 445.697, 22.727,
+                                                  421.125, 799.913};
+
+TEST(CircularBufferTest, PushFrontTest) {
+  CircularBuffer<double> queue(8);
+
+  for (auto& value : values) {
+    queue.PushFront(value);
+  }
+
+  for (unsigned int i = 0; i < pushFrontOut.size(); i++) {
+    EXPECT_EQ(pushFrontOut[i], queue[i]);
+  }
+}
+
+TEST(CircularBufferTest, PushBackTest) {
+  CircularBuffer<double> queue(8);
+
+  for (auto& value : values) {
+    queue.PushBack(value);
+  }
+
+  for (unsigned int i = 0; i < pushBackOut.size(); i++) {
+    EXPECT_EQ(pushBackOut[i], queue[i]);
+  }
+}
+
+TEST(CircularBufferTest, PushPopTest) {
+  CircularBuffer<double> queue(3);
+
+  // Insert three elements into the buffer
+  queue.PushBack(1.0);
+  queue.PushBack(2.0);
+  queue.PushBack(3.0);
+
+  EXPECT_EQ(1.0, queue[0]);
+  EXPECT_EQ(2.0, queue[1]);
+  EXPECT_EQ(3.0, queue[2]);
+
+  /*
+   * The buffer is full now, so pushing subsequent elements will overwrite the
+   * front-most elements.
+   */
+
+  queue.PushBack(4.0); // Overwrite 1 with 4
+
+  // The buffer now contains 2, 3 and 4
+  EXPECT_EQ(2.0, queue[0]);
+  EXPECT_EQ(3.0, queue[1]);
+  EXPECT_EQ(4.0, queue[2]);
+
+  queue.PushBack(5.0); // Overwrite 2 with 5
+
+  // The buffer now contains 3, 4 and 5
+  EXPECT_EQ(3.0, queue[0]);
+  EXPECT_EQ(4.0, queue[1]);
+  EXPECT_EQ(5.0, queue[2]);
+
+  EXPECT_EQ(5.0, queue.PopBack()); // 5 is removed
+
+  // The buffer now contains 3 and 4
+  EXPECT_EQ(3.0, queue[0]);
+  EXPECT_EQ(4.0, queue[1]);
+
+  EXPECT_EQ(3.0, queue.PopFront()); // 3 is removed
+
+  // Leaving only one element with value == 4
+  EXPECT_EQ(4.0, queue[0]);
+}
diff --git a/wpilibcIntegrationTests/src/ConditionVariableTest.cpp b/wpilibcIntegrationTests/src/ConditionVariableTest.cpp
index 43e792a..c405e94 100644
--- a/wpilibcIntegrationTests/src/ConditionVariableTest.cpp
+++ b/wpilibcIntegrationTests/src/ConditionVariableTest.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "TestBench.h"
 
 #include "HAL/cpp/priority_condition_variable.h"
diff --git a/wpilibcIntegrationTests/src/CounterTest.cpp b/wpilibcIntegrationTests/src/CounterTest.cpp
index 12a4226..cbf9dc5 100644
--- a/wpilibcIntegrationTests/src/CounterTest.cpp
+++ b/wpilibcIntegrationTests/src/CounterTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/DIOLoopTest.cpp b/wpilibcIntegrationTests/src/DIOLoopTest.cpp
index c13d145..480e4b7 100644
--- a/wpilibcIntegrationTests/src/DIOLoopTest.cpp
+++ b/wpilibcIntegrationTests/src/DIOLoopTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
@@ -8,6 +8,7 @@
 #include <Counter.h>
 #include <DigitalInput.h>
 #include <DigitalOutput.h>
+#include <InterruptableSensorBase.h>
 #include <Timer.h>
 #include "gtest/gtest.h"
 #include "TestBench.h"
@@ -58,6 +59,60 @@
   EXPECT_TRUE(m_input->Get()) << "The digital output was turned on, but "
                               << "the digital input is off.";
 }
+/**
+ * Tests to see if the DIO PWM functionality works.
+ */
+TEST_F(DIOLoopTest, DIOPWM) {
+  Reset();
+
+  m_output->Set(false);
+  Wait(kDelayTime);
+  EXPECT_FALSE(m_input->Get()) << "The digital output was turned off, but "
+                               << "the digital input is on.";
+
+  //Set frequency to 2.0 Hz
+  m_output->SetPWMRate(2.0);
+  //Enable PWM, but leave it off
+  m_output->EnablePWM(0.0);
+  Wait(0.5);
+  m_output->UpdateDutyCycle(0.5);
+  m_input->RequestInterrupts();
+  m_input->SetUpSourceEdge(false, true);
+  InterruptableSensorBase::WaitResult result = m_input->WaitForInterrupt(3.0, true);
+
+  Wait(0.5);
+  bool firstCycle = m_input->Get();
+  Wait(0.5);
+  bool secondCycle = m_input->Get();
+  Wait(0.5);
+  bool thirdCycle = m_input->Get();
+  Wait(0.5);
+  bool forthCycle = m_input->Get();
+  Wait(0.5);
+  bool fifthCycle = m_input->Get();
+  Wait(0.5);
+  bool sixthCycle = m_input->Get();
+  Wait(0.5);
+  bool seventhCycle = m_input->Get();
+  m_output->DisablePWM();
+  Wait(0.5);
+  bool firstAfterStop = m_input->Get();
+  Wait(0.5);
+  bool secondAfterStop = m_input->Get();
+
+  EXPECT_EQ(InterruptableSensorBase::WaitResult::kFallingEdge, result)
+                                  << "WaitForInterrupt was not falling.";
+
+  EXPECT_FALSE(firstCycle) << "Input not low after first delay";
+  EXPECT_TRUE(secondCycle) << "Input not high after second delay";
+  EXPECT_FALSE(thirdCycle) << "Input not low after third delay";
+  EXPECT_TRUE(forthCycle) << "Input not high after forth delay";
+  EXPECT_FALSE(fifthCycle) << "Input not low after fifth delay";
+  EXPECT_TRUE(sixthCycle) << "Input not high after sixth delay";
+  EXPECT_FALSE(seventhCycle) << "Input not low after seventh delay";
+  EXPECT_FALSE(firstAfterStop) << "Input not low after stopping first read";
+  EXPECT_FALSE(secondAfterStop) << "Input not low after stopping second read";
+}
 
 /**
  * Test a fake "counter" that uses the DIO loop as an input to make sure the
diff --git a/wpilibcIntegrationTests/src/DigitalGlitchFilterTest.cpp b/wpilibcIntegrationTests/src/DigitalGlitchFilterTest.cpp
index dfcec48..c30deb8 100644
--- a/wpilibcIntegrationTests/src/DigitalGlitchFilterTest.cpp
+++ b/wpilibcIntegrationTests/src/DigitalGlitchFilterTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2015. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2015-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/FakeEncoderTest.cpp b/wpilibcIntegrationTests/src/FakeEncoderTest.cpp
index 3a5dbbb..601430b 100644
--- a/wpilibcIntegrationTests/src/FakeEncoderTest.cpp
+++ b/wpilibcIntegrationTests/src/FakeEncoderTest.cpp
@@ -1,7 +1,6 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
-/* Open Source Software - may be modified and shared by FRC teams. The code
- */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
 /*----------------------------------------------------------------------------*/
diff --git a/wpilibcIntegrationTests/src/FilterNoiseTest.cpp b/wpilibcIntegrationTests/src/FilterNoiseTest.cpp
new file mode 100644
index 0000000..cad0b17
--- /dev/null
+++ b/wpilibcIntegrationTests/src/FilterNoiseTest.cpp
@@ -0,0 +1,133 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015-2016. 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 <functional>
+#include <memory>
+#include <random>
+#include <thread>
+#include <cmath>
+
+#include <Filters/LinearDigitalFilter.h>
+
+#include "gtest/gtest.h"
+#include "TestBench.h"
+#include "Base.h"
+
+enum FilterNoiseTestType { TEST_SINGLE_POLE_IIR, TEST_MOVAVG };
+
+std::ostream& operator<<(std::ostream& os, const FilterNoiseTestType& type) {
+  switch (type) {
+    case TEST_SINGLE_POLE_IIR:
+      os << "LinearDigitalFilter SinglePoleIIR";
+      break;
+    case TEST_MOVAVG:
+      os << "LinearDigitalFilter MovingAverage";
+      break;
+  }
+
+  return os;
+}
+
+using std::chrono::system_clock;
+
+constexpr double kStdDev = 10.0;
+
+/**
+ * Adds Gaussian white noise to a function returning data. The noise will have
+ * the standard deviation provided in the constructor.
+ */
+class NoiseGenerator : public PIDSource {
+ public:
+  NoiseGenerator(double (*dataFunc)(double), double stdDev) :
+      m_distr(0.0, stdDev) {
+    m_dataFunc = dataFunc;
+  }
+
+  void SetPIDSourceType(PIDSourceType pidSource) override {}
+
+  double Get() {
+    return m_dataFunc(m_count) + m_noise;
+  }
+
+  double PIDGet() override {
+    m_noise = m_distr(m_gen);
+    m_count += TestBench::kFilterStep;
+    return m_dataFunc(m_count) + m_noise;
+  }
+
+  void Reset() {
+    m_count = -TestBench::kFilterStep;
+  }
+
+ private:
+  std::function<double(double)> m_dataFunc;
+  double m_noise = 0.0;
+
+  // Make sure first call to PIDGet() uses m_count == 0
+  double m_count = -TestBench::kFilterStep;
+
+  std::random_device m_rd;
+  std::mt19937 m_gen{m_rd()};
+  std::normal_distribution<double> m_distr;
+};
+
+/**
+ * A fixture that includes a noise generator wrapped in a filter
+ */
+class FilterNoiseTest : public testing::TestWithParam<FilterNoiseTestType> {
+ protected:
+  std::unique_ptr<PIDSource> m_filter;
+  std::shared_ptr<NoiseGenerator> m_noise;
+
+  static double GetData(double t) {
+    return 100.0 * std::sin(2.0 * M_PI * t);
+  }
+
+  void SetUp() override {
+    m_noise = std::make_shared<NoiseGenerator>(GetData, kStdDev);
+
+    switch (GetParam()) {
+      case TEST_SINGLE_POLE_IIR: {
+        m_filter = std::make_unique<LinearDigitalFilter>(LinearDigitalFilter::SinglePoleIIR(m_noise,
+            TestBench::kSinglePoleIIRTimeConstant,
+            TestBench::kFilterStep));
+        break;
+      }
+
+      case TEST_MOVAVG: {
+        m_filter = std::make_unique<LinearDigitalFilter>(LinearDigitalFilter::MovingAverage(m_noise,
+            TestBench::kMovAvgTaps));
+        break;
+      }
+    }
+  }
+};
+
+/**
+ * Test if the filter reduces the noise produced by a signal generator
+ */
+TEST_P(FilterNoiseTest, NoiseReduce) {
+  double theoryData = 0.0;
+  double noiseGenError = 0.0;
+  double filterError = 0.0;
+
+  m_noise->Reset();
+  for (double t = 0; t < TestBench::kFilterTime; t += TestBench::kFilterStep) {
+    theoryData = GetData(t);
+    filterError += std::abs(m_filter->PIDGet() - theoryData);
+    noiseGenError += std::abs(m_noise->Get() - theoryData);
+  }
+
+  RecordProperty("FilterError", filterError);
+
+  // The filter should have produced values closer to the theory
+  EXPECT_GT(noiseGenError, filterError)
+      << "Filter should have reduced noise accumulation but failed";
+}
+
+INSTANTIATE_TEST_CASE_P(Test, FilterNoiseTest,
+                        testing::Values(TEST_SINGLE_POLE_IIR, TEST_MOVAVG));
diff --git a/wpilibcIntegrationTests/src/FilterOutputTest.cpp b/wpilibcIntegrationTests/src/FilterOutputTest.cpp
new file mode 100644
index 0000000..8a64ca4
--- /dev/null
+++ b/wpilibcIntegrationTests/src/FilterOutputTest.cpp
@@ -0,0 +1,124 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015-2016. 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 <functional>
+#include <memory>
+#include <random>
+#include <thread>
+#include <cmath>
+
+#include <Filters/LinearDigitalFilter.h>
+
+#include "gtest/gtest.h"
+#include "TestBench.h"
+#include "Base.h"
+
+enum FilterOutputTestType { TEST_SINGLE_POLE_IIR, TEST_HIGH_PASS, TEST_MOVAVG };
+
+std::ostream& operator<<(std::ostream& os, const FilterOutputTestType& type) {
+  switch (type) {
+    case TEST_SINGLE_POLE_IIR:
+      os << "LinearDigitalFilter SinglePoleIIR";
+      break;
+    case TEST_HIGH_PASS:
+      os << "LinearDigitalFilter HighPass";
+      break;
+    case TEST_MOVAVG:
+      os << "LinearDigitalFilter MovingAverage";
+      break;
+  }
+
+  return os;
+}
+
+class DataWrapper : public PIDSource {
+ public:
+  DataWrapper(double (*dataFunc)(double)) {
+    m_dataFunc = dataFunc;
+  }
+
+  virtual void SetPIDSourceType(PIDSourceType pidSource) {}
+
+  virtual double PIDGet() {
+    m_count += TestBench::kFilterStep;
+    return m_dataFunc(m_count);
+  }
+
+  void Reset() {
+    m_count = -TestBench::kFilterStep;
+  }
+
+ private:
+  std::function<double(double)> m_dataFunc;
+
+  // Make sure first call to PIDGet() uses m_count == 0
+  double m_count = -TestBench::kFilterStep;
+};
+
+/**
+ * A fixture that includes a consistent data source wrapped in a filter
+ */
+class FilterOutputTest : public testing::TestWithParam<FilterOutputTestType> {
+ protected:
+  std::unique_ptr<PIDSource> m_filter;
+  std::shared_ptr<DataWrapper> m_data;
+  double m_expectedOutput = 0.0;
+
+  static double GetData(double t) {
+    return 100.0 * std::sin(2.0 * M_PI * t) + 20.0 * std::cos(50.0 * M_PI * t);
+  }
+
+  void SetUp() override {
+    m_data = std::make_shared<DataWrapper>(GetData);
+
+    switch (GetParam()) {
+      case TEST_SINGLE_POLE_IIR: {
+        m_filter = std::make_unique<LinearDigitalFilter>(LinearDigitalFilter::SinglePoleIIR(m_data,
+                                                                                            TestBench::kSinglePoleIIRTimeConstant,
+                                                                                            TestBench::kFilterStep));
+        m_expectedOutput = TestBench::kSinglePoleIIRExpectedOutput;
+        break;
+      }
+
+      case TEST_HIGH_PASS: {
+        m_filter = std::make_unique<LinearDigitalFilter>(LinearDigitalFilter::HighPass(m_data,
+                                                                                       TestBench::kHighPassTimeConstant,
+                                                                                       TestBench::kFilterStep));
+        m_expectedOutput = TestBench::kHighPassExpectedOutput;
+        break;
+      }
+
+      case TEST_MOVAVG: {
+        m_filter = std::make_unique<LinearDigitalFilter>(LinearDigitalFilter::MovingAverage(m_data,
+                                                                                            TestBench::kMovAvgTaps));
+        m_expectedOutput = TestBench::kMovAvgExpectedOutput;
+        break;
+      }
+    }
+  }
+};
+
+/**
+ * Test if the linear digital filters produce consistent output
+ */
+TEST_P(FilterOutputTest, FilterOutput) {
+  m_data->Reset();
+
+  double filterOutput = 0.0;
+  for (double t = 0.0; t < TestBench::kFilterTime; t += TestBench::kFilterStep) {
+    filterOutput = m_filter->PIDGet();
+  }
+
+  RecordProperty("FilterOutput", filterOutput);
+
+  EXPECT_FLOAT_EQ(m_expectedOutput, filterOutput)
+      << "Filter output didn't match expected value";
+}
+
+INSTANTIATE_TEST_CASE_P(Test, FilterOutputTest,
+                        testing::Values(TEST_SINGLE_POLE_IIR, TEST_HIGH_PASS,
+                                        TEST_MOVAVG));
diff --git a/wpilibcIntegrationTests/src/MotorEncoderTest.cpp b/wpilibcIntegrationTests/src/MotorEncoderTest.cpp
index 47f0ab9..9b3c609 100644
--- a/wpilibcIntegrationTests/src/MotorEncoderTest.cpp
+++ b/wpilibcIntegrationTests/src/MotorEncoderTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
@@ -84,7 +84,7 @@
   Reset();
 
   /* Drive the speed controller briefly to move the encoder */
-  m_speedController->Set(1.0);
+  m_speedController->Set(0.2f);
   Wait(kMotorTime);
   m_speedController->Set(0.0);
 
@@ -100,7 +100,7 @@
   Reset();
 
   /* Drive the speed controller briefly to move the encoder */
-  m_speedController->Set(-1.0f);
+  m_speedController->Set(-0.2f);
   Wait(kMotorTime);
   m_speedController->Set(0.0f);
 
@@ -131,12 +131,12 @@
  */
 TEST_P(MotorEncoderTest, PositionPIDController) {
   Reset();
-
+  double goal = 1000;
   m_encoder->SetPIDSourceType(PIDSourceType::kDisplacement);
   PIDController pid(0.001f, 0.0005f, 0.0f, m_encoder, m_speedController);
-  pid.SetAbsoluteTolerance(20.0f);
-  pid.SetOutputRange(-0.3f, 0.3f);
-  pid.SetSetpoint(2500);
+  pid.SetAbsoluteTolerance(50.0f);
+  pid.SetOutputRange(-0.2f, 0.2f);
+  pid.SetSetpoint(goal);
 
   /* 10 seconds should be plenty time to get to the setpoint */
   pid.Enable();
@@ -145,7 +145,7 @@
 
   RecordProperty("PIDError", pid.GetError());
 
-  EXPECT_TRUE(pid.OnTarget()) << "PID loop did not converge within 10 seconds.";
+  EXPECT_TRUE(pid.OnTarget()) << "PID loop did not converge within 10 seconds. Goal was: "<<goal<<" Error was: "<<pid.GetError();
 }
 
 /**
@@ -156,20 +156,18 @@
 
   m_encoder->SetPIDSourceType(PIDSourceType::kRate);
   PIDController pid(1e-5, 0.0f, 3e-5, 8e-5, m_encoder, m_speedController);
-  pid.SetAbsoluteTolerance(50.0f);
-  pid.SetToleranceBuffer(10);
+  pid.SetAbsoluteTolerance(200.0f);
+  pid.SetToleranceBuffer(50);
   pid.SetOutputRange(-0.3f, 0.3f);
-  pid.SetSetpoint(2000);
+  pid.SetSetpoint(600);
 
   /* 10 seconds should be plenty time to get to the setpoint */
   pid.Enable();
   Wait(10.0);
-
-  RecordProperty("PIDError", pid.GetAvgError());
-
-  EXPECT_TRUE(pid.OnTarget()) << "PID loop did not converge within 10 seconds. Goal was: " << 2000 << " Error was: " << pid.GetError();
-
   pid.Disable();
+  RecordProperty("PIDError", pid.GetError());
+
+  EXPECT_TRUE(pid.OnTarget()) << "PID loop did not converge within 10 seconds. Goal was: " << 600 << " Error was: " << pid.GetError();
 }
 
 /**
diff --git a/wpilibcIntegrationTests/src/MotorInvertingTest.cpp b/wpilibcIntegrationTests/src/MotorInvertingTest.cpp
index 1794299..fc78c32 100644
--- a/wpilibcIntegrationTests/src/MotorInvertingTest.cpp
+++ b/wpilibcIntegrationTests/src/MotorInvertingTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
@@ -14,7 +14,7 @@
 #include "TestBench.h"
 
 enum MotorInvertingTestType { TEST_VICTOR, TEST_JAGUAR, TEST_TALON };
-static const double motorSpeed = 0.25;
+static const double motorSpeed = 0.15;
 static const double delayTime = 0.5;
 std::ostream &operator<<(std::ostream &os, MotorInvertingTestType const &type) {
   switch (type) {
diff --git a/wpilibcIntegrationTests/src/MutexTest.cpp b/wpilibcIntegrationTests/src/MutexTest.cpp
index 1e80ec9..dcd373c 100644
--- a/wpilibcIntegrationTests/src/MutexTest.cpp
+++ b/wpilibcIntegrationTests/src/MutexTest.cpp
@@ -1,3 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016. 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 "HAL/cpp/priority_mutex.h"
 #include "TestBench.h"
 
diff --git a/wpilibcIntegrationTests/src/NotifierTest.cpp b/wpilibcIntegrationTests/src/NotifierTest.cpp
index 10e0504..7d51256 100644
--- a/wpilibcIntegrationTests/src/NotifierTest.cpp
+++ b/wpilibcIntegrationTests/src/NotifierTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/PCMTest.cpp b/wpilibcIntegrationTests/src/PCMTest.cpp
index 14f23ca..23277b0 100644
--- a/wpilibcIntegrationTests/src/PCMTest.cpp
+++ b/wpilibcIntegrationTests/src/PCMTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/PIDToleranceTest.cpp b/wpilibcIntegrationTests/src/PIDToleranceTest.cpp
new file mode 100644
index 0000000..35e60ae
--- /dev/null
+++ b/wpilibcIntegrationTests/src/PIDToleranceTest.cpp
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014-2016. 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 <Timer.h>
+#include "gtest/gtest.h"
+#include "TestBench.h"
+#include "PIDSource.h"
+#include "PIDController.h"
+#include "PIDOutput.h"
+
+class PIDToleranceTest : public testing::Test{
+protected:
+	const double setpoint = 50.0;
+	const double range = 200;
+	const double tolerance = 10.0;
+	class fakeInput : public PIDSource{
+		public:
+		double val = 0;
+		void SetPIDSourceType(PIDSourceType pidSource){
+		  }
+		  PIDSourceType GetPIDSourceType(){
+			  return PIDSourceType::kDisplacement;
+		  }
+		  double PIDGet(){;
+		  	  return val;
+		  }
+	};
+	class fakeOutput : public PIDOutput{
+		void PIDWrite(float output){
+
+		}
+	};
+	fakeInput inp;
+	fakeOutput out;
+	PIDController *pid;
+	virtual void SetUp() override {
+		pid = new PIDController(0.5,0.0,0.0,&inp,&out);
+		pid->SetInputRange(-range/2,range/2);
+	}
+	virtual void TearDown() override {
+		delete pid;
+	}
+	virtual void reset(){
+		inp.val = 0;
+	}
+};
+
+TEST_F(PIDToleranceTest, Absolute){
+	reset();
+	pid->SetAbsoluteTolerance(tolerance);
+	pid->SetSetpoint(setpoint);
+	pid->Enable();
+	EXPECT_FALSE(pid->OnTarget())<<"Error was in tolerance when it should not have been. Error was " << pid->GetAvgError();
+	inp.val = setpoint+tolerance/2;
+	Wait(1.0);
+	EXPECT_TRUE(pid->OnTarget())<<"Error was not in tolerance when it should have been. Error was " << pid->GetAvgError();
+	inp.val = setpoint+10*tolerance;
+	Wait(1.0);
+	EXPECT_FALSE(pid->OnTarget())<<"Error was in tolerance when it should not have been. Error was " << pid->GetAvgError();
+}
+
+TEST_F(PIDToleranceTest, Percent){
+	reset();
+	pid->SetPercentTolerance(tolerance);
+	pid->SetSetpoint(setpoint);
+	pid->Enable();
+	EXPECT_FALSE(pid->OnTarget())<<"Error was in tolerance when it should not have been. Error was " << pid->GetAvgError();
+	inp.val = setpoint+(tolerance)/200*range;//half of percent tolerance away from setpoint
+	Wait(1.0);
+	EXPECT_TRUE(pid->OnTarget())<<"Error was not in tolerance when it should have been. Error was " << pid->GetAvgError();
+	inp.val = setpoint+(tolerance)/50*range;//double percent tolerance away from setPoint
+	Wait(1.0);
+	EXPECT_FALSE(pid->OnTarget())<<"Error was in tolerance when it should not have been. Error was " << pid->GetAvgError();
+
+}
diff --git a/wpilibcIntegrationTests/src/PowerDistributionPanelTest.cpp b/wpilibcIntegrationTests/src/PowerDistributionPanelTest.cpp
index 7dc31fd..ccfb796 100644
--- a/wpilibcIntegrationTests/src/PowerDistributionPanelTest.cpp
+++ b/wpilibcIntegrationTests/src/PowerDistributionPanelTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
@@ -56,40 +56,3 @@
       << "The Talon current was not positive";
 }
 
-/**
- * Test if the current changes when the motor is driven using a victor
- */
-TEST_F(PowerDistributionPanelTest, CheckCurrentVictor) {
-  Wait(kMotorTime);
-
-  /* The Current should be 0 */
-  EXPECT_FLOAT_EQ(0, m_pdp->GetCurrent(TestBench::kVictorPDPChannel))
-      << "The Victor current was non-zero";
-
-  /* Set the motor to full forward */
-  m_victor->Set(1.0);
-  Wait(kMotorTime);
-
-  /* The current should now be positive */
-  ASSERT_GT(m_pdp->GetCurrent(TestBench::kVictorPDPChannel), 0)
-      << "The Victor current was not positive";
-}
-
-/**
- * Test if the current changes when the motor is driven using a jaguar
- */
-TEST_F(PowerDistributionPanelTest, CheckCurrentJaguar) {
-  Wait(kMotorTime);
-
-  /* The Current should be 0 */
-  EXPECT_FLOAT_EQ(0, m_pdp->GetCurrent(TestBench::kJaguarPDPChannel))
-      << "The Jaguar current was non-zero";
-
-  /* Set the motor to full forward */
-  m_jaguar->Set(1.0);
-  Wait(kMotorTime);
-
-  /* The current should now be positive */
-  ASSERT_GT(m_pdp->GetCurrent(TestBench::kJaguarPDPChannel), 0)
-      << "The Jaguar current was not positive";
-}
diff --git a/wpilibcIntegrationTests/src/PreferencesTest.cpp b/wpilibcIntegrationTests/src/PreferencesTest.cpp
index 030d373..31e2fc2 100644
--- a/wpilibcIntegrationTests/src/PreferencesTest.cpp
+++ b/wpilibcIntegrationTests/src/PreferencesTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/RelayTest.cpp b/wpilibcIntegrationTests/src/RelayTest.cpp
index c919297..e18c884 100644
--- a/wpilibcIntegrationTests/src/RelayTest.cpp
+++ b/wpilibcIntegrationTests/src/RelayTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/TestEnvironment.cpp b/wpilibcIntegrationTests/src/TestEnvironment.cpp
index d65493a..b3f5500 100644
--- a/wpilibcIntegrationTests/src/TestEnvironment.cpp
+++ b/wpilibcIntegrationTests/src/TestEnvironment.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp b/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp
index 35b8d29..5b42543 100644
--- a/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp
+++ b/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/TimerTest.cpp b/wpilibcIntegrationTests/src/TimerTest.cpp
index faa6ada..5543938 100644
--- a/wpilibcIntegrationTests/src/TimerTest.cpp
+++ b/wpilibcIntegrationTests/src/TimerTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/command/CommandTest.cpp b/wpilibcIntegrationTests/src/command/CommandTest.cpp
index 3e16021..9b3f7d0 100644
--- a/wpilibcIntegrationTests/src/command/CommandTest.cpp
+++ b/wpilibcIntegrationTests/src/command/CommandTest.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */
diff --git a/wpilibcIntegrationTests/src/command/MockCommand.cpp b/wpilibcIntegrationTests/src/command/MockCommand.cpp
index a4d22f8..c244ebb 100644
--- a/wpilibcIntegrationTests/src/command/MockCommand.cpp
+++ b/wpilibcIntegrationTests/src/command/MockCommand.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Copyright (c) FIRST 2014-2016. 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.                                                               */