Merge "Improve variable names and comments in blob code"
diff --git a/BUILD b/BUILD
new file mode 100644
index 0000000..4509a20
--- /dev/null
+++ b/BUILD
@@ -0,0 +1 @@
+exports_files(["tsconfig.json"])
diff --git a/WORKSPACE b/WORKSPACE
index b1199c7..f5428db 100644
--- a/WORKSPACE
+++ b/WORKSPACE
@@ -407,3 +407,31 @@
         "http://www.frc971.org/Build-Dependencies/core-5.14.1-headers.zip",
     ],
 )
+
+http_archive(
+    name = "build_bazel_rules_typescript",
+    strip_prefix = "rules_typescript-0.21.0",
+    url = "https://github.com/bazelbuild/rules_typescript/archive/0.21.0.zip",
+)
+
+# Fetch our Bazel dependencies that aren't distributed on npm
+load("@build_bazel_rules_typescript//:package.bzl", "rules_typescript_dependencies")
+
+rules_typescript_dependencies()
+
+# Setup TypeScript toolchain
+load("@build_bazel_rules_typescript//:defs.bzl", "ts_setup_workspace")
+
+ts_setup_workspace()
+
+# Setup the NodeJS toolchain
+load("@build_bazel_rules_nodejs//:defs.bzl", "node_repositories", "yarn_install")
+
+node_repositories()
+
+# Setup Bazel managed npm dependencies with the `yarn_install` rule.
+yarn_install(
+    name = "npm",
+    package_json = "//:package.json",
+    yarn_lock = "//:yarn.lock",
+)
diff --git a/aos/input/action_joystick_input.cc b/aos/input/action_joystick_input.cc
index 991ea17..81e277d 100644
--- a/aos/input/action_joystick_input.cc
+++ b/aos/input/action_joystick_input.cc
@@ -16,13 +16,18 @@
                   data.GetControlBit(ControlBit::kEnabled);
   if (auto_running_ != last_auto_running) {
     if (auto_running_) {
+      auto_was_running_ = true;
       StartAuto();
     } else {
       StopAuto();
     }
   }
 
-  if (!auto_running_) {
+  if (!auto_running_ || (run_teleop_in_auto_ && !action_queue_.Running())) {
+    if (auto_was_running_) {
+      AutoEnded();
+      auto_was_running_ = false;
+    }
     if (!data.GetControlBit(ControlBit::kEnabled)) {
       action_queue_.CancelAllActions();
       LOG(DEBUG, "Canceling\n");
diff --git a/aos/input/action_joystick_input.h b/aos/input/action_joystick_input.h
index d4023ca..87b980e 100644
--- a/aos/input/action_joystick_input.h
+++ b/aos/input/action_joystick_input.h
@@ -24,7 +24,14 @@
 
   virtual ~ActionJoystickInput() {}
 
+ protected:
+  void set_run_teleop_in_auto(bool run_teleop_in_auto) {
+    run_teleop_in_auto_ = run_teleop_in_auto;
+  }
+
  private:
+  // Handles anything that needs to be cleaned up when the auto action exits.
+  virtual void AutoEnded() {}
   // Handles any year specific superstructure code.
   virtual void HandleTeleop(const ::aos::input::driver_station::Data &data) = 0;
 
@@ -38,6 +45,16 @@
   // True if an action was running last cycle.
   bool was_running_ = false;
 
+  // If true, we will run teleop during auto mode after auto mode ends.  This is
+  // to support the 2019 sandstorm mode.  Auto will run, and then when the
+  // action ends (either when it's done, or when the driver triggers it to
+  // finish early), we will run teleop regardless of the mode.
+  bool run_teleop_in_auto_ = false;
+
+  // Bool to track if auto was running the last cycle through.  This lets us
+  // call AutoEnded when the auto mode function stops.
+  bool auto_was_running_ = false;
+
   ::std::unique_ptr<DrivetrainInputReader> drivetrain_input_reader_;
   ::aos::common::actions::ActionQueue action_queue_;
 };
diff --git a/aos/input/drivetrain_input.cc b/aos/input/drivetrain_input.cc
index 02957a8..248f1ce 100644
--- a/aos/input/drivetrain_input.cc
+++ b/aos/input/drivetrain_input.cc
@@ -62,12 +62,15 @@
     }
   }
 
-  if (is_control_loop_driving) {
-    if (drivetrain_queue.status.get()) {
-      left_goal_ = drivetrain_queue.status->estimated_left_position;
-      right_goal_ = drivetrain_queue.status->estimated_right_position;
+  if (drivetrain_queue.status.get()) {
+    if (is_control_loop_driving && !last_is_control_loop_driving_) {
+      left_goal_ = drivetrain_queue.status->estimated_left_position +
+                   wheel * wheel_multiplier_;
+      right_goal_ = drivetrain_queue.status->estimated_right_position -
+                    wheel * wheel_multiplier_;
     }
   }
+
   const double current_left_goal =
       left_goal_ - wheel * wheel_multiplier_ + throttle * 0.3;
   const double current_right_goal =
@@ -92,6 +95,8 @@
   if (!new_drivetrain_goal.Send()) {
     LOG(WARNING, "sending stick values failed\n");
   }
+
+  last_is_control_loop_driving_ = is_control_loop_driving;
 }
 
 DrivetrainInputReader::WheelAndThrottle
@@ -242,10 +247,13 @@
 
   // TODO(james): Make a copy assignment operator for ButtonLocation so we don't
   // have to shoehorn in these ternary operators.
-  const ButtonLocation kTurn1 =
+  const ButtonLocation kTurn1 = (top_button_use == TopButtonUse::kLineFollow)
+                                    ? SecondButton
+                                    : DummyButton;
+  // Turn2 does closed loop driving.
+  const ButtonLocation kTurn2 =
       (top_button_use == TopButtonUse::kLineFollow) ? TopButton : DummyButton;
-  // Turn2 currently does nothing on the pistol grip, ever.
-  const ButtonLocation kTurn2 = DummyButton;
+
   const ButtonLocation kShiftHigh =
       (top_button_use == TopButtonUse::kShift) ? TopButton : DummyButton;
   const ButtonLocation kShiftLow =
diff --git a/aos/input/drivetrain_input.h b/aos/input/drivetrain_input.h
index 80046ee..f4b0212 100644
--- a/aos/input/drivetrain_input.h
+++ b/aos/input/drivetrain_input.h
@@ -96,6 +96,8 @@
   const driver_station::ButtonLocation turn2_;
   const TurnButtonUse turn2_use_;
 
+  bool last_is_control_loop_driving_ = false;
+
   // Structure containing the (potentially adjusted) steering and throttle
   // values from the joysticks.
   struct WheelAndThrottle {
@@ -183,7 +185,7 @@
       driver_station::ButtonLocation turn2)
       : DrivetrainInputReader(wheel_high, throttle_high, quick_turn, turn1,
                               TurnButtonUse::kLineFollow, turn2,
-                              TurnButtonUse::kLineFollow),
+                              TurnButtonUse::kControlLoopDriving),
         wheel_low_(wheel_low),
         wheel_velocity_high_(wheel_velocity_high),
         wheel_velocity_low_(wheel_velocity_low),
diff --git a/aos/logging/implementations.cc b/aos/logging/implementations.cc
index efeb704..78b6724 100644
--- a/aos/logging/implementations.cc
+++ b/aos/logging/implementations.cc
@@ -112,8 +112,10 @@
   FillInMessageBase(level, message);
 
   if (message_string.size() + size > sizeof(message->structure.serialized)) {
-    LOG(FATAL, "serialized struct %s (size %zd) and message %s too big\n",
-        type->name.c_str(), size, message_string.c_str());
+    LOG(FATAL,
+        "serialized struct %s (size %zd + %zd > %zd) and message %s too big\n",
+        type->name.c_str(), message_string.size(), size,
+        sizeof(message->structure.serialized), message_string.c_str());
   }
   message->structure.string_length = message_string.size();
   memcpy(message->structure.serialized, message_string.data(),
diff --git a/aos/logging/sizes.h b/aos/logging/sizes.h
index b624a61..d7cfd4e 100644
--- a/aos/logging/sizes.h
+++ b/aos/logging/sizes.h
@@ -3,7 +3,7 @@
 
 // This file exists so C code and context.h can both get at these constants...
 
-#define LOG_MESSAGE_LEN 500
+#define LOG_MESSAGE_LEN 512
 #define LOG_MESSAGE_NAME_LEN 100
 
 #endif  // AOS_LOGGING_SIZES_H_
diff --git a/aos/seasocks/gen_embedded.bzl b/aos/seasocks/gen_embedded.bzl
index 60930b4..34d4bd8 100644
--- a/aos/seasocks/gen_embedded.bzl
+++ b/aos/seasocks/gen_embedded.bzl
@@ -1,45 +1,46 @@
 def _gen_embedded_impl(ctx):
   ctx.action(
     inputs = ctx.files.srcs,
-    outputs = [ ctx.outputs.header ],
+    outputs = [ ctx.outputs.source ],
     executable = ctx.executable._gen_embedded,
-    arguments = [ ctx.outputs.header.path ] + [f.path for f in ctx.files.srcs],
-    progress_message = 'Generating %s' % ctx.outputs.header.short_path,
+    arguments = [ ctx.outputs.source.path ] + [f.path for f in ctx.files.srcs],
+    progress_message = 'Generating %s' % ctx.outputs.source.short_path,
     mnemonic = 'GenEmbedded',
   )
 
   return struct(
-    files = depset([ ctx.outputs.header ]),
+    files = depset([ ctx.outputs.source ]),
   )
 
 _do_gen_embedded = rule(
-  implementation = _gen_embedded_impl,
-  attrs = {
-    'srcs': attr.label_list(
-      mandatory = True,
-      non_empty = True,
-      allow_files = True,
-    ),
-    '_gen_embedded': attr.label(
-      executable = True,
-      default = Label('//aos/seasocks:gen_embedded'),
-      cfg = 'host',
-    ),
-  },
-  outputs = {
-    'header': 'embedded.h',
-  },
-  output_to_genfiles = True,
+    attrs = {
+        "srcs": attr.label_list(
+            mandatory = True,
+            non_empty = True,
+            allow_files = True,
+        ),
+        "_gen_embedded": attr.label(
+            executable = True,
+            default = Label("//aos/seasocks:gen_embedded"),
+            cfg = "host",
+        ),
+    },
+    output_to_genfiles = True,
+    outputs = {
+        "source": "embedded.cc",
+    },
+    implementation = _gen_embedded_impl,
 )
 
-'''Generates the header for Seasocks to load the embedded files.
+"""Generates the header for Seasocks to load the embedded files.
 
 This always outputs a file named "embedded.h" in the current package, so there
 can be a maximum of one of these rules in each package.
 
 Attrs:
   srcs: Files to allow loading.
-'''
+"""
+
 def gen_embedded(name, srcs, visibility = None):
   _do_gen_embedded(
     name = name + '__do_gen',
@@ -48,8 +49,12 @@
   )
   native.cc_library(
     name = name,
-    visibiltity = visibility,
-    hdrs = [
+    visibility = visibility,
+    linkstatic = True,
+    srcs = [
       ':%s__do_gen' % name,
     ],
+    deps = [
+      '@//third_party/seasocks',
+    ],
   )
diff --git a/aos/vision/blob/threshold.cc b/aos/vision/blob/threshold.cc
index 74809d1..36dcafe 100644
--- a/aos/vision/blob/threshold.cc
+++ b/aos/vision/blob/threshold.cc
@@ -4,20 +4,17 @@
 
 namespace aos {
 namespace vision {
+namespace {
 
-// Expands to a unique value for each combination of values for 5 bools.
-#define MASH(v0, v1, v2, v3, v4)                                  \
-  ((uint8_t(v0) << 4) | (uint8_t(v1) << 3) | (uint8_t(v2) << 2) | \
-   (uint8_t(v3) << 1) | (uint8_t(v4)))
+constexpr int kChunkSize = 8;
+
+}  // namespace
 
 // At a high level, the algorithm is the same as the slow thresholding, except
-// it operates in 4-pixel chunks. The handling for each of these chunks is
-// manually flattened (via codegen) into a 32-case switch statement. There are
-// 2^4 cases for each pixel being in or out, along with another set of cases
-// depending on whether the start of the chunk is in a range or not.
+// it operates in kChunkSize-pixel chunks.
 RangeImage FastYuyvYThreshold(ImageFormat fmt, const char *data,
                               uint8_t value) {
-  CHECK_EQ(0, fmt.w % 4);
+  CHECK_EQ(0, fmt.w % kChunkSize);
   std::vector<std::vector<ImageRange>> result;
   result.reserve(fmt.h);
 
@@ -28,195 +25,22 @@
     bool in_range = false;
     int current_range_start = -1;
     std::vector<ImageRange> current_row_ranges;
-    // Iterate through each 4-pixel chunk
-    for (int x = 0; x < fmt.w / 4; ++x) {
+    // Iterate through each kChunkSize-pixel chunk
+    for (int x = 0; x < fmt.w / kChunkSize; ++x) {
       // The per-channel (YUYV) values in the current chunk.
-      uint8_t chunk_channels[8];
-      memcpy(&chunk_channels[0], current_row + x * 4 * 2, 8);
-      const uint8_t pattern =
-          MASH(in_range, chunk_channels[0] > value, chunk_channels[2] > value,
-               chunk_channels[4] > value, chunk_channels[6] > value);
-      switch (pattern) {
-        // clang-format off
-/*
-# Ruby code to generate the below code:
-32.times do |v|
-        puts "case MASH(#{[v[4], v[3], v[2], v[1], v[0]].join(", ")}):"
-        in_range = v[4]
-        current_range_start = "current_range_start"
-        4.times do |i|
-                if v[3 - i] != in_range
-                        if (in_range == 1)
-                                puts "  current_row_ranges.emplace_back(ImageRange(#{current_range_start}, x * 4 + #{i}));"
-                        else
-                                current_range_start = "x * 4 + #{i}"
-                        end
-                        in_range = v[3 - i]
-                end
-        end
-        if (current_range_start != "current_range_start")
-                puts "  current_range_start = #{current_range_start};"
-        end
-        if (in_range != v[4])
-                puts "  in_range = #{["false", "true"][v[0]]};"
-        end
-        puts "  break;"
-end
-*/
-        // clang-format on
-        case MASH(0, 0, 0, 0, 0):
-          break;
-        case MASH(0, 0, 0, 0, 1):
-          current_range_start = x * 4 + 3;
-          in_range = true;
-          break;
-        case MASH(0, 0, 0, 1, 0):
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 2, x * 4 + 3));
-          current_range_start = x * 4 + 2;
-          break;
-        case MASH(0, 0, 0, 1, 1):
-          current_range_start = x * 4 + 2;
-          in_range = true;
-          break;
-        case MASH(0, 0, 1, 0, 0):
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 1, x * 4 + 2));
-          current_range_start = x * 4 + 1;
-          break;
-        case MASH(0, 0, 1, 0, 1):
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 1, x * 4 + 2));
-          current_range_start = x * 4 + 3;
-          in_range = true;
-          break;
-        case MASH(0, 0, 1, 1, 0):
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 1, x * 4 + 3));
-          current_range_start = x * 4 + 1;
-          break;
-        case MASH(0, 0, 1, 1, 1):
-          current_range_start = x * 4 + 1;
-          in_range = true;
-          break;
-        case MASH(0, 1, 0, 0, 0):
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 0, x * 4 + 1));
-          current_range_start = x * 4 + 0;
-          break;
-        case MASH(0, 1, 0, 0, 1):
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 0, x * 4 + 1));
-          current_range_start = x * 4 + 3;
-          in_range = true;
-          break;
-        case MASH(0, 1, 0, 1, 0):
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 0, x * 4 + 1));
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 2, x * 4 + 3));
-          current_range_start = x * 4 + 2;
-          break;
-        case MASH(0, 1, 0, 1, 1):
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 0, x * 4 + 1));
-          current_range_start = x * 4 + 2;
-          in_range = true;
-          break;
-        case MASH(0, 1, 1, 0, 0):
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 0, x * 4 + 2));
-          current_range_start = x * 4 + 0;
-          break;
-        case MASH(0, 1, 1, 0, 1):
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 0, x * 4 + 2));
-          current_range_start = x * 4 + 3;
-          in_range = true;
-          break;
-        case MASH(0, 1, 1, 1, 0):
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 0, x * 4 + 3));
-          current_range_start = x * 4 + 0;
-          break;
-        case MASH(0, 1, 1, 1, 1):
-          current_range_start = x * 4 + 0;
-          in_range = true;
-          break;
-        case MASH(1, 0, 0, 0, 0):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 0));
-          in_range = false;
-          break;
-        case MASH(1, 0, 0, 0, 1):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 0));
-          current_range_start = x * 4 + 3;
-          break;
-        case MASH(1, 0, 0, 1, 0):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 0));
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 2, x * 4 + 3));
-          current_range_start = x * 4 + 2;
-          in_range = false;
-          break;
-        case MASH(1, 0, 0, 1, 1):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 0));
-          current_range_start = x * 4 + 2;
-          break;
-        case MASH(1, 0, 1, 0, 0):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 0));
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 1, x * 4 + 2));
-          current_range_start = x * 4 + 1;
-          in_range = false;
-          break;
-        case MASH(1, 0, 1, 0, 1):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 0));
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 1, x * 4 + 2));
-          current_range_start = x * 4 + 3;
-          break;
-        case MASH(1, 0, 1, 1, 0):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 0));
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 1, x * 4 + 3));
-          current_range_start = x * 4 + 1;
-          in_range = false;
-          break;
-        case MASH(1, 0, 1, 1, 1):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 0));
-          current_range_start = x * 4 + 1;
-          break;
-        case MASH(1, 1, 0, 0, 0):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 1));
-          in_range = false;
-          break;
-        case MASH(1, 1, 0, 0, 1):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 1));
-          current_range_start = x * 4 + 3;
-          break;
-        case MASH(1, 1, 0, 1, 0):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 1));
-          current_row_ranges.emplace_back(ImageRange(x * 4 + 2, x * 4 + 3));
-          current_range_start = x * 4 + 2;
-          in_range = false;
-          break;
-        case MASH(1, 1, 0, 1, 1):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 1));
-          current_range_start = x * 4 + 2;
-          break;
-        case MASH(1, 1, 1, 0, 0):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 2));
-          in_range = false;
-          break;
-        case MASH(1, 1, 1, 0, 1):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 2));
-          current_range_start = x * 4 + 3;
-          break;
-        case MASH(1, 1, 1, 1, 0):
-          current_row_ranges.emplace_back(
-              ImageRange(current_range_start, x * 4 + 3));
-          in_range = false;
-          break;
-        case MASH(1, 1, 1, 1, 1):
-          break;
+      uint8_t chunk_channels[2 * kChunkSize];
+      memcpy(&chunk_channels[0], current_row + x * kChunkSize * 2, 2 * kChunkSize);
+
+      for (int i = 0; i < kChunkSize; ++i) {
+        if ((chunk_channels[i * 2] > value) != in_range) {
+          const int here = x * kChunkSize + i;
+          if (in_range) {
+            current_row_ranges.emplace_back(ImageRange(current_range_start, here));
+          } else {
+            current_range_start = here;
+          }
+          in_range = !in_range;
+        }
       }
     }
     if (in_range) {
@@ -227,7 +51,5 @@
   return RangeImage(0, std::move(result));
 }
 
-#undef MASH
-
 }  // namespace vision
 }  // namespace aos
diff --git a/aos/vision/image/camera_params.proto b/aos/vision/image/camera_params.proto
index c109154..947de96 100644
--- a/aos/vision/image/camera_params.proto
+++ b/aos/vision/image/camera_params.proto
@@ -10,7 +10,7 @@
   optional int32 height = 2 [default = 960];
 
   // Exposure setting.
-  optional int32 exposure = 3 [default = 10];
+  optional int32 exposure = 3 [default = 200];
 
   // Brightness setting.
   optional int32 brightness = 4 [default = 128];
diff --git a/aos/vision/tools/jpeg_vision_test.cc b/aos/vision/tools/jpeg_vision_test.cc
index 806fd80..5267041 100644
--- a/aos/vision/tools/jpeg_vision_test.cc
+++ b/aos/vision/tools/jpeg_vision_test.cc
@@ -74,7 +74,7 @@
     prev_data_ = data.to_string();
 
     // Threshold the image with the given lambda.
-    RangeImage rimg = ThresholdImageWithFunction(img_ptr, [](PixelRef &px) {
+    RangeImage rimg = ThresholdImageWithFunction(img_ptr, [](PixelRef px) {
       if (px.g > 88) {
         uint8_t min = std::min(px.b, px.r);
         uint8_t max = std::max(px.b, px.r);
diff --git a/frc971/autonomous/base_autonomous_actor.cc b/frc971/autonomous/base_autonomous_actor.cc
index ac1b3b7..ade396e 100644
--- a/frc971/autonomous/base_autonomous_actor.cc
+++ b/frc971/autonomous/base_autonomous_actor.cc
@@ -66,7 +66,7 @@
   drivetrain_message->linear = linear;
   drivetrain_message->angular = angular;
 
-  LOG_STRUCT(DEBUG, "drivetrain_goal", *drivetrain_message);
+  LOG_STRUCT(DEBUG, "dtg", *drivetrain_message);
 
   drivetrain_message.Send();
 }
@@ -349,6 +349,96 @@
   }
 }
 
+BaseAutonomousActor::SplineHandle BaseAutonomousActor::PlanSpline(
+    const ::frc971::MultiSpline &spline) {
+  LOG(INFO, "Planning spline\n");
+
+  int32_t spline_handle = (++spline_handle_) | ((getpid() & 0xFFFF) << 15);
+
+  drivetrain_queue.goal.FetchLatest();
+
+  auto drivetrain_message = drivetrain_queue.goal.MakeMessage();
+  drivetrain_message->controller_type = 2;
+
+  drivetrain_message->spline = spline;
+  drivetrain_message->spline.spline_idx = spline_handle;
+  drivetrain_message->spline_handle = goal_spline_handle_;
+
+  LOG_STRUCT(DEBUG, "dtg", *drivetrain_message);
+
+  drivetrain_message.Send();
+
+  return BaseAutonomousActor::SplineHandle(spline_handle, this);
+}
+
+bool BaseAutonomousActor::SplineHandle::IsPlanned() {
+  drivetrain_queue.status.FetchLatest();
+  LOG_STRUCT(INFO, "dts", *drivetrain_queue.status.get());
+  if (drivetrain_queue.status.get() &&
+      ((drivetrain_queue.status->trajectory_logging.planning_spline_idx ==
+            spline_handle_ &&
+        drivetrain_queue.status->trajectory_logging.planning_state == 3) ||
+       drivetrain_queue.status->trajectory_logging.current_spline_idx ==
+           spline_handle_)) {
+    return true;
+  }
+  return false;
+}
+
+bool BaseAutonomousActor::SplineHandle::WaitForPlan() {
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
+  while (true) {
+    if (base_autonomous_actor_->ShouldCancel()) {
+      return false;
+    }
+    phased_loop.SleepUntilNext();
+    if (IsPlanned()) {
+      return true;
+    }
+  }
+}
+
+void BaseAutonomousActor::SplineHandle::Start() {
+  auto drivetrain_message = drivetrain_queue.goal.MakeMessage();
+  drivetrain_message->controller_type = 2;
+
+  LOG(INFO, "Starting spline\n");
+
+  drivetrain_message->spline_handle = spline_handle_;
+  base_autonomous_actor_->goal_spline_handle_ = spline_handle_;
+
+  LOG_STRUCT(DEBUG, "dtg", *drivetrain_message);
+
+  drivetrain_message.Send();
+}
+
+bool BaseAutonomousActor::SplineHandle::IsDone() {
+  drivetrain_queue.status.FetchLatest();
+  LOG_STRUCT(INFO, "dts", *drivetrain_queue.status.get());
+
+  if (drivetrain_queue.status.get() &&
+      drivetrain_queue.status->trajectory_logging.current_spline_idx ==
+          spline_handle_) {
+    return false;
+  }
+  return true;
+}
+
+bool BaseAutonomousActor::SplineHandle::WaitForDone() {
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
+  while (true) {
+    if (base_autonomous_actor_->ShouldCancel()) {
+      return false;
+    }
+    phased_loop.SleepUntilNext();
+    if (IsDone()) {
+      return true;
+    }
+  }
+}
+
 ::std::unique_ptr<AutonomousAction> MakeAutonomousAction(
     const AutonomousActionParams &params) {
   return ::std::unique_ptr<AutonomousAction>(
diff --git a/frc971/autonomous/base_autonomous_actor.h b/frc971/autonomous/base_autonomous_actor.h
index dd53a7d..7e3ef35 100644
--- a/frc971/autonomous/base_autonomous_actor.h
+++ b/frc971/autonomous/base_autonomous_actor.h
@@ -20,6 +20,32 @@
       const control_loops::drivetrain::DrivetrainConfig<double> &dt_config);
 
  protected:
+  class SplineHandle {
+   public:
+    bool IsPlanned();
+    bool WaitForPlan();
+    void Start();
+
+    bool IsDone();
+    bool WaitForDone();
+
+    // Wait for done, wait until X from the end, wait for distance from the end
+
+   private:
+    friend BaseAutonomousActor;
+    SplineHandle(int32_t spline_handle,
+                 BaseAutonomousActor *base_autonomous_actor)
+        : spline_handle_(spline_handle),
+          base_autonomous_actor_(base_autonomous_actor) {}
+
+    int32_t spline_handle_;
+    BaseAutonomousActor *base_autonomous_actor_;
+  };
+
+  // Starts planning the spline, and returns a handle to be used to manipulate
+  // it.
+  SplineHandle PlanSpline(const ::frc971::MultiSpline &spline);
+
   void ResetDrivetrain();
   void InitializeEncoders();
   void StartDrive(double distance, double angle, ProfileParameters linear,
@@ -67,7 +93,14 @@
   }
 
  private:
+  friend class SplineHandle;
+
   double max_drivetrain_voltage_ = 12.0;
+
+  // Unique counter so we get unique spline handles.
+  int spline_handle_ = 0;
+  // Last goal spline handle;
+  int32_t goal_spline_handle_ = 0;
 };
 
 using AutonomousAction =
diff --git a/frc971/control_loops/drivetrain/BUILD b/frc971/control_loops/drivetrain/BUILD
index d3ed728..1480e4e 100644
--- a/frc971/control_loops/drivetrain/BUILD
+++ b/frc971/control_loops/drivetrain/BUILD
@@ -499,7 +499,7 @@
         "//aos/network:team_number",
         "//third_party/eigen",
         "//third_party/matplotlib-cpp",
-        "//y2016/control_loops/drivetrain:drivetrain_base",
+        "//y2019/control_loops/drivetrain:drivetrain_base",
         "@com_github_gflags_gflags//:gflags",
     ],
 )
diff --git a/frc971/control_loops/drivetrain/drivetrain.cc b/frc971/control_loops/drivetrain/drivetrain.cc
index 1b37612..6a2ea76 100644
--- a/frc971/control_loops/drivetrain/drivetrain.cc
+++ b/frc971/control_loops/drivetrain/drivetrain.cc
@@ -151,6 +151,9 @@
       case IMUType::IMU_X:
         last_accel_ = -::frc971::imu_values->accelerometer_x;
         break;
+      case IMUType::IMU_FLIPPED_X:
+        last_accel_ = ::frc971::imu_values->accelerometer_x;
+        break;
       case IMUType::IMU_Y:
         last_accel_ = -::frc971::imu_values->accelerometer_y;
         break;
@@ -239,7 +242,8 @@
     // TODO(james): Use a watcher (instead of a fetcher) once we support it in
     // simulation.
     if (localizer_control_fetcher_.Fetch()) {
-      localizer_->ResetPosition(localizer_control_fetcher_->x,
+      LOG_STRUCT(DEBUG, "localizer_control", *localizer_control_fetcher_);
+      localizer_->ResetPosition(monotonic_now, localizer_control_fetcher_->x,
                                 localizer_control_fetcher_->y,
                                 localizer_control_fetcher_->theta);
     }
@@ -257,7 +261,7 @@
     dt_closedloop_.SetGoal(*goal);
     dt_openloop_.SetGoal(*goal);
     dt_spline_.SetGoal(*goal);
-    dt_line_follow_.SetGoal(*goal);
+    dt_line_follow_.SetGoal(monotonic_now, *goal);
   }
 
   dt_openloop_.Update(robot_state().voltage_battery);
@@ -272,7 +276,7 @@
 
   dt_spline_.Update(output != NULL && controller_type == 2, trajectory_state);
 
-  dt_line_follow_.Update(trajectory_state);
+  dt_line_follow_.Update(monotonic_now, trajectory_state);
 
   switch (controller_type) {
     case 0:
diff --git a/frc971/control_loops/drivetrain/drivetrain.q b/frc971/control_loops/drivetrain/drivetrain.q
index 74be414..73ebe10 100644
--- a/frc971/control_loops/drivetrain/drivetrain.q
+++ b/frc971/control_loops/drivetrain/drivetrain.q
@@ -46,8 +46,14 @@
   // State of the spline execution.
   bool is_executing;
 
-  int32_t current_spline_handle;
+  // The handle of the goal spline.  0 means stop requested.
+  int32_t goal_spline_handle;
+  // Handle of the executing spline.  -1 means none requested.  If there was no
+  // spline executing when a spline finished optimizing, it will become the
+  // current spline even if we aren't ready to start yet.
   int32_t current_spline_idx;
+  // Handle of the spline that is being optimized and staged.
+  int32_t planning_spline_idx;
 
   // Expected position and velocity on the spline
   float x;
@@ -67,6 +73,14 @@
   float x;
   float y;
   float theta;
+  // Current lateral offset from line pointing straight out of the target.
+  float offset;
+  // Current distance from the plane of the target, in meters.
+  float distance_to_target;
+  // Current goal heading.
+  float goal_theta;
+  // Current relative heading.
+  float rel_theta;
 };
 
 queue_group DrivetrainQueue {
diff --git a/frc971/control_loops/drivetrain/drivetrain_config.h b/frc971/control_loops/drivetrain/drivetrain_config.h
index 53c2315..685516f 100644
--- a/frc971/control_loops/drivetrain/drivetrain_config.h
+++ b/frc971/control_loops/drivetrain/drivetrain_config.h
@@ -34,8 +34,9 @@
 };
 
 enum class IMUType : int32_t {
-  IMU_X = 0, // Use the x-axis of the IMU.
-  IMU_Y = 1, // Use the y-axis of the IMU.
+  IMU_X = 0,          // Use the x-axis of the IMU.
+  IMU_Y = 1,          // Use the y-axis of the IMU.
+  IMU_FLIPPED_X = 2,  // Use the flipped x-axis of the IMU.
 };
 
 template <typename Scalar = double>
diff --git a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
index b00ab3f..d4c765f 100644
--- a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
+++ b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
@@ -111,8 +111,8 @@
     double expected_x = my_drivetrain_queue_.status->trajectory_logging.x;
     double expected_y = my_drivetrain_queue_.status->trajectory_logging.y;
     auto actual = drivetrain_motor_plant_.GetPosition();
-    EXPECT_NEAR(actual(0), expected_x, 3e-3);
-    EXPECT_NEAR(actual(1), expected_y, 3e-3);
+    EXPECT_NEAR(actual(0), expected_x, 1e-2);
+    EXPECT_NEAR(actual(1), expected_y, 1e-2);
   }
 
   void WaitForTrajectoryPlan() {
@@ -744,7 +744,7 @@
   // Should have run off the end of the target, running along the y=x line.
   EXPECT_LT(1.0, drivetrain_motor_plant_.GetPosition().x());
   EXPECT_NEAR(drivetrain_motor_plant_.GetPosition().x(),
-              drivetrain_motor_plant_.GetPosition().y(), 1e-4);
+              drivetrain_motor_plant_.GetPosition().y(), 0.1);
 }
 
 // Tests that the line follower will not run and defer to regular open-loop
diff --git a/frc971/control_loops/drivetrain/hybrid_ekf.h b/frc971/control_loops/drivetrain/hybrid_ekf.h
index 119386a..42dc67a 100644
--- a/frc971/control_loops/drivetrain/hybrid_ekf.h
+++ b/frc971/control_loops/drivetrain/hybrid_ekf.h
@@ -49,8 +49,11 @@
     kLeftVelocity = 4,
     kRightEncoder = 5,
     kRightVelocity = 6,
+    kLeftVoltageError = 7,
+    kRightVoltageError = 8 ,
+    kAngularError = 9,
   };
-  static constexpr int kNStates = 7;
+  static constexpr int kNStates = 10;
   static constexpr int kNInputs = 2;
   // Number of previous samples to save.
   static constexpr int kSaveSamples = 50;
@@ -68,11 +71,19 @@
   // variable-size measurement updates.
   typedef Eigen::Matrix<Scalar, kNOutputs, 1> Output;
   typedef Eigen::Matrix<Scalar, kNStates, kNStates> StateSquare;
-  // State is [x_position, y_position, theta, left encoder, left ground vel,
-  // right encoder, right ground vel]. left/right encoder should correspond
-  // directly to encoder readings left/right velocities are the velocity of the
-  // left/right sides over the
+  // State is [x_position, y_position, theta, Kalman States], where
+  // Kalman States are the states from the standard drivetrain Kalman Filter,
+  // which is: [left encoder, left ground vel, right encoder, right ground vel,
+  // left voltage error, right voltage error, angular_error], where:
+  // left/right encoder should correspond directly to encoder readings
+  // left/right velocities are the velocity of the left/right sides over the
   //   ground (i.e., corrected for angular_error).
+  // voltage errors are the difference between commanded and effective voltage,
+  //   used to estimate consistent modelling errors (e.g., friction).
+  // angular error is the difference between the angular velocity as estimated
+  //   by the encoders vs. estimated by the gyro, such as might be caused by
+  //   wheels on one side of the drivetrain being too small or one side's
+  //   wheels slipping more than the other.
   typedef Eigen::Matrix<Scalar, kNStates, 1> State;
 
   // Constructs a HybridEkf for a particular drivetrain.
@@ -96,6 +107,7 @@
                          const State &state, const StateSquare &P) {
     observations_.clear();
     X_hat_ = state;
+    have_zeroed_encoders_ = true;
     P_ = P;
     observations_.PushFromBottom(
         {t,
@@ -140,6 +152,27 @@
                              const Scalar right_encoder, const Scalar gyro_rate,
                              const Input &U,
                              ::aos::monotonic_clock::time_point t) {
+    // Because the check below for have_zeroed_encoders_ will add an
+    // Observation, do a check here to ensure that initialization has been
+    // performed and so there is at least one observation.
+    CHECK(!observations_.empty());
+    if (!have_zeroed_encoders_) {
+      // This logic handles ensuring that on the first encoder reading, we
+      // update the internal state for the encoders to match the reading.
+      // Otherwise, if we restart the drivetrain without restarting
+      // wpilib_interface, then we can get some obnoxious initial corrections
+      // that mess up the localization.
+      State newstate = X_hat_;
+      newstate(kLeftEncoder, 0) = left_encoder;
+      newstate(kRightEncoder, 0) = right_encoder;
+      newstate(kLeftVoltageError, 0) = 0.0;
+      newstate(kRightVoltageError, 0) = 0.0;
+      newstate(kAngularError, 0) = 0.0;
+      ResetInitialState(t, newstate, P_);
+      // We need to set have_zeroed_encoders_ after ResetInitialPosition because
+      // the reset clears have_zeroed_encoders_...
+      have_zeroed_encoders_ = true;
+    }
     Output z(left_encoder, right_encoder, gyro_rate);
     Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
     R.setZero();
@@ -294,6 +327,8 @@
   Scalar encoder_noise_, gyro_noise_;
   Eigen::Matrix<Scalar, kNStates, kNInputs> B_continuous_;
 
+  bool have_zeroed_encoders_ = false;
+
   aos::PriorityQueue<Observation, kSaveSamples, ::std::less<Observation>>
       observations_;
 
@@ -396,7 +431,9 @@
 
   // Encoder derivatives
   A_continuous_(kLeftEncoder, kLeftVelocity) = 1.0;
+  A_continuous_(kLeftEncoder, kAngularError) = 1.0;
   A_continuous_(kRightEncoder, kRightVelocity) = 1.0;
+  A_continuous_(kRightEncoder, kAngularError) = -1.0;
 
   // Pull velocity derivatives from velocity matrices.
   // Note that this looks really awkward (doesn't use
@@ -413,22 +450,26 @@
   B_continuous_.setZero();
   B_continuous_.row(kLeftVelocity) = vel_coefs.B_continuous.row(0);
   B_continuous_.row(kRightVelocity) = vel_coefs.B_continuous.row(1);
+  A_continuous_.template block<kNStates, kNInputs>(0, 7) = B_continuous_;
 
   Q_continuous_.setZero();
   // TODO(james): Improve estimates of process noise--e.g., X/Y noise can
   // probably be reduced when we are stopped because you rarely jump randomly.
   // Or maybe it's more appropriate to scale wheelspeed noise with wheelspeed,
   // since the wheels aren't likely to slip much stopped.
-  Q_continuous_(kX, kX) = 0.01;
-  Q_continuous_(kY, kY) = 0.01;
+  Q_continuous_(kX, kX) = 0.002;
+  Q_continuous_(kY, kY) = 0.002;
   Q_continuous_(kTheta, kTheta) = 0.0002;
-  Q_continuous_(kLeftEncoder, kLeftEncoder) = ::std::pow(0.03, 2.0);
-  Q_continuous_(kRightEncoder, kRightEncoder) = ::std::pow(0.03, 2.0);
-  Q_continuous_(kLeftVelocity, kLeftVelocity) = ::std::pow(0.1, 2.0);
-  Q_continuous_(kRightVelocity, kRightVelocity) = ::std::pow(0.1, 2.0);
+  Q_continuous_(kLeftEncoder, kLeftEncoder) = ::std::pow(0.15, 2.0);
+  Q_continuous_(kRightEncoder, kRightEncoder) = ::std::pow(0.15, 2.0);
+  Q_continuous_(kLeftVelocity, kLeftVelocity) = ::std::pow(0.5, 2.0);
+  Q_continuous_(kRightVelocity, kRightVelocity) = ::std::pow(0.5, 2.0);
+  Q_continuous_(kLeftVoltageError, kLeftVoltageError) = ::std::pow(10.0, 2.0);
+  Q_continuous_(kRightVoltageError, kRightVoltageError) = ::std::pow(10.0, 2.0);
+  Q_continuous_(kAngularError, kAngularError) = ::std::pow(2.0, 2.0);
 
   P_.setZero();
-  P_.diagonal() << 0.1, 0.1, 0.01, 0.02, 0.01, 0.02, 0.01;
+  P_.diagonal() << 0.1, 0.1, 0.01, 0.02, 0.01, 0.02, 0.01, 1, 1, 0.03;
 
   H_encoders_and_gyro_.setZero();
   // Encoders are stored directly in the state matrix, so are a minor
@@ -441,8 +482,10 @@
 
   const Eigen::Matrix<Scalar, 4, 4> R_kf_drivetrain =
       dt_config_.make_kf_drivetrain_loop().observer().coefficients().R;
-  encoder_noise_ = R_kf_drivetrain(0, 0);
-  gyro_noise_ = R_kf_drivetrain(2, 2);
+  // TODO(james): The multipliers here are hand-waving things that I put in when
+  // tuning things. I haven't yet tried messing with these values again.
+  encoder_noise_ = 0.05 * R_kf_drivetrain(0, 0);
+  gyro_noise_ = 0.1 * R_kf_drivetrain(2, 2);
 }
 
 }  // namespace drivetrain
diff --git a/frc971/control_loops/drivetrain/hybrid_ekf_test.cc b/frc971/control_loops/drivetrain/hybrid_ekf_test.cc
index 1702ec4..80ce95c 100644
--- a/frc971/control_loops/drivetrain/hybrid_ekf_test.cc
+++ b/frc971/control_loops/drivetrain/hybrid_ekf_test.cc
@@ -52,16 +52,22 @@
     EXPECT_EQ(Xdot_ekf(StateIdx::kX, 0), ctheta * (left_vel + right_vel) / 2.0);
     EXPECT_EQ(Xdot_ekf(StateIdx::kY, 0), stheta * (left_vel + right_vel) / 2.0);
     EXPECT_EQ(Xdot_ekf(StateIdx::kTheta, 0), (right_vel - left_vel) / diameter);
-    EXPECT_EQ(Xdot_ekf(StateIdx::kLeftEncoder, 0), left_vel);
-    EXPECT_EQ(Xdot_ekf(StateIdx::kRightEncoder, 0), right_vel);
+    EXPECT_EQ(Xdot_ekf(StateIdx::kLeftEncoder, 0),
+              left_vel + X(StateIdx::kAngularError, 0));
+    EXPECT_EQ(Xdot_ekf(StateIdx::kRightEncoder, 0),
+              right_vel - X(StateIdx::kAngularError, 0));
 
     Eigen::Matrix<double, 2, 1> vel_x(X(StateIdx::kLeftVelocity, 0),
                                       X(StateIdx::kRightVelocity, 0));
     Eigen::Matrix<double, 2, 1> expected_vel_X =
         velocity_plant_coefs_.A_continuous * vel_x +
-        velocity_plant_coefs_.B_continuous * U;
+        velocity_plant_coefs_.B_continuous *
+            (U + X.middleRows<2>(StateIdx::kLeftVoltageError));
     EXPECT_EQ(Xdot_ekf(StateIdx::kLeftVelocity, 0), expected_vel_X(0, 0));
     EXPECT_EQ(Xdot_ekf(StateIdx::kRightVelocity, 0), expected_vel_X(1, 0));
+
+    // Dynamics don't expect error terms to change:
+    EXPECT_EQ(0.0, Xdot_ekf.bottomRows<3>().squaredNorm());
   }
   State DiffEq(const State &X, const Input &U) {
     return ekf_.DiffEq(X, U);
@@ -87,14 +93,18 @@
   CheckDiffEq(State::Zero(), Input::Zero());
   CheckDiffEq(State::Zero(), {-5.0, 5.0});
   CheckDiffEq(State::Zero(), {12.0, -3.0});
-  CheckDiffEq((State() << 100.0, 200.0, M_PI, 1.234, 0.5, 1.2, 0.6).finished(),
+  CheckDiffEq((State() << 100.0, 200.0, M_PI, 1.234, 0.5, 1.2, 0.6, 3.0, -4.0,
+               0.3).finished(),
               {5.0, 6.0});
-  CheckDiffEq((State() << 100.0, 200.0, 2.0, 1.234, 0.5, 1.2, 0.6).finished(),
+  CheckDiffEq((State() << 100.0, 200.0, 2.0, 1.234, 0.5, 1.2, 0.6, 3.0, -4.0,
+               0.3).finished(),
               {5.0, 6.0});
-  CheckDiffEq((State() << 100.0, 200.0, -2.0, 1.234, 0.5, 1.2, 0.6).finished(),
+  CheckDiffEq((State() << 100.0, 200.0, -2.0, 1.234, 0.5, 1.2, 0.6, 3.0, -4.0,
+               0.3).finished(),
               {5.0, 6.0});
   // And check that a theta outisde of [-M_PI, M_PI] works.
-  CheckDiffEq((State() << 100.0, 200.0, 200.0, 1.234, 0.5, 1.2, 0.6).finished(),
+  CheckDiffEq((State() << 100.0, 200.0, 200.0, 1.234, 0.5, 1.2, 0.6, 3.0, -4.0,
+               0.3).finished(),
               {5.0, 6.0});
 }
 
@@ -102,7 +112,7 @@
 // with zero change in time, the state should approach the estimation.
 TEST_F(HybridEkfTest, ZeroTimeCorrect) {
   HybridEkf<>::Output Z(0.5, 0.5, 1);
-  Eigen::Matrix<double, 3, 7> H;
+  Eigen::Matrix<double, 3, 10> H;
   H.setIdentity();
   auto h = [H](const State &X, const Input &) { return H * X; };
   auto dhdx = [H](const State &) { return H; };
@@ -130,7 +140,7 @@
   HybridEkf<>::Output Z(0, 0, 0);
   // Use true_X to track what we think the true robot state is.
   State true_X = ekf_.X_hat();
-  Eigen::Matrix<double, 3, 7> H;
+  Eigen::Matrix<double, 3, 10> H;
   H.setZero();
   auto h = [H](const State &X, const Input &) { return H * X; };
   auto dhdx = [H](const State &) { return H; };
@@ -161,6 +171,9 @@
   EXPECT_NEAR(ekf_.X_hat(StateIdx::kLeftVelocity) * 0.8,
               ekf_.X_hat(StateIdx::kRightVelocity),
               ekf_.X_hat(StateIdx::kLeftVelocity) * 0.1);
+  EXPECT_EQ(0.0, ekf_.X_hat(StateIdx::kLeftVoltageError));
+  EXPECT_EQ(0.0, ekf_.X_hat(StateIdx::kRightVoltageError));
+  EXPECT_EQ(0.0, ekf_.X_hat(StateIdx::kAngularError));
   const double ending_p_norm = ekf_.P().norm();
   // Due to lack of corrections, noise should've increased.
   EXPECT_GT(ending_p_norm, starting_p_norm * 1.10);
@@ -180,7 +193,7 @@
 TEST_P(HybridEkfOldCorrectionsTest, CreateOldCorrection) {
   HybridEkf<>::Output Z;
   Z.setZero();
-  Eigen::Matrix<double, 3, 7> H;
+  Eigen::Matrix<double, 3, 10> H;
   H.setZero();
   auto h_zero = [H](const State &X, const Input &) { return H * X; };
   auto dhdx_zero = [H](const State &) { return H; };
@@ -218,7 +231,7 @@
   expected_X_hat(0, 0) = Z(0, 0);
   expected_X_hat(1, 0) = Z(1, 0) + modeled_X_hat(0, 0);
   expected_X_hat(2, 0) = Z(2, 0);
-  EXPECT_LT((expected_X_hat - ekf_.X_hat()).norm(),
+  EXPECT_LT((expected_X_hat.topRows<7>() - ekf_.X_hat().topRows<7>()).norm(),
            1e-3)
       << "X_hat: " << ekf_.X_hat() << " expected " << expected_X_hat;
   // The covariance after the predictions but before the corrections should
@@ -236,7 +249,7 @@
 TEST_F(HybridEkfTest, DiscardTooOldCorrection) {
   HybridEkf<>::Output Z;
   Z.setZero();
-  Eigen::Matrix<double, 3, 7> H;
+  Eigen::Matrix<double, 3, 10> H;
   H.setZero();
   auto h_zero = [H](const State &X, const Input &) { return H * X; };
   auto dhdx_zero = [H](const State &) { return H; };
@@ -291,11 +304,11 @@
 }
 
 // Tests that encoder updates cause everything to converge properly in the
-// presence of an initial velocity error.
+// presence of voltage error.
 TEST_F(HybridEkfTest, PerfectEncoderUpdatesWithVoltageError) {
   State true_X = ekf_.X_hat();
-  true_X(StateIdx::kLeftVelocity, 0) = 0.2;
-  true_X(StateIdx::kRightVelocity, 0) = 0.2;
+  true_X(StateIdx::kLeftVoltageError, 0) = 2.0;
+  true_X(StateIdx::kRightVoltageError, 0) = 2.0;
   Input U(5.0, 5.0);
   for (int ii = 0; ii < 1000; ++ii) {
     true_X = Update(true_X, U);
@@ -306,7 +319,7 @@
                                    dt_config_.robot_radius / 2.0,
                                U, t0_ + (ii + 1) * dt_config_.dt);
   }
-  EXPECT_NEAR((true_X - ekf_.X_hat()).norm(), 0.0, 5e-3)
+  EXPECT_NEAR((true_X - ekf_.X_hat()).norm(), 0.0, 5e-2)
       << "Expected non-x/y estimates to converge to correct. "
          "Estimated X_hat:\n"
       << ekf_.X_hat() << "\ntrue X:\n"
@@ -315,11 +328,11 @@
 
 // Tests encoder/gyro updates when we have some errors in our estimate.
 TEST_F(HybridEkfTest, PerfectEncoderUpdateConverges) {
-  // In order to simulate modelling errors, we start the encoder values slightly
-  // off.
+  // In order to simulate modelling errors, we add an angular_error and start
+  // the encoder values slightly off.
   State true_X = ekf_.X_hat();
+  true_X(StateIdx::kAngularError, 0) = 1.0;
   true_X(StateIdx::kLeftEncoder, 0) += 2.0;
-  true_X(StateIdx::kLeftVelocity, 0) = 0.1;
   true_X(StateIdx::kRightEncoder, 0) -= 2.0;
   // After enough time, everything should converge to near-perfect (if there
   // were any errors in the original absolute state (x/y/theta) state, then we
@@ -337,7 +350,7 @@
                                    dt_config_.robot_radius / 2.0,
                                U, t0_ + (ii + 1) * dt_config_.dt);
   }
-  EXPECT_NEAR((true_X - ekf_.X_hat()).norm(), 0.0, 1e-4)
+  EXPECT_NEAR((true_X - ekf_.X_hat()).norm(), 0.0, 3e-5)
       << "Expected non-x/y estimates to converge to correct. "
          "Estimated X_hat:\n"
       << ekf_.X_hat() << "\ntrue X:\n"
@@ -346,11 +359,11 @@
 
 // Tests encoder/gyro updates in a realistic-ish scenario with noise:
 TEST_F(HybridEkfTest, RealisticEncoderUpdateConverges) {
-  // In order to simulate modelling errors, we start the encoder values slightly
-  // off.
+  // In order to simulate modelling errors, we add an angular_error and start
+  // the encoder values slightly off.
   State true_X = ekf_.X_hat();
+  true_X(StateIdx::kAngularError, 0) = 1.0;
   true_X(StateIdx::kLeftEncoder, 0) += 2.0;
-  true_X(StateIdx::kLeftVelocity, 0) = 0.1;
   true_X(StateIdx::kRightEncoder, 0) -= 2.0;
   Input U(10.0, 5.0);
   for (int ii = 0; ii < 100; ++ii) {
@@ -364,7 +377,7 @@
         U, t0_ + (ii + 1) * dt_config_.dt);
   }
   EXPECT_NEAR(
-      (true_X.bottomRows<6>() - ekf_.X_hat().bottomRows<6>()).squaredNorm(),
+      (true_X.bottomRows<9>() - ekf_.X_hat().bottomRows<9>()).squaredNorm(),
       0.0, 2e-3)
       << "Expected non-x/y estimates to converge to correct. "
          "Estimated X_hat:\n" << ekf_.X_hat() << "\ntrue X:\n" << true_X;
@@ -398,7 +411,7 @@
   // Check that we die when only one of h and dhdx are provided:
   EXPECT_DEATH(ekf_.Correct({1, 2, 3}, &U, {}, {},
                             [](const State &) {
-                              return Eigen::Matrix<double, 3, 7>::Zero();
+                              return Eigen::Matrix<double, 3, 10>::Zero();
                             },
                             {}, t0_ + ::std::chrono::seconds(1)),
                "make_h");
diff --git a/frc971/control_loops/drivetrain/line_follow_drivetrain.cc b/frc971/control_loops/drivetrain/line_follow_drivetrain.cc
index b5417af..4c51569 100644
--- a/frc971/control_loops/drivetrain/line_follow_drivetrain.cc
+++ b/frc971/control_loops/drivetrain/line_follow_drivetrain.cc
@@ -1,7 +1,9 @@
-#include <iostream>
 #include "frc971/control_loops/drivetrain/line_follow_drivetrain.h"
 
+#include <chrono>
+
 #include "aos/commonmath.h"
+#include "aos/time/time.h"
 #include "aos/util/math.h"
 #include "frc971/control_loops/c2d.h"
 #include "frc971/control_loops/dlqr.h"
@@ -9,9 +11,11 @@
 namespace frc971 {
 namespace control_loops {
 namespace drivetrain {
+namespace {
+namespace chrono = ::std::chrono;
+}  // namespace
 
 constexpr double LineFollowDrivetrain::kMaxVoltage;
-constexpr double LineFollowDrivetrain::kPolyN;
 
 namespace {
 ::Eigen::Matrix<double, 3, 3> AContinuous(
@@ -99,71 +103,34 @@
       target_selector_(target_selector),
       U_(0, 0) {}
 
-double LineFollowDrivetrain::GoalTheta(
-    const ::Eigen::Matrix<double, 5, 1> &state) const {
-  // TODO(james): Consider latching the sign of the goal so that the driver
-  // can back up without the robot trying to turn around...
-  // On the other hand, we may just want to force the driver to take over
-  // entirely if they need to backup.
-  int sign = ::aos::sign(goal_velocity_);
-  // Given a Nth degree polynomial with just a single term that
-  // has its minimum (with a slope of zero) at (0, 0) and passing
-  // through (x0, y0), we will have:
-  // y = a * x^N
-  // a = y0 / x0^N
-  // And the slope of the tangent line at (x0, y0) will be
-  // N * a * x0^(N-1)
-  // = N * y0 / x0^N * x0^(N-1)
-  // = N * y0 / x0
-  // Giving a heading of
-  // atan2(-N * y0, -x0)
-  // where we add the negative signs to make things work out properly when we
-  // are trying to drive forwards towards zero. We reverse the sign of both
-  // terms if we want to drive backwards.
-  return ::std::atan2(-sign * kPolyN * state.y(), -sign * state.x());
-}
-
-double LineFollowDrivetrain::GoalThetaDot(
-    const ::Eigen::Matrix<double, 5, 1> &state) const {
-  // theta = atan2(-N * y0, -x0)
-  // Note: d(atan2(p(t), q(t)))/dt
-  //       = (p(t) * q'(t) - q(t) * p'(t)) / (p(t)^2 + q(t)^2)
-  // Note: x0' = cos(theta) * v, y0' = sin(theta) * v
-  // Note that for the sin/cos calculations we discard the
-  //   negatives in the arctangent to make the signs work out (the
-  //   dtheta/dt needs to be correct as we travel along the path). This
-  //   also corresponds with the fact that thetadot is agnostic towards
-  //   whether the robot is driving forwards or backwards, so long as it is
-  //   trying to drive towards the target.
-  // Note: sin(theta) = sin(atan2(N * y0, x0))
-  //       = N * y0 / sqrt(N^2 * y0^2 + x0^2)
-  // Note: cos(theta) = cos(atan2(N * y0, x0))
-  //       = x0 / sqrt(N^2 * y0^2 + x0^2)
-  // dtheta/dt
-  // = (-x0 * (-N * y0') - -N * y0 * (-x0')) / (N^2 * y0^2 + x0^2)
-  // = N * (x0 * v * sin(theta) - y0 * v * cos(theta)) / (N^2 * y0^2 + x0^2)
-  // = N * v * (x0 * (N * y0) - y0 * (x0)) / (N^2 * y0^2 + x0^2)^1.5
-  // = N * v * (N - 1) * x0 * y0 / (N^2 * y0^2 + x0^2)^1.5
-  const double linear_vel = (state(3, 0) + state(4, 0)) / 2.0;
-  const double x2 = ::std::pow(state.x(), 2);
-  const double y2 = ::std::pow(state.y(), 2);
-  const double norm = y2 * kPolyN * kPolyN + x2;
-  // When we get too near the goal, avoid singularity in a sane manner.
-  if (norm < 1e-3) {
-    return 0.0;
-  }
-  return kPolyN * (kPolyN - 1) * linear_vel * state.x() * state.y() /
-         (norm * ::std::sqrt(norm));
-}
-
 void LineFollowDrivetrain::SetGoal(
+    ::aos::monotonic_clock::time_point now,
     const ::frc971::control_loops::DrivetrainQueue::Goal &goal) {
   // TODO(james): More properly calculate goal velocity from throttle.
-  goal_velocity_ = goal.throttle;
+  goal_velocity_ = 4.0 * goal.throttle;
+  // The amount of time to freeze the target choice after the driver releases
+  // the button. Depending on the current state, we vary how long this timeout
+  // is so that we can avoid button glitches causing issues.
+  chrono::nanoseconds freeze_delay = chrono::seconds(0);
   // Freeze the target once the driver presses the button; if we haven't yet
   // confirmed a target when the driver presses the button, we will not do
   // anything and report not ready until we have a target.
-  freeze_target_ = goal.controller_type == 3;
+  if (goal.controller_type == 3) {
+    last_enable_ = now;
+    // If we already acquired a target, we want to keep track if it.
+    if (have_target_) {
+      freeze_delay = chrono::milliseconds(500);
+      // If we've had the target acquired for a while, the driver is probably
+      // happy with the current target selection, so we really want to keep it.
+      if (now > chrono::milliseconds(1000) + start_of_target_acquire_) {
+        freeze_delay = chrono::milliseconds(2000);
+      }
+    }
+  }
+  freeze_target_ = now <= freeze_delay + last_enable_;
+  // Set an adjustment that lets the driver tweak the offset for where we place
+  // the target left/right.
+  side_adjust_ = -goal.wheel * 0.1;
 }
 
 bool LineFollowDrivetrain::SetOutput(
@@ -177,7 +144,48 @@
   return have_target_;
 }
 
+double LineFollowDrivetrain::GoalTheta(
+    const ::Eigen::Matrix<double, 5, 1> &abs_state, double relative_y_offset,
+    double velocity_sign) {
+  // Calculates the goal angle for the drivetrain given our position.
+  // The calculated goal will be such that a point disc_rad to one side of the
+  // drivetrain (the side depends on where we approach from) will end up hitting
+  // the plane of the target exactly disc_rad from the center of the target.
+  // This allows us to better approach targets in the 2019 game from an
+  // angle--radii of zero imply driving straight in.
+  const double disc_rad = target_selector_->TargetRadius();
+  // Depending on whether we are to the right or left of the target, we work off
+  // of a different side of the robot.
+  const double edge_sign = relative_y_offset > 0 ? 1.0 : -1.0;
+  // Note side_adjust which is the input from the driver's wheel to allow
+  // shifting the goal target left/right.
+  const double edge_offset = edge_sign * disc_rad - side_adjust_;
+  // The point that we are trying to get the disc to hit.
+  const Pose corner = Pose(&target_pose_, {0.0, edge_offset, 0.0}, 0.0);
+  // A pose for the current robot position that is square to the target.
+  Pose square_robot =
+      Pose({abs_state.x(), abs_state.y(), 0.0}, 0.0).Rebase(&corner);
+  // To prevent numerical issues, we limit x so that when the localizer isn't
+  // working properly and ends up driving past the target, we still get sane
+  // results.
+  square_robot.mutable_pos()->x() =
+      ::std::min(::std::min(square_robot.mutable_pos()->x(), -disc_rad), -0.01);
+  // Distance from the edge of the disc on the robot to the velcro we want to
+  // hit on the target.
+  const double dist_to_corner = square_robot.xy_norm();
+  // The following actually handles calculating the heading we need the robot to
+  // take (relative to the plane of the target).
+  const double alpha = ::std::acos(disc_rad / dist_to_corner);
+  const double heading_to_robot = edge_sign * square_robot.heading();
+  double theta = -edge_sign * (M_PI - alpha - (heading_to_robot - M_PI_2));
+  if (velocity_sign < 0) {
+    theta = ::aos::math::NormalizeAngle(theta + M_PI);
+  }
+  return theta;
+}
+
 void LineFollowDrivetrain::Update(
+    ::aos::monotonic_clock::time_point now,
     const ::Eigen::Matrix<double, 5, 1> &abs_state) {
   // Because we assume the target selector may have some internal state (e.g.,
   // not confirming a target until some time as passed), we should call
@@ -189,6 +197,8 @@
     // target before.
     if (!have_target_ && new_target) {
       have_target_ = true;
+      start_of_target_acquire_ = now;
+      velocity_sign_ = goal_velocity_ >= 0.0 ? 1.0 : -1.0;
       target_pose_ = target_selector_->TargetPose();
     }
   } else {
@@ -197,12 +207,15 @@
     have_target_ = new_target;
     if (have_target_) {
       target_pose_ = target_selector_->TargetPose();
+      velocity_sign_ = goal_velocity_ >= 0.0 ? 1.0 : -1.0;
     }
   }
-
   // Get the robot pose in the target coordinate frame.
-  const Pose relative_robot_pose = Pose({abs_state.x(), abs_state.y(), 0.0},
-                                        abs_state(2, 0)).Rebase(&target_pose_);
+  relative_pose_ = Pose({abs_state.x(), abs_state.y(), 0.0}, abs_state(2, 0))
+                       .Rebase(&target_pose_);
+  double goal_theta =
+      GoalTheta(abs_state, relative_pose_.rel_pos().y(), velocity_sign_);
+
   // Always force a slight negative X, so that the driver can continue to drive
   // past zero if they want.
   // The "slight negative" needs to be large enough that we won't force
@@ -210,28 +223,38 @@
   // line--because, in practice, the driver should never be trying to drive to a
   // target where they are significantly off laterally at <0.1m from the target,
   // this should not be a problem.
-  const double relative_x = ::std::min(relative_robot_pose.rel_pos().x(), -0.1);
+  const double relative_x = ::std::min(relative_pose_.rel_pos().x(), -0.1);
   const ::Eigen::Matrix<double, 5, 1> rel_state =
       (::Eigen::Matrix<double, 5, 1>() << relative_x,
-       relative_robot_pose.rel_pos().y(), relative_robot_pose.rel_theta(),
-       abs_state(3, 0), abs_state(4, 0))
-          .finished();
-  ::Eigen::Matrix<double, 3, 1> controls_goal(
-      GoalTheta(rel_state), goal_velocity_, GoalThetaDot(rel_state));
+       relative_pose_.rel_pos().y(), relative_pose_.rel_theta(),
+       abs_state(3, 0), abs_state(4, 0)).finished();
+  if (velocity_sign_ * goal_velocity_ < 0)  {
+    goal_theta = rel_state(2, 0);
+  }
+  controls_goal_ << goal_theta, goal_velocity_, 0.0;
   ::Eigen::Matrix<double, 3, 1> controls_state;
   controls_state(0, 0) = rel_state(2, 0);
   controls_state.block<2, 1>(1, 0) =
       dt_config_.Tlr_to_la() * rel_state.block<2, 1>(3, 0);
-  ::Eigen::Matrix<double, 3, 1> controls_err = controls_goal - controls_state;
+  ::Eigen::Matrix<double, 3, 1> controls_err = controls_goal_ - controls_state;
   // Because we are taking the difference of an angle, normaliez to [-pi, pi].
   controls_err(0, 0) = ::aos::math::NormalizeAngle(controls_err(0, 0));
   // TODO(james): Calculate the next goal so that we are properly doing
   // feed-forwards.
   ::Eigen::Matrix<double, 2, 1> U_ff =
-      Kff_ * (controls_goal - A_d_ * controls_goal);
+      Kff_ * (controls_goal_ - A_d_ * controls_goal_);
   U_ = K_ * controls_err + U_ff;
-  const double maxU = U_.lpNorm<::Eigen::Infinity>();
-  U_ *= (maxU > kMaxVoltage) ? kMaxVoltage / maxU : 1.0;
+  const double maxU = ::std::max(U_(0, 0), U_(1, 0));
+  const double minU = ::std::min(U_(0, 0), U_(1, 0));
+  const double diffU = ::std::abs(U_(1, 0) - U_(0, 0));
+  const double maxAbsU = ::std::max(maxU, -minU);
+  if (diffU > 24.0) {
+    U_ *= (maxAbsU > kMaxVoltage) ? kMaxVoltage / maxAbsU : 1.0;
+  } else if (maxU > 12.0) {
+    U_ = U_ + U_.Ones() * (12.0 - maxU);
+  } else if (minU < -12.0) {
+    U_ = U_ - U_.Ones() * (minU + 12.0);
+  }
 }
 
 void LineFollowDrivetrain::PopulateStatus(
@@ -241,6 +264,11 @@
   status->line_follow_logging.x = target_pose_.abs_pos().x();
   status->line_follow_logging.y = target_pose_.abs_pos().y();
   status->line_follow_logging.theta = target_pose_.abs_theta();
+  status->line_follow_logging.offset = relative_pose_.rel_pos().y();
+  status->line_follow_logging.distance_to_target =
+      -relative_pose_.rel_pos().x();
+  status->line_follow_logging.goal_theta = controls_goal_(0, 0);
+  status->line_follow_logging.rel_theta = relative_pose_.rel_theta();
 }
 
 }  // namespace drivetrain
diff --git a/frc971/control_loops/drivetrain/line_follow_drivetrain.h b/frc971/control_loops/drivetrain/line_follow_drivetrain.h
index de9ff5a..09b2080 100644
--- a/frc971/control_loops/drivetrain/line_follow_drivetrain.h
+++ b/frc971/control_loops/drivetrain/line_follow_drivetrain.h
@@ -17,25 +17,22 @@
 
 // A drivetrain that permits a velocity input from the driver while controlling
 // lateral motion.
-// TODO(james): Do we want to allow some driver input on lateral control? It may
-// just be too confusing to make work effectively, but it also wouldn't be too
-// hard to just allow the driver to specify an offset to the angle/angular
-// velocity.
 class LineFollowDrivetrain {
  public:
   typedef TypedPose<double> Pose;
 
-  LineFollowDrivetrain(
-      const DrivetrainConfig<double> &dt_config,
-      TargetSelectorInterface *target_selector);
+  LineFollowDrivetrain(const DrivetrainConfig<double> &dt_config,
+                       TargetSelectorInterface *target_selector);
   // Sets the current goal; the drivetrain queue contains throttle_velocity
   // which is used to command overall robot velocity. The goal_pose is a Pose
-  // representing where we are tring to go. This would typically be the Pose of
+  // representing where we are trying to go. This would typically be the Pose of
   // a Target; the positive X-axis in the Pose's frame represents the direction
   // we want to go (we approach the pose from the left-half plane).
-  void SetGoal(const ::frc971::control_loops::DrivetrainQueue::Goal &goal);
+  void SetGoal(::aos::monotonic_clock::time_point now,
+               const ::frc971::control_loops::DrivetrainQueue::Goal &goal);
   // State: [x, y, theta, left_vel, right_vel]
-  void Update(const ::Eigen::Matrix<double, 5, 1> &state);
+  void Update(::aos::monotonic_clock::time_point now,
+              const ::Eigen::Matrix<double, 5, 1> &state);
   // Returns whether we set the output. If false, that implies that we do not
   // yet have a target to track into and so some other drivetrain should take
   // over.
@@ -48,24 +45,18 @@
   // Nominal max voltage.
   // TODO(james): Is there a config for this or anything?
   static constexpr double kMaxVoltage = 12.0;
-  // Degree of the polynomial to follow in. Should be strictly greater than 1.
-  // A value of 1 would imply that we drive straight to the target (but not hit
-  // it straight on, unless we happened to start right in front of it). A value
-  // of zero would imply driving straight until we hit the plane of the target.
-  // Values between 0 and 1 would imply hitting the target from the side.
-  static constexpr double kPolyN = 3.0;
-  static_assert(kPolyN > 1.0,
-                "We want to hit targets straight on (see above comments).");
 
-  double GoalTheta(const ::Eigen::Matrix<double, 5, 1> &state) const;
-  double GoalThetaDot(const ::Eigen::Matrix<double, 5, 1> &state) const;
+  double GoalTheta(const ::Eigen::Matrix<double, 5, 1> &abs_state,
+                   double relative_y_offset, double velocity_sign);
 
   const DrivetrainConfig<double> dt_config_;
   // TODO(james): These should probably be factored out somewhere.
+  // TODO(james): This controller is not actually asymptotically stable, due to
+  // the varying goal theta.
   const ::Eigen::DiagonalMatrix<double, 3> Q_ =
       (::Eigen::DiagonalMatrix<double, 3>().diagonal()
-           << 1.0 / ::std::pow(0.01, 2),
-       1.0 / ::std::pow(0.1, 2), 1.0 / ::std::pow(10.0, 2))
+           << 1.0 / ::std::pow(0.1, 2),
+       1.0 / ::std::pow(1.0, 2), 1.0 / ::std::pow(1.0, 2))
           .finished()
           .asDiagonal();
   const ::Eigen::DiagonalMatrix<double, 2> R_ =
@@ -86,6 +77,20 @@
   bool have_target_ = false;
   Pose target_pose_;
   double goal_velocity_ = 0.0;
+  // The amount to shift the center of the goal target side-to-side, to give the
+  // driver an input that lets them account for panels that are offset on the
+  // grabber.
+  double side_adjust_ = 0.0;  // meters
+  double velocity_sign_ = 1.0;
+
+  // The last time at which we saw an enable button.
+  ::aos::monotonic_clock::time_point last_enable_;
+  // The time at which we first acquired the current target.
+  ::aos::monotonic_clock::time_point start_of_target_acquire_;
+  // Most recent relative pose to target, used for debugging.
+  Pose relative_pose_;
+  // Current goal state, used for debugging.
+  ::Eigen::Matrix<double, 3, 1> controls_goal_;
 
   // Voltage output to apply
   ::Eigen::Matrix<double, 2, 1> U_;
diff --git a/frc971/control_loops/drivetrain/line_follow_drivetrain_test.cc b/frc971/control_loops/drivetrain/line_follow_drivetrain_test.cc
index 65cf9bf..414ec81 100644
--- a/frc971/control_loops/drivetrain/line_follow_drivetrain_test.cc
+++ b/frc971/control_loops/drivetrain/line_follow_drivetrain_test.cc
@@ -53,8 +53,8 @@
     ::frc971::control_loops::DrivetrainQueue::Goal goal;
     goal.throttle = driver_model_(state_);
     goal.controller_type = freeze_target_ ? 3 : 0;
-    drivetrain_.SetGoal(goal);
-    drivetrain_.Update(state_);
+    drivetrain_.SetGoal(t_, goal);
+    drivetrain_.Update(t_, state_);
 
     ::frc971::control_loops::DrivetrainQueue::Output output;
     EXPECT_EQ(expect_output_, drivetrain_.SetOutput(&output));
@@ -85,51 +85,26 @@
     simulation_ur_.push_back(U(1, 0));
     simulation_x_.push_back(state_.x());
     simulation_y_.push_back(state_.y());
+    simulation_theta_.push_back(state_(3, 0));
   }
 
   // Check that left/right velocities are near zero and the absolute position is
   // near that of the goal Pose.
   void VerifyNearGoal() const {
-    EXPECT_NEAR(goal_pose().abs_pos().x(), state_(0, 0), 1e-3);
-    EXPECT_NEAR(goal_pose().abs_pos().y(), state_(1, 0), 1e-3);
-    // state should be at 0 or PI (we should've come in striaght on or straight
-    // backwards).
-    const double angle_err =
-        ::aos::math::DiffAngle(goal_pose().abs_theta(), state_(2, 0));
-    const double angle_pi_err = ::aos::math::DiffAngle(angle_err, M_PI);
-    EXPECT_LT(::std::min(::std::abs(angle_err), ::std::abs(angle_pi_err)),
-              1e-3);
+    EXPECT_NEAR(goal_pose().abs_pos().x(), state_(0, 0), 1e-2);
+    EXPECT_NEAR(goal_pose().abs_pos().y(), state_(1, 0), 1e-2);
     // Left/right velocities are zero:
-    EXPECT_NEAR(0.0, state_(3, 0), 1e-3);
-    EXPECT_NEAR(0.0, state_(4, 0), 1e-3);
+    EXPECT_NEAR(0.0, state_(3, 0), 1e-2);
+    EXPECT_NEAR(0.0, state_(4, 0), 1e-2);
   }
 
-  void CheckGoalTheta(double x, double y, double v, double expected_theta,
-                          double expected_thetadot) {
+  double GoalTheta(double x, double y, double v, double throttle) {
+    ::frc971::control_loops::DrivetrainQueue::Goal goal;
+    goal.throttle = throttle;
+    drivetrain_.SetGoal(t_, goal);
     ::Eigen::Matrix<double, 5, 1> state;
     state << x, y, 0.0, v, v;
-    const double theta = drivetrain_.GoalTheta(state);
-    const double thetadot = drivetrain_.GoalThetaDot(state);
-    EXPECT_EQ(expected_theta, theta) << "x " << x << " y " << y << " v " << v;
-    EXPECT_EQ(expected_thetadot, thetadot)
-        << "x " << x << " y " << y << " v " << v;
-  }
-
-  void CheckGoalThetaDotAtState(double x, double y, double v) {
-    ::Eigen::Matrix<double, 5, 1> state;
-    state << x, y, 0.0, v, v;
-    const double theta = drivetrain_.GoalTheta(state);
-    const double thetadot = drivetrain_.GoalThetaDot(state);
-    const double dx = v * ::std::cos(theta);
-    const double dy = v * ::std::sin(theta);
-    constexpr double kEps = 1e-5;
-    state(0, 0) += dx * kEps;
-    state(1, 0) += dy * kEps;
-    const double next_theta = drivetrain_.GoalTheta(state);
-    EXPECT_NEAR(thetadot, ::aos::math::DiffAngle(next_theta, theta) / kEps,
-                1e-4)
-        << "theta: " << theta << " nexttheta: " << next_theta << " x " << x
-        << " y " << y << " v " << v;
+    return drivetrain_.GoalTheta(state, y, throttle > 0.0 ? 1.0 : -1.0);
   }
 
   void TearDown() override {
@@ -137,6 +112,7 @@
       matplotlibcpp::figure();
       matplotlibcpp::plot(time_, simulation_ul_, {{"label", "ul"}});
       matplotlibcpp::plot(time_, simulation_ur_, {{"label", "ur"}});
+      matplotlibcpp::plot(time_, simulation_theta_, {{"label", "theta"}});
       matplotlibcpp::legend();
 
       TypedPose<double> target = goal_pose();
@@ -194,18 +170,33 @@
   ::std::vector<double> simulation_ur_;
   ::std::vector<double> simulation_x_;
   ::std::vector<double> simulation_y_;
+  ::std::vector<double> simulation_theta_;
 };
 
-TEST_F(LineFollowDrivetrainTest, ValidGoalThetaDot) {
+TEST_F(LineFollowDrivetrainTest, BasicGoalThetaCheck) {
   for (double x : {1.0, 0.0, -1.0, -2.0, -3.0}) {
     for (double y : {-3.0, -2.0, -1.0, 0.0, 1.0, 2.0, 3.0}) {
       for (double v : {-3.0, -2.0, -1.0, 0.0, 1.0, 2.0, 3.0}) {
-        if (x == 0.0 && y == 0.0) {
-          // When x/y are zero, we can encounter singularities. The code should
-          // just provide zeros in this case.
-          CheckGoalTheta(x, y, v, 0.0, 0.0);
-        } else {
-          CheckGoalThetaDotAtState(x, y, v);
+        for (double throttle : {-1.0, 1.0}) {
+          target_selector_.set_target_radius(0.0);
+          const double zero_rad_theta = GoalTheta(x, y, v, throttle);
+          EXPECT_NEAR(
+              0.0,
+              ::aos::math::DiffAngle((throttle > 0.0 ? M_PI : 0.0) +
+                                         ::std::atan2(y, ::std::min(-0.01, x)),
+                                     zero_rad_theta),
+              1e-14);
+          target_selector_.set_target_radius(0.05);
+          const double small_rad_theta = GoalTheta(x, y, v, throttle);
+          if (y > 0) {
+            EXPECT_LT(small_rad_theta, zero_rad_theta);
+          } else if (y == 0) {
+            EXPECT_NEAR(0.0,
+                        ::aos::math::DiffAngle(small_rad_theta, zero_rad_theta),
+                        1e-14);
+          } else {
+            EXPECT_GT(small_rad_theta, zero_rad_theta);
+          }
         }
       }
     }
@@ -215,8 +206,12 @@
 // If the driver commands the robot to keep going, we should just run straight
 // off the end and keep going along the line:
 TEST_F(LineFollowDrivetrainTest, RunOffEnd) {
-  state_ << -1.0, 0.1, 0.0, 0.0, 0.0;
-  driver_model_ = [](const ::Eigen::Matrix<double, 5, 1> &) { return 1.0; };
+  freeze_target_ = true;
+  state_ << -1.0, 0.0, 0.0, 0.0, 0.0;
+  // TODO(james): This test currently relies on the scalar on the throttle to
+  // velocity conversion being 4.0. This should probably be moved out into a
+  // config.
+  driver_model_ = [](const ::Eigen::Matrix<double, 5, 1> &) { return 0.25; };
   RunForTime(chrono::seconds(10));
   EXPECT_LT(6.0, state_.x());
   EXPECT_NEAR(0.0, state_.y(), 1e-4);
@@ -250,7 +245,8 @@
   set_goal_pose({{1.0, 1.0, 0.0}, M_PI_2});
 
   RunForTime(::std::chrono::seconds(5));
-  EXPECT_NEAR(0.0, state_.squaredNorm(), 1e-25);
+  EXPECT_NEAR(0.0, state_.squaredNorm(), 1e-25)
+      << "Expected state of zero, got: " << state_.transpose();
 }
 
 // Tests that when we freeze the controller without having acquired a target, we
@@ -268,9 +264,9 @@
 
   // Now, provide a target:
   target_selector_.set_has_target(true);
-  set_goal_pose({{1.0, 1.0, 0.0}, M_PI_2});
+  set_goal_pose({{1.0, 2.0, 0.0}, M_PI_2});
   driver_model_ = [this](const ::Eigen::Matrix<double, 5, 1> &state) {
-    return (state.topRows<2>() - goal_pose().abs_pos().topRows<2>()).norm();
+    return -(state.y() - goal_pose().abs_pos().y());
   };
   expect_output_ = true;
 
@@ -289,10 +285,13 @@
     : public LineFollowDrivetrainTest,
       public ::testing::WithParamInterface<Pose> {};
 TEST_P(LineFollowDrivetrainTargetParamTest, NonZeroTargetTest) {
+  freeze_target_ = true;
+  target_selector_.set_has_target(true);
   // Start the state at zero and then put the target in a
   state_.setZero();
   driver_model_ = [this](const ::Eigen::Matrix<double, 5, 1> &state) {
-    return (state.topRows<2>() - GetParam().abs_pos().topRows<2>()).norm();
+    return 0.2 *
+           (state.topRows<2>() - GetParam().abs_pos().topRows<2>()).norm();
   };
   set_goal_pose(GetParam());
   RunForTime(chrono::seconds(10));
@@ -353,13 +352,13 @@
                 .finished()),
         ::testing::Values(
             [](const ::Eigen::Matrix<double, 5, 1> &state) {
-              return -5.0 * state.x();
+              return -1.0 * state.x();
             },
             [](const ::Eigen::Matrix<double, 5, 1> &state) {
-              return 5.0 * state.x();
+              return 1.0 * state.x();
             },
             [](const ::Eigen::Matrix<double, 5, 1> &state) {
-              return -1.0 * ::std::abs(state.x()) - 0.5 * state.x() * state.x();
+              return -0.25 * ::std::abs(state.x()) - 0.125 * state.x() * state.x();
             })));
 
 }  // namespace testing
diff --git a/frc971/control_loops/drivetrain/localizer.h b/frc971/control_loops/drivetrain/localizer.h
index f0685dd..9866803 100644
--- a/frc971/control_loops/drivetrain/localizer.h
+++ b/frc971/control_loops/drivetrain/localizer.h
@@ -25,6 +25,11 @@
   // Gets the current target pose. Should only be called if UpdateSelection has
   // returned true.
   virtual TypedPose<double> TargetPose() const = 0;
+  // The "radius" of the target--for y2019, we wanted to drive in so that a disc
+  // with radius r would hit the plane of the target at an offset of exactly r
+  // from the TargetPose--this is distinct from wanting the center of the
+  // robot to project straight onto the center of the target.
+  virtual double TargetRadius() const = 0;
 };
 
 // Defines an interface for classes that provide field-global localization.
@@ -44,7 +49,8 @@
                       double left_encoder, double right_encoder,
                       double gyro_rate, double longitudinal_accelerometer) = 0;
   // Reset the absolute position of the estimator.
-  virtual void ResetPosition(double x, double y, double theta) = 0;
+  virtual void ResetPosition(::aos::monotonic_clock::time_point t, double x,
+                             double y, double theta) = 0;
   // There are several subtly different norms floating around for state
   // matrices. In order to avoid that mess, we jus tprovide direct accessors for
   // the values that most people care about.
@@ -53,6 +59,8 @@
   virtual double theta() const = 0;
   virtual double left_velocity() const = 0;
   virtual double right_velocity() const = 0;
+  virtual double left_encoder() const = 0;
+  virtual double right_encoder() const = 0;
   virtual double left_voltage_error() const = 0;
   virtual double right_voltage_error() const = 0;
   virtual TargetSelectorInterface *target_selector() = 0;
@@ -66,14 +74,17 @@
     return has_target_;
   }
   TypedPose<double> TargetPose() const override { return pose_; }
+  double TargetRadius() const override { return target_radius_; }
 
   void set_pose(const TypedPose<double> &pose) { pose_ = pose; }
+  void set_target_radius(double radius) { target_radius_ = radius; }
   void set_has_target(bool has_target) { has_target_ = has_target; }
   bool has_target() const { return has_target_; }
 
  private:
   bool has_target_ = true;
   TypedPose<double> pose_;
+  double target_radius_ = 0.0;
 };
 
 // Uses the generic HybridEkf implementation to provide a basic field estimator.
@@ -97,27 +108,36 @@
     ekf_.UpdateEncodersAndGyro(left_encoder, right_encoder, gyro_rate, U, now);
   }
 
-  void ResetPosition(double x, double y, double theta) override {
+  void ResetPosition(::aos::monotonic_clock::time_point t, double x, double y,
+                     double theta) override {
     const double left_encoder = ekf_.X_hat(StateIdx::kLeftEncoder);
     const double right_encoder = ekf_.X_hat(StateIdx::kRightEncoder);
-    ekf_.ResetInitialState(
-        ::aos::monotonic_clock::now(),
-        (Ekf::State() << x, y, theta, left_encoder, 0, right_encoder, 0)
-            .finished(),
-        ekf_.P());
+    ekf_.ResetInitialState(t, (Ekf::State() << x, y, theta, left_encoder, 0,
+                               right_encoder, 0, 0, 0, 0).finished(),
+                           ekf_.P());
   };
 
   double x() const override { return ekf_.X_hat(StateIdx::kX); }
   double y() const override { return ekf_.X_hat(StateIdx::kY); }
   double theta() const override { return ekf_.X_hat(StateIdx::kTheta); }
+  double left_encoder() const override {
+    return ekf_.X_hat(StateIdx::kLeftEncoder);
+  }
+  double right_encoder() const override {
+    return ekf_.X_hat(StateIdx::kRightEncoder);
+  }
   double left_velocity() const override {
     return ekf_.X_hat(StateIdx::kLeftVelocity);
   }
   double right_velocity() const override {
     return ekf_.X_hat(StateIdx::kRightVelocity);
   }
-  double left_voltage_error() const override { return 0.0; }
-  double right_voltage_error() const override { return 0.0; }
+  double left_voltage_error() const override {
+    return ekf_.X_hat(StateIdx::kLeftVoltageError);
+  }
+  double right_voltage_error() const override {
+    return ekf_.X_hat(StateIdx::kRightVoltageError);
+  }
 
   TrivialTargetSelector *target_selector() override {
     return &target_selector_;
diff --git a/frc971/control_loops/drivetrain/splinedrivetrain.cc b/frc971/control_loops/drivetrain/splinedrivetrain.cc
index 2621007..0b6026d 100644
--- a/frc971/control_loops/drivetrain/splinedrivetrain.cc
+++ b/frc971/control_loops/drivetrain/splinedrivetrain.cc
@@ -41,6 +41,7 @@
     plan_state_ = PlanState::kBuildingTrajectory;
     const ::frc971::MultiSpline &multispline = goal_.spline;
     future_spline_idx_ = multispline.spline_idx;
+    planning_spline_idx_ = future_spline_idx_;
     auto x = multispline.spline_x;
     auto y = multispline.spline_y;
     ::std::vector<Spline> splines = ::std::vector<Spline>();
@@ -187,8 +188,15 @@
     }
     status->trajectory_logging.planning_state = static_cast<int8_t>(plan_state_.load());
     status->trajectory_logging.is_executing = !IsAtEnd();
-    status->trajectory_logging.current_spline_handle = current_spline_handle_;
+    status->trajectory_logging.goal_spline_handle = current_spline_handle_;
     status->trajectory_logging.current_spline_idx = current_spline_idx_;
+
+    int32_t planning_spline_idx = planning_spline_idx_;
+    if (current_spline_idx_ == planning_spline_idx) {
+      status->trajectory_logging.planning_spline_idx = 0;
+    } else {
+      status->trajectory_logging.planning_spline_idx = planning_spline_idx_;
+    }
   }
 }
 
diff --git a/frc971/control_loops/drivetrain/splinedrivetrain.h b/frc971/control_loops/drivetrain/splinedrivetrain.h
index c9ebbe4..3e47f5a 100644
--- a/frc971/control_loops/drivetrain/splinedrivetrain.h
+++ b/frc971/control_loops/drivetrain/splinedrivetrain.h
@@ -99,13 +99,14 @@
   ::std::unique_ptr<Trajectory> past_trajectory_;
   ::std::unique_ptr<Trajectory> future_trajectory_;
   int32_t future_spline_idx_ = 0;  // Current spline being computed.
+  ::std::atomic<int32_t> planning_spline_idx_{-1};
 
   // TODO(alex): pull this out of dt_config.
   const ::Eigen::DiagonalMatrix<double, 5> Q =
       (::Eigen::DiagonalMatrix<double, 5>().diagonal()
-           << 1.0 / ::std::pow(0.05, 2),
-       1.0 / ::std::pow(0.05, 2), 1.0 / ::std::pow(0.2, 2),
-       1.0 / ::std::pow(0.5, 2), 1.0 / ::std::pow(0.5, 2))
+           << 1.0 / ::std::pow(0.07, 2),
+       1.0 / ::std::pow(0.07, 2), 1.0 / ::std::pow(0.2, 2),
+       1.0 / ::std::pow(1.5, 2), 1.0 / ::std::pow(1.5, 2))
           .finished()
           .asDiagonal();
   const ::Eigen::DiagonalMatrix<double, 2> R =
diff --git a/frc971/control_loops/drivetrain/trajectory_plot.cc b/frc971/control_loops/drivetrain/trajectory_plot.cc
index fec90f1..8508099 100644
--- a/frc971/control_loops/drivetrain/trajectory_plot.cc
+++ b/frc971/control_loops/drivetrain/trajectory_plot.cc
@@ -9,7 +9,7 @@
 #include "frc971/control_loops/dlqr.h"
 #include "gflags/gflags.h"
 #include "third_party/matplotlib-cpp/matplotlibcpp.h"
-#include "y2016/control_loops/drivetrain/drivetrain_base.h"
+#include "y2019/control_loops/drivetrain/drivetrain_base.h"
 
 // Notes:
 //   Basic ideas from spline following are from Jared Russell and
@@ -55,7 +55,7 @@
                      .finished())));
   Trajectory trajectory(
       &distance_spline,
-      ::y2016::control_loops::drivetrain::GetDrivetrainConfig());
+      ::y2019::control_loops::drivetrain::GetDrivetrainConfig());
   trajectory.set_lateral_acceleration(2.0);
   trajectory.set_longitudal_acceleration(1.0);
 
diff --git a/package.json b/package.json
new file mode 100644
index 0000000..0b20391
--- /dev/null
+++ b/package.json
@@ -0,0 +1,9 @@
+{
+  "name": "971-Robot-Code",
+  "license": "MIT",
+  "devDependencies": {
+    "@bazel/bazel": "^0.19.1",
+    "@bazel/typescript": "0.21.0",
+    "typescript": "^3.1.6"
+  }
+}
diff --git a/third_party/seasocks/BUILD b/third_party/seasocks/BUILD
index 0daf8ea..974b131 100644
--- a/third_party/seasocks/BUILD
+++ b/third_party/seasocks/BUILD
@@ -1,22 +1,24 @@
-licenses(['notice'])
+licenses(["notice"])
 
 cc_library(
-  name = 'seasocks',
-  visibility = ['//visibility:public'],
-  srcs = glob(['src/main/c/**/*.cpp']),
-  hdrs = glob([
-    'src/main/c/**/*.h',
-  ], exclude=[
-    'src/main/internal/**/*',
-  ]),
-  includes = ['src/main/c'],
-  copts = [
-    # TODO(Brian): Don't apply this to all of the code...
-    '-Wno-cast-align',
-    '-Wno-cast-qual',
-
-    '-Wno-switch-enum',
-    '-Wno-format-nonliteral',
-    '-Wno-unused-parameter',
-  ],
+    name = "seasocks",
+    srcs = glob(include = ["src/main/c/**/*.cpp"]),
+    hdrs = glob(
+        include = [
+            "src/main/c/**/*.h",
+        ],
+        exclude = [
+            "src/main/internal/**/*",
+        ],
+    ),
+    copts = [
+        # TODO(Brian): Don't apply this to all of the code...
+        "-Wno-cast-align",
+        "-Wno-cast-qual",
+        "-Wno-switch-enum",
+        "-Wno-format-nonliteral",
+        "-Wno-unused-parameter",
+    ],
+    includes = ["src/main/c"],
+    visibility = ["//visibility:public"],
 )
diff --git a/tsconfig.json b/tsconfig.json
new file mode 100644
index 0000000..91093d3
--- /dev/null
+++ b/tsconfig.json
@@ -0,0 +1,10 @@
+{
+  "compilerOptions": {
+    "experimentalDecorators": true,
+    "strict": true,
+    "noImplicitAny": false
+  },
+  "bazelOptions": {
+    "workspaceName": "971-Robot-Code"
+  }
+}
diff --git a/y2016/dashboard/dashboard.cc b/y2016/dashboard/dashboard.cc
index ceb4358..5f0a33f 100644
--- a/y2016/dashboard/dashboard.cc
+++ b/y2016/dashboard/dashboard.cc
@@ -8,6 +8,7 @@
 #include <thread>
 #include <vector>
 
+#include "internal/Embedded.h"
 #include "seasocks/Server.h"
 
 #include "aos/init.h"
@@ -22,8 +23,6 @@
 #include "y2016/control_loops/superstructure/superstructure.q.h"
 #include "y2016/queues/ball_detector.q.h"
 
-#include "y2016/dashboard/embedded.h"
-
 namespace chrono = ::std::chrono;
 
 namespace y2016 {
@@ -292,6 +291,9 @@
 }  // namespace y2016
 
 int main(int, char *[]) {
+  // Make sure to reference this to force the linker to include it.
+  findEmbeddedContent("");
+
   ::aos::InitNRT();
 
   ::seasocks::Server server(::std::shared_ptr<seasocks::Logger>(
diff --git a/y2019/BUILD b/y2019/BUILD
index 276f09c..c49e7c4 100644
--- a/y2019/BUILD
+++ b/y2019/BUILD
@@ -3,11 +3,16 @@
 load("@com_google_protobuf//:protobuf.bzl", "cc_proto_library")
 
 robot_downloader(
+    dirs = [
+        "//y2019/vision/server:www_files",
+    ],
     start_binaries = [
         ":joystick_reader",
         ":wpilib_interface",
         "//y2019/control_loops/drivetrain:drivetrain",
         "//y2019/control_loops/superstructure:superstructure",
+        "//y2019/actors:binaries",
+        "//y2019/vision/server",
     ],
 )
 
@@ -131,6 +136,7 @@
         "//frc971/control_loops/drivetrain:drivetrain_queue",
         "//frc971/control_loops/drivetrain:localizer_queue",
         "//y2019/control_loops/drivetrain:drivetrain_base",
+        "//y2019/control_loops/drivetrain:target_selector_queue",
         "//y2019/control_loops/superstructure:superstructure_queue",
         "@com_google_protobuf//:protobuf",
     ],
diff --git a/y2019/actors/BUILD b/y2019/actors/BUILD
new file mode 100644
index 0000000..ee70772
--- /dev/null
+++ b/y2019/actors/BUILD
@@ -0,0 +1,50 @@
+filegroup(
+    name = "binaries.stripped",
+    srcs = [
+        ":autonomous_action.stripped",
+    ],
+    visibility = ["//visibility:public"],
+)
+
+filegroup(
+    name = "binaries",
+    srcs = [
+        ":autonomous_action",
+    ],
+    visibility = ["//visibility:public"],
+)
+
+cc_library(
+    name = "autonomous_action_lib",
+    srcs = [
+        "auto_splines.cc",
+        "autonomous_actor.cc",
+    ],
+    hdrs = [
+        "auto_splines.h",
+        "autonomous_actor.h",
+    ],
+    deps = [
+        "//aos/logging",
+        "//aos/util:phased_loop",
+        "//frc971/autonomous:base_autonomous_actor",
+        "//frc971/control_loops:queues",
+        "//frc971/control_loops/drivetrain:drivetrain_config",
+        "//frc971/control_loops/drivetrain:drivetrain_queue",
+        "//frc971/control_loops/drivetrain:localizer_queue",
+        "//y2019/control_loops/drivetrain:drivetrain_base",
+        "//y2019/control_loops/superstructure:superstructure_queue",
+    ],
+)
+
+cc_binary(
+    name = "autonomous_action",
+    srcs = [
+        "autonomous_actor_main.cc",
+    ],
+    deps = [
+        ":autonomous_action_lib",
+        "//aos:init",
+        "//frc971/autonomous:auto_queue",
+    ],
+)
diff --git a/y2019/actors/auto_splines.cc b/y2019/actors/auto_splines.cc
new file mode 100644
index 0000000..f316037
--- /dev/null
+++ b/y2019/actors/auto_splines.cc
@@ -0,0 +1,75 @@
+#include "y2019/actors/auto_splines.h"
+
+#include "frc971/control_loops/control_loops.q.h"
+
+namespace y2019 {
+namespace actors {
+
+::frc971::MultiSpline AutonomousSplines::HPToNearRocket() {
+  ::frc971::MultiSpline spline;
+  ::frc971::Constraint longitudinal_constraint;
+  ::frc971::Constraint lateral_constraint;
+  ::frc971::Constraint voltage_constraint;
+
+  longitudinal_constraint.constraint_type = 1;
+  longitudinal_constraint.value = 1.0;
+
+  lateral_constraint.constraint_type = 2;
+  lateral_constraint.value = 1.0;
+
+  voltage_constraint.constraint_type = 3;
+  voltage_constraint.value = 12.0;
+
+  spline.spline_count = 1;
+  spline.spline_x = {{0.4, 1.0, 3.0, 4.0, 4.5, 5.05}};
+  spline.spline_y = {{3.4, 3.4, 3.4, 3.0, 3.0, 3.5}};
+  spline.constraints = {
+      {longitudinal_constraint, lateral_constraint, voltage_constraint}};
+  return spline;
+}
+
+::frc971::MultiSpline AutonomousSplines::BasicSSpline() {
+  ::frc971::MultiSpline spline;
+  ::frc971::Constraint longitudinal_constraint;
+  ::frc971::Constraint lateral_constraint;
+  ::frc971::Constraint voltage_constraint;
+
+  longitudinal_constraint.constraint_type = 1;
+  longitudinal_constraint.value = 1.0;
+
+  lateral_constraint.constraint_type = 2;
+  lateral_constraint.value = 1.0;
+
+  voltage_constraint.constraint_type = 3;
+  voltage_constraint.value = 6.0;
+
+  spline.spline_count = 1;
+  const float startx = 0.4;
+  const float starty = 3.4;
+  spline.spline_x = {{0.0f + startx, 0.6f + startx, 0.6f + startx,
+                      0.4f + startx, 0.4f + startx, 1.0f + startx}};
+  spline.spline_y = {{starty - 0.0f, starty - 0.0f, starty - 0.3f,
+                      starty - 0.7f, starty - 1.0f, starty - 1.0f}};
+  spline.constraints = {
+      {longitudinal_constraint, lateral_constraint, voltage_constraint}};
+  return spline;
+}
+
+::frc971::MultiSpline AutonomousSplines::StraightLine() {
+  ::frc971::MultiSpline spline;
+  ::frc971::Constraint contraints;
+
+  contraints.constraint_type = 0;
+  contraints.value = 0.0;
+  contraints.start_distance = 0.0;
+  contraints.end_distance = 0.0;
+
+  spline.spline_count = 1;
+  spline.spline_x = {{-12.3, -11.9, -11.5, -11.1, -10.6, -10.0}};
+  spline.spline_y = {{1.25, 1.25, 1.25, 1.25, 1.25, 1.25}};
+  spline.constraints = {{contraints}};
+  return spline;
+}
+
+}  // namespace actors
+}  // namespace y2019
diff --git a/y2019/actors/auto_splines.h b/y2019/actors/auto_splines.h
new file mode 100644
index 0000000..7e79d1f
--- /dev/null
+++ b/y2019/actors/auto_splines.h
@@ -0,0 +1,30 @@
+#ifndef Y2019_ACTORS_AUTO_SPLINES_H_
+#define Y2019_ACTORS_AUTO_SPLINES_H_
+
+#include "frc971/control_loops/control_loops.q.h"
+/*
+
+  The cooridinate system for the autonomous splines is the same as the spline
+  python generator and drivetrain spline systems.
+
+*/
+
+namespace y2019 {
+namespace actors {
+
+class AutonomousSplines {
+ public:
+  // A spline that does an 's' cause that's what he wanted.
+  static ::frc971::MultiSpline BasicSSpline();
+
+  // Straight
+  static ::frc971::MultiSpline StraightLine();
+
+  // HP to near side rocket
+  static ::frc971::MultiSpline HPToNearRocket();
+};
+
+}  // namespace actors
+}  // namespace y2019
+
+#endif // Y2019_ACTORS_AUTO_SPLINES_H_
diff --git a/y2019/actors/autonomous_actor.cc b/y2019/actors/autonomous_actor.cc
new file mode 100644
index 0000000..85d516c
--- /dev/null
+++ b/y2019/actors/autonomous_actor.cc
@@ -0,0 +1,133 @@
+#include "y2019/actors/autonomous_actor.h"
+
+#include <inttypes.h>
+
+#include <chrono>
+#include <cmath>
+
+#include "aos/logging/logging.h"
+#include "aos/util/phased_loop.h"
+
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+#include "frc971/control_loops/drivetrain/localizer.q.h"
+#include "y2019/actors/auto_splines.h"
+#include "y2019/control_loops/drivetrain/drivetrain_base.h"
+
+namespace y2019 {
+namespace actors {
+using ::frc971::control_loops::drivetrain_queue;
+using ::frc971::control_loops::drivetrain::localizer_control;
+using ::aos::monotonic_clock;
+namespace chrono = ::std::chrono;
+
+namespace {
+
+double DoubleSeconds(monotonic_clock::duration duration) {
+  return ::std::chrono::duration_cast<::std::chrono::duration<double>>(duration)
+      .count();
+}
+
+constexpr bool is_left = false;
+
+constexpr double turn_scalar = is_left ? 1.0 : -1.0;
+
+}  // namespace
+
+AutonomousActor::AutonomousActor(
+    ::frc971::autonomous::AutonomousActionQueueGroup *s)
+    : frc971::autonomous::BaseAutonomousActor(
+          s, control_loops::drivetrain::GetDrivetrainConfig()) {}
+
+void AutonomousActor::Reset() {
+  elevator_goal_ = 0.01;
+  wrist_goal_ = -M_PI / 2.0;
+  intake_goal_ = -1.2;
+
+  suction_on_ = false;
+  suction_gamepiece_ = 1;
+
+  elevator_max_velocity_ = 0.0;
+  elevator_max_acceleration_ = 0.0;
+  wrist_max_velocity_ = 0.0;
+  wrist_max_acceleration_ = 0.0;
+
+  InitializeEncoders();
+  SendSuperstructureGoal();
+
+  {
+    auto localizer_resetter = localizer_control.MakeMessage();
+    // Start on the left l2.
+    localizer_resetter->x = 1.0;
+    localizer_resetter->y = 1.5 * turn_scalar;
+    localizer_resetter->theta = M_PI;
+    if (!localizer_resetter.Send()) {
+      LOG(ERROR, "Failed to reset localizer.\n");
+    }
+  }
+
+  // Wait for the drivetrain to run so it has time to reset the heading.
+  // Otherwise our drivetrain reset will do a 180 right at the start.
+  drivetrain_queue.status.FetchAnother();
+  LOG(INFO, "Heading is %f\n", drivetrain_queue.status->estimated_heading);
+  InitializeEncoders();
+  ResetDrivetrain();
+  drivetrain_queue.status.FetchAnother();
+  LOG(INFO, "Heading is %f\n", drivetrain_queue.status->estimated_heading);
+
+  ResetDrivetrain();
+  InitializeEncoders();
+}
+
+const ProfileParameters kJumpDrive = {2.0, 3.0};
+const ProfileParameters kDrive = {4.0, 3.0};
+const ProfileParameters kTurn = {5.0, 15.0};
+
+bool AutonomousActor::RunAction(
+    const ::frc971::autonomous::AutonomousActionParams &params) {
+  monotonic_clock::time_point start_time = monotonic_clock::now();
+  LOG(INFO, "Starting autonomous action with mode %" PRId32 "\n", params.mode);
+  Reset();
+
+  // Grab the disk, wait until we have vacuum, then jump
+  set_elevator_goal(0.01);
+  set_wrist_goal(-M_PI / 2.0);
+  set_intake_goal(-1.2);
+  set_suction_goal(true, 1);
+  SendSuperstructureGoal();
+
+  if (!WaitForGamePiece()) return true;
+  LOG(INFO, "Has game piece\n");
+
+  StartDrive(-4.0, 0.0, kJumpDrive, kTurn);
+  if (!WaitForDriveNear(3.3, 10.0)) return true;
+  LOG(INFO, "Lifting\n");
+  set_elevator_goal(0.30);
+  SendSuperstructureGoal();
+
+  if (!WaitForDriveNear(2.8, 10.0)) return true;
+  LOG(INFO, "Off the platform\n");
+
+  StartDrive(0.0, 1.00 * turn_scalar, kDrive, kTurn);
+  LOG(INFO, "Turn started\n");
+  if (!WaitForSuperstructureDone()) return true;
+  LOG(INFO, "Superstructure done\n");
+
+  if (!WaitForDriveNear(0.7, 10.0)) return true;
+  StartDrive(0.0, -0.35 * turn_scalar, kDrive, kTurn);
+
+  LOG(INFO, "Elevator up\n");
+  set_elevator_goal(0.78);
+  SendSuperstructureGoal();
+
+  if (!WaitForDriveDone()) return true;
+  LOG(INFO, "Done driving\n");
+
+  if (!WaitForSuperstructureDone()) return true;
+
+  LOG(INFO, "Done %f\n", DoubleSeconds(monotonic_clock::now() - start_time));
+
+  return true;
+}
+
+}  // namespace actors
+}  // namespace y2019
diff --git a/y2019/actors/autonomous_actor.h b/y2019/actors/autonomous_actor.h
new file mode 100644
index 0000000..82e1aeb
--- /dev/null
+++ b/y2019/actors/autonomous_actor.h
@@ -0,0 +1,158 @@
+#ifndef Y2019_ACTORS_AUTONOMOUS_ACTOR_H_
+#define Y2019_ACTORS_AUTONOMOUS_ACTOR_H_
+
+#include <chrono>
+#include <memory>
+
+#include "aos/actions/actions.h"
+#include "aos/actions/actor.h"
+#include "frc971/autonomous/base_autonomous_actor.h"
+#include "frc971/control_loops/control_loops.q.h"
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+#include "y2019/control_loops/superstructure/superstructure.q.h"
+
+namespace y2019 {
+namespace actors {
+
+using ::frc971::ProfileParameters;
+using ::y2019::control_loops::superstructure::superstructure_queue;
+
+class AutonomousActor : public ::frc971::autonomous::BaseAutonomousActor {
+ public:
+  explicit AutonomousActor(::frc971::autonomous::AutonomousActionQueueGroup *s);
+
+  bool RunAction(
+      const ::frc971::autonomous::AutonomousActionParams &params) override;
+
+ private:
+  void Reset();
+
+  double elevator_goal_ = 0.0;
+  double wrist_goal_ = 0.0;
+  double intake_goal_ = 0.0;
+
+  bool suction_on_ = true;
+  int suction_gamepiece_ = 1;
+
+  double elevator_max_velocity_ = 0.0;
+  double elevator_max_acceleration_ = 0.0;
+  double wrist_max_velocity_ = 0.0;
+  double wrist_max_acceleration_ = 0.0;
+
+  void set_elevator_goal(double elevator_goal) {
+    elevator_goal_ = elevator_goal;
+  }
+  void set_wrist_goal(double wrist_goal) { wrist_goal_ = wrist_goal; }
+  void set_intake_goal(double intake_goal) { intake_goal_ = intake_goal; }
+
+  void set_suction_goal(bool on, int gamepiece_mode) {
+    suction_on_ = on;
+    suction_gamepiece_ = gamepiece_mode;
+  }
+
+  void set_elevator_max_velocity(double elevator_max_velocity) {
+    elevator_max_velocity_ = elevator_max_velocity;
+  }
+  void set_elevator_max_acceleration(double elevator_max_acceleration) {
+    elevator_max_acceleration_ = elevator_max_acceleration;
+  }
+  void set_wrist_max_velocity(double wrist_max_velocity) {
+    wrist_max_velocity_ = wrist_max_velocity;
+  }
+  void set_wrist_max_acceleration(double wrist_max_acceleration) {
+    wrist_max_acceleration_ = wrist_max_acceleration;
+  }
+
+  void SendSuperstructureGoal() {
+    auto new_superstructure_goal = superstructure_queue.goal.MakeMessage();
+    new_superstructure_goal->elevator.unsafe_goal = elevator_goal_;
+    new_superstructure_goal->wrist.unsafe_goal = wrist_goal_;
+    new_superstructure_goal->intake.unsafe_goal = intake_goal_;
+
+    new_superstructure_goal->suction.grab_piece = suction_on_;
+    new_superstructure_goal->suction.gamepiece_mode = suction_gamepiece_;
+
+    new_superstructure_goal->elevator.profile_params.max_velocity =
+        elevator_max_velocity_;
+    new_superstructure_goal->elevator.profile_params.max_acceleration =
+        elevator_max_acceleration_;
+
+    new_superstructure_goal->wrist.profile_params.max_velocity =
+        wrist_max_velocity_;
+    new_superstructure_goal->wrist.profile_params.max_acceleration =
+        wrist_max_acceleration_;
+
+    if (!new_superstructure_goal.Send()) {
+      LOG(ERROR, "Sending superstructure goal failed.\n");
+    }
+  }
+
+  bool IsSucked() {
+    superstructure_queue.status.FetchLatest();
+
+    if (superstructure_queue.status.get()) {
+      return superstructure_queue.status->has_piece;
+    }
+    return false;
+  }
+
+  bool WaitForGamePiece() {
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                        ::std::chrono::milliseconds(5) / 2);
+
+    while (true) {
+      if (ShouldCancel()) {
+        return false;
+      }
+      phased_loop.SleepUntilNext();
+      if (IsSucked()) {
+        return true;
+      }
+    }
+  }
+
+  bool IsSuperstructureDone() {
+    superstructure_queue.status.FetchLatest();
+
+    double kElevatorTolerance = 0.01;
+    double kWristTolerance = 0.05;
+
+    if (superstructure_queue.status.get()) {
+      const bool elevator_at_goal =
+          ::std::abs(elevator_goal_ -
+                     superstructure_queue.status->elevator.position) <
+          kElevatorTolerance;
+
+      const bool wrist_at_goal =
+          ::std::abs(wrist_goal_ -
+                     superstructure_queue.status->wrist.position) <
+          kWristTolerance;
+
+      return elevator_at_goal && wrist_at_goal;
+    }
+    return false;
+  }
+
+  bool WaitForSuperstructureDone() {
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                        ::std::chrono::milliseconds(5) / 2);
+
+    while (true) {
+      if (ShouldCancel()) {
+        return false;
+      }
+      phased_loop.SleepUntilNext();
+      superstructure_queue.status.FetchLatest();
+      superstructure_queue.goal.FetchLatest();
+      if (IsSuperstructureDone()) {
+        return true;
+      }
+    }
+  }
+};
+
+}  // namespace actors
+}  // namespace y2019
+
+#endif  // Y2019_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2019/actors/autonomous_actor_main.cc b/y2019/actors/autonomous_actor_main.cc
new file mode 100644
index 0000000..0a77eb9
--- /dev/null
+++ b/y2019/actors/autonomous_actor_main.cc
@@ -0,0 +1,16 @@
+#include <stdio.h>
+
+#include "aos/init.h"
+#include "frc971/autonomous/auto.q.h"
+#include "y2019/actors/autonomous_actor.h"
+
+int main(int /*argc*/, char * /*argv*/ []) {
+  ::aos::Init(-1);
+
+  ::y2019::actors::AutonomousActor autonomous(
+      &::frc971::autonomous::autonomous_action);
+  autonomous.Run();
+
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/y2019/constants.cc b/y2019/constants.cc
index 285cb21..7406488 100644
--- a/y2019/constants.cc
+++ b/y2019/constants.cc
@@ -143,15 +143,15 @@
   stilts_params->zeroing_constants.allowable_encoder_error = 0.9;
 
   r->camera_noise_parameters = {.max_viewable_distance = 10.0,
-                                .heading_noise = 0.2,
-                                .nominal_distance_noise = 0.3,
-                                .nominal_skew_noise = 0.35,
+                                .heading_noise = 0.1,
+                                .nominal_distance_noise = 0.15,
+                                .nominal_skew_noise = 0.45,
                                 .nominal_height_noise = 0.01};
 
   // Deliberately make FOV a bit large so that we are overly conservative in
   // our EKF.
   for (auto &camera : r->cameras) {
-    camera.fov = M_PI_2 * 1.1;
+    camera.fov = M_PI_2 * 1.5;
   }
 
   switch (team) {
@@ -178,29 +178,32 @@
       break;
 
     case kCompTeamNumber:
-      elevator_params->zeroing_constants.measured_absolute_position = 0.024407;
-      elevator->potentiometer_offset = -0.075017 + 0.015837 + 0.009793 - 0.012017;
+      elevator_params->zeroing_constants.measured_absolute_position = 0.160736;
+      elevator->potentiometer_offset =
+          -0.075017 + 0.015837 + 0.009793 - 0.012017 + 0.019915 + 0.010126 +
+          0.005541 + 0.006088 - 0.039687 + 0.005843;
 
       intake->zeroing_constants.measured_absolute_position = 1.860016;
 
-      wrist_params->zeroing_constants.measured_absolute_position = 0.163840;
-      wrist->potentiometer_offset = -4.257454;
+      wrist_params->zeroing_constants.measured_absolute_position = 0.164498;
+      wrist->potentiometer_offset = -4.257454 - 0.058039;
 
-      stilts_params->zeroing_constants.measured_absolute_position = 0.030049;
-      stilts->potentiometer_offset = -0.015760 + 0.011604;
+      stilts_params->zeroing_constants.measured_absolute_position = 0.066843;
+      stilts->potentiometer_offset = -0.015760 + 0.011604 - 0.061213 + 0.006690;
+      FillCameraPoses(vision::CompBotTeensyId(), &r->cameras);
       break;
 
     case kPracticeTeamNumber:
-      elevator_params->zeroing_constants.measured_absolute_position = 0.147809;
-      elevator->potentiometer_offset = -0.022320 + 0.020567 - 0.022355 - 0.006497 + 0.019690;
+      elevator_params->zeroing_constants.measured_absolute_position = 0.132216;
+      elevator->potentiometer_offset = -0.022320 + 0.020567 - 0.022355 - 0.006497 + 0.019690 + 0.009151;
 
       intake->zeroing_constants.measured_absolute_position = 1.756847;
 
       wrist_params->zeroing_constants.measured_absolute_position = 0.192576;
       wrist->potentiometer_offset = -4.200894 - 0.187134;
 
-      stilts_params->zeroing_constants.measured_absolute_position = 0.043580;
-      stilts->potentiometer_offset = -0.093820 + 0.0124 - 0.008334 + 0.004507;
+      stilts_params->zeroing_constants.measured_absolute_position = 0.050550;
+      stilts->potentiometer_offset = -0.093820 + 0.0124 - 0.008334 + 0.004507 - 0.007973 + -0.001221;
 
       FillCameraPoses(vision::PracticeBotTeensyId(), &r->cameras);
       break;
@@ -308,59 +311,74 @@
   constexpr double kHpSlotY = InchToMeters((26 * 12 + 10.5) / 2.0 - 25.9);
   constexpr double kHpSlotTheta = M_PI;
 
-  constexpr double kNormalZ = 0.85;
-  constexpr double kPortZ = 1.04;
+  constexpr double kNormalZ = 0.80;
+  constexpr double kPortZ = 1.00;
 
-  const Pose far_side_cargo_bay({kFarSideCargoBayX, kSideCargoBayY, kNormalZ},
-                                kSideCargoBayTheta);
-  const Pose mid_side_cargo_bay({kMidSideCargoBayX, kSideCargoBayY, kNormalZ},
-                                kSideCargoBayTheta);
-  const Pose near_side_cargo_bay({kNearSideCargoBayX, kSideCargoBayY, kNormalZ},
-                                 kSideCargoBayTheta);
+  constexpr double kDiscRadius = InchToMeters(19.0 / 2.0);
 
-  const Pose face_cargo_bay({kFaceCargoBayX, kFaceCargoBayY, kNormalZ},
-                            kFaceCargoBayTheta);
+  constexpr Target::GoalType kBothGoal = Target::GoalType::kBoth;
+  constexpr Target::GoalType kBallGoal = Target::GoalType::kBalls;
+  constexpr Target::GoalType kDiscGoal = Target::GoalType::kHatches;
+  constexpr Target::GoalType kNoneGoal = Target::GoalType::kNone;
+  using TargetType = Target::TargetType;
 
-  const Pose rocket_port({kRocketPortX, kRocketPortY, kPortZ},
-                         kRocketPortTheta);
+  const Target far_side_cargo_bay(
+      {{kFarSideCargoBayX, kSideCargoBayY, kNormalZ}, kSideCargoBayTheta},
+      kDiscRadius, TargetType::kFarSideCargoBay, kBothGoal);
+  const Target mid_side_cargo_bay(
+      {{kMidSideCargoBayX, kSideCargoBayY, kNormalZ}, kSideCargoBayTheta},
+      kDiscRadius, TargetType::kMidSideCargoBay, kBothGoal);
+  const Target near_side_cargo_bay(
+      {{kNearSideCargoBayX, kSideCargoBayY, kNormalZ}, kSideCargoBayTheta},
+      kDiscRadius, TargetType::kNearSideCargoBay, kBothGoal);
 
-  const Pose rocket_near({kRocketNearX, kRocketHatchY, kNormalZ},
-                         kRocketNearTheta);
-  const Pose rocket_far({kRocketFarX, kRocketHatchY, kNormalZ},
-                        kRocketFarTheta);
+  const Target face_cargo_bay(
+      {{kFaceCargoBayX, kFaceCargoBayY, kNormalZ}, kFaceCargoBayTheta},
+      kDiscRadius, TargetType::kFaceCargoBay, kBothGoal);
 
-  const Pose hp_slot({0.0, kHpSlotY, kNormalZ}, kHpSlotTheta);
+  // The rocket port, since it is only for balls, has no meaningful radius
+  // to work with (and is over-ridden with zero in target_selector).
+  const Target rocket_port(
+      {{kRocketPortX, kRocketPortY, kPortZ}, kRocketPortTheta}, 0.0,
+      TargetType::kRocketPortal, kBallGoal);
 
-  const ::std::array<Pose, 8> quarter_field_targets{
+  const Target rocket_near(
+      {{kRocketNearX, kRocketHatchY, kNormalZ}, kRocketNearTheta}, kDiscRadius,
+      TargetType::kNearRocket, kDiscGoal);
+  const Target rocket_far(
+      {{kRocketFarX, kRocketHatchY, kNormalZ}, kRocketFarTheta}, kDiscRadius,
+      TargetType::kFarRocket, kDiscGoal);
+
+  const Target hp_slot({{0.0, kHpSlotY, kNormalZ}, kHpSlotTheta}, 0.00,
+                       TargetType::kHPSlot, kBothGoal);
+
+  const ::std::array<Target, 8> quarter_field_targets{
       {far_side_cargo_bay, mid_side_cargo_bay, near_side_cargo_bay,
        face_cargo_bay, rocket_port, rocket_near, rocket_far, hp_slot}};
 
   // Mirror across center field mid-line (short field axis):
-  ::std::array<Pose, 16> half_field_targets;
+  ::std::array<Target, 16> half_field_targets;
   ::std::copy(quarter_field_targets.begin(), quarter_field_targets.end(),
               half_field_targets.begin());
   for (int ii = 0; ii < 8; ++ii) {
     const int jj = ii + 8;
     half_field_targets[jj] = quarter_field_targets[ii];
-    half_field_targets[jj].mutable_pos()->x() =
-        2.0 * kCenterFieldX - half_field_targets[jj].rel_pos().x();
-    half_field_targets[jj].set_theta(
-        aos::math::NormalizeAngle(M_PI - half_field_targets[jj].rel_theta()));
+    half_field_targets[jj].mutable_pose()->mutable_pos()->x() =
+        2.0 * kCenterFieldX - half_field_targets[jj].pose().rel_pos().x();
+    half_field_targets[jj].mutable_pose()->set_theta(aos::math::NormalizeAngle(
+        M_PI - half_field_targets[jj].pose().rel_theta()));
+    // Targets on the opposite side of the field can't be driven to.
+    half_field_targets[jj].set_goal_type(kNoneGoal);
   }
 
-  ::std::array<Pose, 32> target_poses_;
-
   // Mirror across x-axis (long field axis):
   ::std::copy(half_field_targets.begin(), half_field_targets.end(),
-              target_poses_.begin());
+              targets_.begin());
   for (int ii = 0; ii < 16; ++ii) {
     const int jj = ii + 16;
-    target_poses_[jj] = half_field_targets[ii];
-    target_poses_[jj].mutable_pos()->y() *= -1;
-    target_poses_[jj].set_theta(-target_poses_[jj].rel_theta());
-  }
-  for (int ii = 0; ii < 32; ++ii) {
-    targets_[ii] = {target_poses_[ii]};
+    targets_[jj] = half_field_targets[ii];
+    targets_[jj].mutable_pose()->mutable_pos()->y() *= -1;
+    targets_[jj].mutable_pose()->set_theta(-targets_[jj].pose().rel_theta());
   }
 
   // Define rocket obstacles as just being a single line that should block any
diff --git a/y2019/control_loops/drivetrain/BUILD b/y2019/control_loops/drivetrain/BUILD
index 5a4dd40..49cda13 100644
--- a/y2019/control_loops/drivetrain/BUILD
+++ b/y2019/control_loops/drivetrain/BUILD
@@ -84,6 +84,14 @@
 )
 
 queue_library(
+    name = "target_selector_queue",
+    srcs = [
+        "target_selector.q",
+    ],
+    visibility = ["//visibility:public"],
+)
+
+queue_library(
     name = "camera_queue",
     srcs = [
         "camera.q",
@@ -126,9 +134,11 @@
     hdrs = ["target_selector.h"],
     deps = [
         ":camera",
+        ":target_selector_queue",
         "//frc971/control_loops:pose",
         "//frc971/control_loops/drivetrain:localizer",
         "//y2019:constants",
+        "//y2019/control_loops/superstructure:superstructure_queue",
     ],
 )
 
@@ -138,6 +148,7 @@
     deps = [
         ":target_selector",
         "//aos/testing:googletest",
+        "//aos/testing:test_shm",
     ],
 )
 
diff --git a/y2019/control_loops/drivetrain/camera.h b/y2019/control_loops/drivetrain/camera.h
index d59ac21..e21bf87 100644
--- a/y2019/control_loops/drivetrain/camera.h
+++ b/y2019/control_loops/drivetrain/camera.h
@@ -34,12 +34,49 @@
 class TypedTarget {
  public:
   typedef ::frc971::control_loops::TypedPose<Scalar> Pose;
-  TypedTarget(const Pose &pose) : pose_(pose) {}
+  // The nature of the target as a goal--to mark what modes it is a valid
+  // potential goal pose and to mark targets on the opposite side of the field
+  // as not being viable targets.
+  enum class GoalType {
+    // None marks targets that are on the opposite side of the field and not
+    // viable goal poses.
+    kNone,
+    // Spots where we can touch hatch panels.
+    kHatches,
+    // Spots where we can mess with balls.
+    kBalls,
+    // Spots for both (cargo ship, human loading).
+    kBoth,
+  };
+  // Which target this is within a given field quadrant:
+  enum class TargetType {
+    kHPSlot,
+    kFaceCargoBay,
+    kNearSideCargoBay,
+    kMidSideCargoBay,
+    kFarSideCargoBay,
+    kNearRocket,
+    kFarRocket,
+    kRocketPortal,
+  };
+  TypedTarget(const Pose &pose, double radius = 0,
+              TargetType target_type = TargetType::kHPSlot,
+              GoalType goal_type = GoalType::kBoth)
+      : pose_(pose),
+        radius_(radius),
+        target_type_(target_type),
+        goal_type_(goal_type) {}
   TypedTarget() {}
   Pose pose() const { return pose_; }
+  Pose *mutable_pose() { return &pose_; }
 
   bool occluded() const { return occluded_; }
   void set_occluded(bool occluded) { occluded_ = occluded; }
+  double radius() const { return radius_; }
+  GoalType goal_type() const { return goal_type_; }
+  void set_goal_type(GoalType goal_type) { goal_type_ = goal_type; }
+  TargetType target_type() const { return target_type_; }
+  void set_target_type(TargetType target_type) { target_type_ = target_type; }
 
   // Get a list of points for plotting. These points should be plotted on
   // an x/y plane in the global frame with lines connecting the points.
@@ -63,6 +100,14 @@
  private:
   Pose pose_;
   bool occluded_ = false;
+  // The effective radius of the target--for placing discs, this should be the
+  // radius of the disc; for fetching discs and working with balls this should
+  // be near zero.
+  // TODO(james): We may actually want a non-zero (possibly negative?) number
+  // here for balls.
+  double radius_ = 0.0;
+  TargetType target_type_ = TargetType::kHPSlot;
+  GoalType goal_type_ = GoalType::kBoth;
 };  // class TypedTarget
 
 typedef TypedTarget<double> Target;
diff --git a/y2019/control_loops/drivetrain/camera_test.cc b/y2019/control_loops/drivetrain/camera_test.cc
index d0a4b85..f9b6e8d 100644
--- a/y2019/control_loops/drivetrain/camera_test.cc
+++ b/y2019/control_loops/drivetrain/camera_test.cc
@@ -8,12 +8,16 @@
 
 // Check that a Target's basic operations work.
 TEST(TargetTest, BasicTargetTest) {
-  Target target({{1, 2, 3}, M_PI / 2.0});
+  Target target({{1, 2, 3}, M_PI / 2.0}, 1.234,
+                Target::TargetType::kFaceCargoBay, Target::GoalType::kHatches);
 
   EXPECT_EQ(1.0, target.pose().abs_pos().x());
   EXPECT_EQ(2.0, target.pose().abs_pos().y());
   EXPECT_EQ(3.0, target.pose().abs_pos().z());
   EXPECT_EQ(M_PI / 2.0, target.pose().abs_theta());
+  EXPECT_EQ(1.234, target.radius());
+  EXPECT_EQ(Target::GoalType::kHatches, target.goal_type());
+  EXPECT_EQ(Target::TargetType::kFaceCargoBay, target.target_type());
 
   EXPECT_FALSE(target.occluded());
   target.set_occluded(true);
diff --git a/y2019/control_loops/drivetrain/drivetrain_base.cc b/y2019/control_loops/drivetrain/drivetrain_base.cc
index 1dfe99a..089bdf0 100644
--- a/y2019/control_loops/drivetrain/drivetrain_base.cc
+++ b/y2019/control_loops/drivetrain/drivetrain_base.cc
@@ -26,7 +26,7 @@
       ::frc971::control_loops::drivetrain::ShifterType::SIMPLE_SHIFTER,
       ::frc971::control_loops::drivetrain::LoopType::CLOSED_LOOP,
       ::frc971::control_loops::drivetrain::GyroType::IMU_Z_GYRO,
-      ::frc971::control_loops::drivetrain::IMUType::IMU_X,
+      ::frc971::control_loops::drivetrain::IMUType::IMU_FLIPPED_X,
 
       drivetrain::MakeDrivetrainLoop,
       drivetrain::MakeVelocityDrivetrainLoop,
diff --git a/y2019/control_loops/drivetrain/event_loop_localizer.cc b/y2019/control_loops/drivetrain/event_loop_localizer.cc
index dad667f..f33f4e5 100644
--- a/y2019/control_loops/drivetrain/event_loop_localizer.cc
+++ b/y2019/control_loops/drivetrain/event_loop_localizer.cc
@@ -25,22 +25,23 @@
 }
 
 EventLoopLocalizer::EventLoopLocalizer(
-    const ::frc971::control_loops::drivetrain::DrivetrainConfig<double>
-        &dt_config,
+    const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
+        dt_config,
     ::aos::EventLoop *event_loop)
     : event_loop_(event_loop),
       cameras_(MakeCameras(&robot_pose_)),
-      localizer_(dt_config, &robot_pose_) {
+      localizer_(dt_config, &robot_pose_),
+      target_selector_(event_loop) {
   localizer_.ResetInitialState(::aos::monotonic_clock::now(),
                                Localizer::State::Zero(), localizer_.P());
-  ResetPosition(0.5, 3.4, 0.0);
+  ResetPosition(::aos::monotonic_clock::now(), 0.5, 3.4, 0.0);
   frame_fetcher_ = event_loop_->MakeFetcher<CameraFrame>(
       ".y2019.control_loops.drivetrain.camera_frames");
 }
 
-void EventLoopLocalizer::Reset(const Localizer::State &state) {
-  localizer_.ResetInitialState(::aos::monotonic_clock::now(), state,
-                               localizer_.P());
+void EventLoopLocalizer::Reset(::aos::monotonic_clock::time_point now,
+                               const Localizer::State &state) {
+  localizer_.ResetInitialState(now, state, localizer_.P());
 }
 
 void EventLoopLocalizer::Update(
diff --git a/y2019/control_loops/drivetrain/event_loop_localizer.h b/y2019/control_loops/drivetrain/event_loop_localizer.h
index 9207ec1..6d5ca29 100644
--- a/y2019/control_loops/drivetrain/event_loop_localizer.h
+++ b/y2019/control_loops/drivetrain/event_loop_localizer.h
@@ -33,8 +33,10 @@
           &dt_config,
       ::aos::EventLoop *event_loop);
 
-  void Reset(const Localizer::State &state);
-  void ResetPosition(double x, double y, double theta) override {
+  void Reset(::aos::monotonic_clock::time_point t,
+             const Localizer::State &state);
+  void ResetPosition(::aos::monotonic_clock::time_point t, double x, double y,
+                     double theta) override {
     // When we reset the state, we want to keep the encoder positions intact, so
     // we copy from the original state and reset everything else.
     Localizer::State new_state = localizer_.X_hat();
@@ -44,7 +46,11 @@
     // Velocity terms.
     new_state(4, 0) = 0.0;
     new_state(6, 0) = 0.0;
-    Reset(new_state);
+    // Voltage/angular error terms.
+    new_state(7, 0) = 0.0;
+    new_state(8, 0) = 0.0;
+    new_state(9, 0) = 0.0;
+    Reset(t, new_state);
   }
 
   void Update(const ::Eigen::Matrix<double, 2, 1> &U,
@@ -58,14 +64,24 @@
     return localizer_.X_hat(StateIdx::kY); }
   double theta() const override {
     return localizer_.X_hat(StateIdx::kTheta); }
+  double left_encoder() const override {
+    return localizer_.X_hat(StateIdx::kLeftEncoder);
+  }
+  double right_encoder() const override {
+    return localizer_.X_hat(StateIdx::kRightEncoder);
+  }
   double left_velocity() const override {
     return localizer_.X_hat(StateIdx::kLeftVelocity);
   }
   double right_velocity() const override {
     return localizer_.X_hat(StateIdx::kRightVelocity);
   }
-  double left_voltage_error() const override { return 0.0; }
-  double right_voltage_error() const override { return 0.0; }
+  double left_voltage_error() const override {
+    return localizer_.X_hat(StateIdx::kLeftVoltageError);
+  }
+  double right_voltage_error() const override {
+    return localizer_.X_hat(StateIdx::kRightVoltageError);
+  }
 
   TargetSelector *target_selector() override {
     return &target_selector_;
diff --git a/y2019/control_loops/drivetrain/localized_drivetrain_test.cc b/y2019/control_loops/drivetrain/localized_drivetrain_test.cc
index e086e36..b405588 100644
--- a/y2019/control_loops/drivetrain/localized_drivetrain_test.cc
+++ b/y2019/control_loops/drivetrain/localized_drivetrain_test.cc
@@ -67,10 +67,11 @@
   void SetStartingPosition(const Eigen::Matrix<double, 3, 1> &xytheta) {
     *drivetrain_motor_plant_.mutable_state() << xytheta.x(), xytheta.y(),
         xytheta(2, 0), 0.0, 0.0;
-    Eigen::Matrix<double, 7, 1> localizer_state;
+    Eigen::Matrix<double, EventLoopLocalizer::Localizer::kNStates, 1>
+        localizer_state;
     localizer_state.setZero();
     localizer_state.block<3, 1>(0, 0) = xytheta;
-    localizer_.Reset(localizer_state);
+    localizer_.Reset(monotonic_clock::now(), localizer_state);
   }
 
   void RunIteration() {
@@ -296,7 +297,7 @@
       .Send();
   RunForTime(chrono::seconds(3));
   VerifyNearGoal();
-  VerifyEstimatorAccurate(1e-4);
+  VerifyEstimatorAccurate(5e-4);
 }
 
 namespace {
@@ -307,12 +308,12 @@
 // forward from roughly the right spot gets us to the HP slot.
 TEST_F(LocalizedDrivetrainTest, LineFollowToHPSlot) {
   set_enable_cameras(false);
-  SetStartingPosition({4, 3, M_PI});
+  SetStartingPosition({4, HPSlotLeft().abs_pos().y(), M_PI});
   my_drivetrain_queue_.goal.MakeWithBuilder()
       .controller_type(3)
-      .throttle(0.9)
+      .throttle(0.5)
       .Send();
-  RunForTime(chrono::seconds(10));
+  RunForTime(chrono::seconds(6));
 
   VerifyEstimatorAccurate(1e-8);
   // Due to the fact that we aren't modulating the throttle, we don't try to hit
diff --git a/y2019/control_loops/drivetrain/localizer.h b/y2019/control_loops/drivetrain/localizer.h
index b717837..58b6901 100644
--- a/y2019/control_loops/drivetrain/localizer.h
+++ b/y2019/control_loops/drivetrain/localizer.h
@@ -100,7 +100,7 @@
   // The threshold to use for completely rejecting potentially bad target
   // matches.
   // TODO(james): Tune
-  static constexpr Scalar kRejectionScore = 1.0;
+  static constexpr Scalar kRejectionScore = 1000000.0;
 
   // Checks that the targets coming in make some sense--mostly to prevent NaNs
   // or the such from propagating.
@@ -306,6 +306,11 @@
         size_t view_idx = best_frames[ii];
         if (view_idx < 0 || view_idx >= camera_views.size()) {
           LOG(ERROR, "Somehow, the view scorer failed.\n");
+          h_functions->push_back(
+              [](const State &, const Input &) { return Output::Zero(); });
+          dhdx_functions->push_back([](const State &) {
+            return Eigen::Matrix<Scalar, kNOutputs, kNStates>::Zero();
+          });
           continue;
         }
         const Eigen::Matrix<Scalar, kNOutputs, kNStates> best_H =
diff --git a/y2019/control_loops/drivetrain/localizer_test.cc b/y2019/control_loops/drivetrain/localizer_test.cc
index f062234..281abdc 100644
--- a/y2019/control_loops/drivetrain/localizer_test.cc
+++ b/y2019/control_loops/drivetrain/localizer_test.cc
@@ -399,7 +399,7 @@
     U(1, 0) = ::std::max(::std::min(U(1, 0), 12.0), -12.0);
 
     state = ::frc971::control_loops::RungeKuttaU(
-        [this](const ::Eigen::Matrix<double, 7, 1> &X,
+        [this](const ::Eigen::Matrix<double, 10, 1> &X,
                const ::Eigen::Matrix<double, 2, 1> &U) { return DiffEq(X, U); },
         state, U,
         ::std::chrono::duration_cast<::std::chrono::duration<double>>(
@@ -418,7 +418,7 @@
                            ::std::pow(state(StateIdx::kRightVelocity, 0), 2)) /
                    3.0);
       TestLocalizer::State disturbance;
-      disturbance << 0.02, 0.02, 0.001, 0.03, 0.02, 0.0, 0.0;
+      disturbance << 0.02, 0.02, 0.001, 0.03, 0.02, 0.0, 0.0, 0.0, 0.0, 0.0;
       disturbance *= disturbance_scale;
       state += disturbance;
     }
@@ -498,9 +498,11 @@
         LocalizerTestParams({
             /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
             /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
-            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0)
                 .finished(),
-            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0)
                 .finished(),
             /*noisify=*/false,
             /*disturb=*/false,
@@ -512,9 +514,11 @@
         LocalizerTestParams({
             /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
             /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
-            (TestLocalizer::State() << 0.0, -4.0, 0.0, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.0, -4.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0)
                 .finished(),
-            (TestLocalizer::State() << 0.0, -4.0, 0.0, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.0, -4.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0)
                 .finished(),
             /*noisify=*/false,
             /*disturb=*/false,
@@ -525,22 +529,41 @@
         LocalizerTestParams({
             /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
             /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
-            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0)
                 .finished(),
-            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0)
                 .finished(),
             /*noisify=*/true,
             /*disturb=*/false,
             /*estimate_tolerance=*/0.2,
-            /*goal_tolerance=*/0.2,
+            /*goal_tolerance=*/0.4,
         }),
         // Repeats perfect scenario, but add initial estimator error.
         LocalizerTestParams({
             /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
             /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
-            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0)
                 .finished(),
-            (TestLocalizer::State() << 0.1, -5.1, -0.01, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.1, -5.1, -0.01, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0, 0.0)
+                .finished(),
+            /*noisify=*/false,
+            /*disturb=*/false,
+            /*estimate_tolerance=*/1e-4,
+            /*goal_tolerance=*/2e-2,
+        }),
+        // Repeats perfect scenario, but add voltage + angular errors:
+        LocalizerTestParams({
+            /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
+            /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
+            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0,
+             0.5, 0.02)
+                .finished(),
+            (TestLocalizer::State() << 0.1, -5.1, -0.01, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0, 0.0)
                 .finished(),
             /*noisify=*/false,
             /*disturb=*/false,
@@ -551,9 +574,11 @@
         LocalizerTestParams({
             /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
             /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
-            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0)
                 .finished(),
-            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0)
                 .finished(),
             /*noisify=*/false,
             /*disturb=*/true,
@@ -564,14 +589,16 @@
         LocalizerTestParams({
             /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
             /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
-            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0)
                 .finished(),
-            (TestLocalizer::State() << 0.1, -5.1, 0.03, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.1, -5.1, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0)
                 .finished(),
             /*noisify=*/true,
             /*disturb=*/true,
             /*estimate_tolerance=*/0.15,
-            /*goal_tolerance=*/0.8,
+            /*goal_tolerance=*/0.5,
         }),
         // Try another spline, just in case the one I was using is special for
         // some reason; this path will also go straight up to a target, to
@@ -579,14 +606,16 @@
         LocalizerTestParams({
             /*control_pts_x=*/{{0.5, 3.5, 4.0, 8.0, 11.0, 10.2}},
             /*control_pts_y=*/{{1.0, 1.0, -3.0, -2.0, -3.5, -3.65}},
-            (TestLocalizer::State() << 0.6, 1.01, 0.01, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.6, 1.01, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0)
                 .finished(),
-            (TestLocalizer::State() << 0.5, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0)
+            (TestLocalizer::State() << 0.5, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
+             0.0, 0.0)
                 .finished(),
             /*noisify=*/true,
             /*disturb=*/false,
-            /*estimate_tolerance=*/0.15,
-            /*goal_tolerance=*/0.5,
+            /*estimate_tolerance=*/0.25,
+            /*goal_tolerance=*/0.7,
         })));
 
 }  // namespace testing
diff --git a/y2019/control_loops/drivetrain/target_selector.cc b/y2019/control_loops/drivetrain/target_selector.cc
index 449ce64..7b6918a 100644
--- a/y2019/control_loops/drivetrain/target_selector.cc
+++ b/y2019/control_loops/drivetrain/target_selector.cc
@@ -5,17 +5,35 @@
 
 constexpr double TargetSelector::kFakeFov;
 
-TargetSelector::TargetSelector()
+TargetSelector::TargetSelector(::aos::EventLoop *event_loop)
     : front_viewer_({&robot_pose_, {0.0, 0.0, 0.0}, 0.0}, kFakeFov, fake_noise_,
                     constants::Field().targets(), {}),
       back_viewer_({&robot_pose_, {0.0, 0.0, 0.0}, M_PI}, kFakeFov, fake_noise_,
-                   constants::Field().targets(), {}) {}
+                   constants::Field().targets(), {}),
+      hint_fetcher_(event_loop->MakeFetcher<drivetrain::TargetSelectorHint>(
+          ".y2019.control_loops.drivetrain.target_selector_hint")),
+      superstructure_goal_fetcher_(event_loop->MakeFetcher<
+          superstructure::SuperstructureQueue::Goal>(
+          ".y2019.control_loops.superstructure.superstructure_queue.goal")) {}
 
 bool TargetSelector::UpdateSelection(const ::Eigen::Matrix<double, 5, 1> &state,
                                      double command_speed) {
   if (::std::abs(command_speed) < kMinDecisionSpeed) {
     return false;
   }
+  if (superstructure_goal_fetcher_.Fetch()) {
+    ball_mode_ = superstructure_goal_fetcher_->suction.gamepiece_mode == 0;
+  }
+  if (hint_fetcher_.Fetch()) {
+    LOG_STRUCT(DEBUG, "selector_hint", *hint_fetcher_);
+    // suggested_target is unsigned so we don't check for >= 0.
+    if (hint_fetcher_->suggested_target < 4) {
+      target_hint_ =
+          static_cast<SelectionHint>(hint_fetcher_->suggested_target);
+    } else {
+      LOG(ERROR, "Got invalid suggested target.\n");
+    }
+  }
   *robot_pose_.mutable_pos() << state.x(), state.y(), 0.0;
   robot_pose_.set_theta(state(2, 0));
   ::aos::SizedArray<FakeCamera::TargetView,
@@ -36,8 +54,41 @@
   // means the largest target in the camera view).
   double largest_target_noise = ::std::numeric_limits<double>::infinity();
   for (const auto &view : target_views) {
+    // Skip targets that aren't viable for going to (e.g., on the opposite side
+    // of the field).
+    // TODO(james): Support ball vs. hatch mode filtering.
+    if (view.target->goal_type() == Target::GoalType::kNone ||
+        view.target->goal_type() == (ball_mode_ ? Target::GoalType::kHatches
+                                                : Target::GoalType::kBalls)) {
+      continue;
+    }
+    switch (target_hint_) {
+      case SelectionHint::kNearShip:
+        if (view.target->target_type() !=
+            Target::TargetType::kNearSideCargoBay) {
+          continue;
+        }
+        break;
+      case SelectionHint::kMidShip:
+        if (view.target->target_type() !=
+            Target::TargetType::kMidSideCargoBay) {
+          continue;
+        }
+        break;
+      case SelectionHint::kFarShip:
+        if (view.target->target_type() !=
+            Target::TargetType::kFarSideCargoBay) {
+          continue;
+        }
+        break;
+      case SelectionHint::kNone:
+      default:
+        break;
+    }
     if (view.noise.distance < largest_target_noise) {
       target_pose_ = view.target->pose();
+      // If we are in ball mode, use a radius of zero.
+      target_radius_ = ball_mode_ ? 0.0 : view.target->radius();
       largest_target_noise = view.noise.distance;
     }
   }
diff --git a/y2019/control_loops/drivetrain/target_selector.h b/y2019/control_loops/drivetrain/target_selector.h
index 965d7cc..4c001ad 100644
--- a/y2019/control_loops/drivetrain/target_selector.h
+++ b/y2019/control_loops/drivetrain/target_selector.h
@@ -5,6 +5,8 @@
 #include "frc971/control_loops/drivetrain/localizer.h"
 #include "y2019/constants.h"
 #include "y2019/control_loops/drivetrain/camera.h"
+#include "y2019/control_loops/drivetrain/target_selector.q.h"
+#include "y2019/control_loops/superstructure/superstructure.q.h"
 
 namespace y2019 {
 namespace control_loops {
@@ -27,12 +29,23 @@
   typedef TypedCamera<y2019::constants::Field::kNumTargets,
                       /*num_obstacles=*/0, double> FakeCamera;
 
-  TargetSelector();
+  enum class SelectionHint {
+    // No hint
+    kNone = 0,
+    // Cargo ship bays
+    kNearShip = 1,
+    kMidShip = 2,
+    kFarShip = 3,
+  };
+
+  TargetSelector(::aos::EventLoop *event_loop);
 
   bool UpdateSelection(const ::Eigen::Matrix<double, 5, 1> &state,
                        double command_speed) override;
   Pose TargetPose() const override { return target_pose_; }
 
+  double TargetRadius() const override { return target_radius_; }
+
  private:
   static constexpr double kFakeFov = M_PI * 0.7;
   // Longitudinal speed at which the robot must be going in order for us to make
@@ -40,6 +53,7 @@
   static constexpr double kMinDecisionSpeed = 0.7;  // m/s
   Pose robot_pose_;
   Pose target_pose_;
+  double target_radius_;
   // For the noise of our fake cameras, we only really care about the max
   // distance, which will be the maximum distance we let ourselves guide in
   // from. The distance noise is set so that we can use the camera's estimate of
@@ -51,6 +65,14 @@
                                              .nominal_height_noise = 0};
   FakeCamera front_viewer_;
   FakeCamera back_viewer_;
+
+  ::aos::Fetcher<drivetrain::TargetSelectorHint> hint_fetcher_;
+  ::aos::Fetcher<superstructure::SuperstructureQueue::Goal>
+      superstructure_goal_fetcher_;
+
+  // Whether we are currently in ball mode.
+  bool ball_mode_ = false;
+  SelectionHint target_hint_ = SelectionHint::kNone;
 };
 
 }  // namespace control_loops
diff --git a/y2019/control_loops/drivetrain/target_selector.q b/y2019/control_loops/drivetrain/target_selector.q
new file mode 100644
index 0000000..c917d39
--- /dev/null
+++ b/y2019/control_loops/drivetrain/target_selector.q
@@ -0,0 +1,12 @@
+package y2019.control_loops.drivetrain;
+
+// A message to provide information to the target selector about what it should
+message TargetSelectorHint {
+  // Which target we should go for:
+  // 0 implies no selection, we should just default to whatever.
+  // 1, 2, and 3 imply the near, middle, and far targets.
+  // These should match the SelectionHint enum in target_selector.h.
+  uint8_t suggested_target;
+};
+
+queue TargetSelectorHint target_selector_hint;
diff --git a/y2019/control_loops/drivetrain/target_selector_test.cc b/y2019/control_loops/drivetrain/target_selector_test.cc
index 4b440c2..aa655e6 100644
--- a/y2019/control_loops/drivetrain/target_selector_test.cc
+++ b/y2019/control_loops/drivetrain/target_selector_test.cc
@@ -1,6 +1,8 @@
 #include "y2019/control_loops/drivetrain/target_selector.h"
 
+#include "aos/testing/test_shm.h"
 #include "gtest/gtest.h"
+#include "y2019/control_loops/superstructure/superstructure.q.h"
 
 namespace y2019 {
 namespace control_loops {
@@ -8,12 +10,15 @@
 
 typedef ::frc971::control_loops::TypedPose<double> Pose;
 typedef ::Eigen::Matrix<double, 5, 1> State;
+using SelectionHint = TargetSelector::SelectionHint;
 
 namespace {
 // Accessors to get some useful particular targets on the field:
 Pose HPSlotLeft() { return constants::Field().targets()[7].pose(); }
 Pose CargoNearLeft() { return constants::Field().targets()[2].pose(); }
-Pose RocketPortalLeft() { return constants::Field().targets()[4].pose(); }
+Pose RocketHatchFarLeft() { return constants::Field().targets()[6].pose(); }
+Pose RocketPortal() { return constants::Field().targets()[4].pose(); }
+double HatchRadius() { return constants::Field().targets()[6].radius(); }
 }  // namespace
 
 // Tests the target selector with:
@@ -23,14 +28,40 @@
 // -If (1) is true, the pose we expect to get back.
 struct TestParams {
   State state;
+  bool ball_mode;
+  SelectionHint selection_hint;
   double command_speed;
   bool expect_target;
   Pose expected_pose;
+  double expected_radius;
 };
-class TargetSelectorParamTest : public ::testing::TestWithParam<TestParams> {};
+class TargetSelectorParamTest : public ::testing::TestWithParam<TestParams> {
+ protected:
+  virtual void TearDown() override {
+    ::y2019::control_loops::superstructure::superstructure_queue.goal.Clear();
+    ::y2019::control_loops::drivetrain::target_selector_hint.Clear();
+  }
+  ::aos::ShmEventLoop event_loop_;
+
+ private:
+  ::aos::testing::TestSharedMemory my_shm_;
+};
 
 TEST_P(TargetSelectorParamTest, ExpectReturn) {
-  TargetSelector selector;
+  TargetSelector selector(&event_loop_);
+  {
+    auto super_goal =
+        ::y2019::control_loops::superstructure::superstructure_queue.goal
+            .MakeMessage();
+    super_goal->suction.gamepiece_mode = GetParam().ball_mode ? 0 : 1;
+    ASSERT_TRUE(super_goal.Send());
+  }
+  {
+    auto hint =
+        ::y2019::control_loops::drivetrain::target_selector_hint.MakeMessage();
+    hint->suggested_target = static_cast<int>(GetParam().selection_hint);
+    ASSERT_TRUE(hint.Send());
+  }
   bool expect_target = GetParam().expect_target;
   const State state = GetParam().state;
   ASSERT_EQ(expect_target,
@@ -49,6 +80,8 @@
         << " but got " << actual_pos.transpose() << " with the robot at "
         << state.transpose();
     EXPECT_EQ(expected_angle, actual_angle);
+    EXPECT_EQ(GetParam().expected_radius, selector.TargetRadius());
+    EXPECT_EQ(expected_angle, actual_angle);
   }
 }
 
@@ -57,42 +90,82 @@
     ::testing::Values(
         // When we are far away from anything, we should not register any
         // targets:
-        TestParams{
-            (State() << 0.0, 0.0, 0.0, 1.0, 1.0).finished(), 1.0, false, {}},
+        TestParams{(State() << 0.0, 0.0, 0.0, 1.0, 1.0).finished(),
+                   /*ball_mode=*/false,
+                   SelectionHint::kNone,
+                   1.0,
+                   false,
+                   {},
+                   /*expected_radius=*/0.0},
         // Aim for a human-player spot; at low speeds we should not register
         // anything.
         TestParams{(State() << 4.0, 2.0, M_PI, 0.05, 0.05).finished(),
+                   /*ball_mode=*/false,
+                   SelectionHint::kNone,
                    0.05,
                    false,
-                   {}},
+                   {},
+                   /*expected_radius=*/0.0},
         TestParams{(State() << 4.0, 2.0, M_PI, -0.05, -0.05).finished(),
+                   /*ball_mode=*/false,
+                   SelectionHint::kNone,
                    -0.05,
                    false,
-                   {}},
-        TestParams{(State() << 4.0, 2.0, M_PI, 0.5, 0.5).finished(), 1.0, true,
-                   HPSlotLeft()},
+                   {},
+                   /*expected_radius=*/0.0},
+        TestParams{(State() << 4.0, 2.0, M_PI, 0.5, 0.5).finished(),
+                   /*ball_mode=*/false, SelectionHint::kNone, 1.0, true,
+                   HPSlotLeft(), /*expected_radius=*/0.0},
         // Put ourselves between the rocket and cargo ship; we should see the
-        // portal driving one direction and the near cargo ship port the other.
+        // hatches driving one direction and the near cargo ship port the other.
         // We also command a speed opposite the current direction of motion and
         // confirm that that behaves as expected.
-        TestParams{(State() << 6.0, 2.0, -M_PI_2, -0.5, -0.5).finished(), 1.0,
-                   true, CargoNearLeft()},
-        TestParams{(State() << 6.0, 2.0, M_PI_2, 0.5, 0.5).finished(), -1.0,
-                   true, CargoNearLeft()},
-        TestParams{(State() << 6.0, 2.0, -M_PI_2, 0.5, 0.5).finished(), -1.0,
-                   true, RocketPortalLeft()},
-        TestParams{(State() << 6.0, 2.0, M_PI_2, -0.5, -0.5).finished(), 1.0,
-                   true, RocketPortalLeft()},
+        TestParams{(State() << 6.0, 2.0, -M_PI_2, -0.5, -0.5).finished(),
+                   /*ball_mode=*/false, SelectionHint::kNone, 1.0, true,
+                   CargoNearLeft(), /*expected_radius=*/HatchRadius()},
+        TestParams{(State() << 6.0, 2.0, M_PI_2, 0.5, 0.5).finished(),
+                   /*ball_mode=*/false, SelectionHint::kNone, -1.0, true,
+                   CargoNearLeft(), /*expected_radius=*/HatchRadius()},
+        TestParams{(State() << 6.0, 2.0, -M_PI_2, 0.5, 0.5).finished(),
+                   /*ball_mode=*/false, SelectionHint::kNone, -1.0, true,
+                   RocketHatchFarLeft(), /*expected_radius=*/HatchRadius()},
+        TestParams{(State() << 6.0, 2.0, M_PI_2, -0.5, -0.5).finished(),
+                   /*ball_mode=*/false, SelectionHint::kNone, 1.0, true,
+                   RocketHatchFarLeft(), /*expected_radius=*/HatchRadius()},
         // And we shouldn't see anything spinning in place:
         TestParams{(State() << 6.0, 2.0, M_PI_2, -0.5, 0.5).finished(),
+                   /*ball_mode=*/false,
+                   SelectionHint::kNone,
                    0.0,
                    false,
-                   {}},
+                   {},
+                   /*expected_radius=*/0.0},
         // Drive backwards off the field--we should not see anything.
         TestParams{(State() << -0.1, 0.0, 0.0, -0.5, -0.5).finished(),
+                   /*ball_mode=*/false,
+                   SelectionHint::kNone,
                    -1.0,
                    false,
-                   {}}));
+                   {},
+                   /*expected_radius=*/0.0},
+        // In ball mode, we should be able to see the portal, and get zero
+        // radius.
+        TestParams{(State() << 6.0, 2.0, M_PI_2, 0.5, 0.5).finished(),
+                   /*ball_mode=*/true,
+                   SelectionHint::kNone,
+                   1.0,
+                   true,
+                   RocketPortal(),
+                   /*expected_radius=*/0.0},
+        // Reversing direction should get cargo ship with zero radius.
+        TestParams{(State() << 6.0, 2.0, M_PI_2, 0.5, 0.5).finished(),
+                   /*ball_mode=*/true,
+                   SelectionHint::kNone,
+                   -1.0,
+                   true,
+                   CargoNearLeft(),
+                   /*expected_radius=*/0.0}
+                   ));
 
 }  // namespace testing
 }  // namespace control_loops
diff --git a/y2019/control_loops/python/drivetrain.py b/y2019/control_loops/python/drivetrain.py
index e2d6eec..4a68fde 100644
--- a/y2019/control_loops/python/drivetrain.py
+++ b/y2019/control_loops/python/drivetrain.py
@@ -25,7 +25,7 @@
     wheel_radius=4.0 * 0.0254 / 2.0,
     G=9.0 / 52.0,
     q_pos=0.14,
-    q_vel=0.95,
+    q_vel=1.30,
     efficiency=0.80,
     has_imu=True,
     force=True,
diff --git a/y2019/control_loops/superstructure/BUILD b/y2019/control_loops/superstructure/BUILD
index 524a1ba..87afdfa 100644
--- a/y2019/control_loops/superstructure/BUILD
+++ b/y2019/control_loops/superstructure/BUILD
@@ -27,6 +27,7 @@
         ":superstructure_queue",
         ":vacuum",
         "//aos/controls:control_loop",
+        "//frc971/control_loops/drivetrain:drivetrain_queue",
         "//y2019:constants",
         "//y2019:status_light",
     ],
@@ -48,6 +49,7 @@
         "//frc971/control_loops:capped_test_plant",
         "//frc971/control_loops:position_sensor_sim",
         "//frc971/control_loops:team_number_test_environment",
+        "//frc971/control_loops/drivetrain:drivetrain_queue",
         "//y2019:status_light",
         "//y2019/control_loops/superstructure/intake:intake_plants",
     ],
diff --git a/y2019/control_loops/superstructure/collision_avoidance.h b/y2019/control_loops/superstructure/collision_avoidance.h
index 7fc80cd..90a45f6 100644
--- a/y2019/control_loops/superstructure/collision_avoidance.h
+++ b/y2019/control_loops/superstructure/collision_avoidance.h
@@ -60,7 +60,7 @@
 
   // Angle constraints for the wrist when below kElevatorClearDownHeight
   static constexpr double kWristMaxAngle = M_PI / 2.0 + 0.05;
-  static constexpr double kWristMinAngle = -M_PI / 2.0 - 0.05;
+  static constexpr double kWristMinAngle = -M_PI / 2.0 - 0.25;
 
   // Angles outside of which the intake is fully clear of the wrist.
   static constexpr double kIntakeOutAngle = 0.3;
diff --git a/y2019/control_loops/superstructure/superstructure.cc b/y2019/control_loops/superstructure/superstructure.cc
index dd332b8..8fe02a3 100644
--- a/y2019/control_loops/superstructure/superstructure.cc
+++ b/y2019/control_loops/superstructure/superstructure.cc
@@ -2,6 +2,7 @@
 
 #include "aos/controls/control_loops.q.h"
 #include "frc971/control_loops/control_loops.q.h"
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
 #include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
 
 #include "y2019/status_light.q.h"
@@ -92,19 +93,54 @@
   intake_.set_min_position(collision_avoidance_.min_intake_goal());
   intake_.set_max_position(collision_avoidance_.max_intake_goal());
 
+  ::frc971::control_loops::drivetrain_queue.status.FetchLatest();
+
   if (status && unsafe_goal) {
     // Light Logic
     if (status->estopped) {
       // Estop is red
-      SendColors(0.5, 0.0, 0.0);
-    } else if (unsafe_goal->suction.gamepiece_mode == 0) {
-      // Ball mode is blue
-      SendColors(0.0, 0.0, 0.5);
-    } else if (unsafe_goal->suction.gamepiece_mode == 1) {
-      // Disk mode is yellow
-      SendColors(0.5, 0.5, 0.0);
+      SendColors(1.0, 0.0, 0.0);
+    } else if (::frc971::control_loops::drivetrain_queue.status.get() &&
+               ::frc971::control_loops::drivetrain_queue.status
+                   ->line_follow_logging.frozen) {
+      // Vision align is flashing white for button pressed, purple for target
+      // acquired.
+      ++line_blink_count_;
+      if (line_blink_count_ < 20) {
+        if (::frc971::control_loops::drivetrain_queue.status
+                ->line_follow_logging.have_target) {
+          SendColors(1.0, 0.0, 1.0);
+        } else {
+          SendColors(1.0, 1.0, 1.0);
+        }
+      } else {
+        // And then flash with green if we have a game piece.
+        if (status->has_piece) {
+          SendColors(0.0, 1.0, 0.0);
+        } else {
+          SendColors(0.0, 0.0, 0.0);
+        }
+      }
+
+      if (line_blink_count_ > 40) {
+        line_blink_count_ = 0;
+      }
     } else {
-      SendColors(0.0, 0.0, 0.0);
+      line_blink_count_ = 0;
+      if (status->has_piece) {
+        // Green if we have a game piece.
+        SendColors(0.0, 1.0, 0.0);
+      } else if (unsafe_goal->suction.gamepiece_mode == 0 &&
+                 !status->has_piece) {
+        // Ball mode is orange
+        SendColors(1.0, 0.1, 0.0);
+      } else if (unsafe_goal->suction.gamepiece_mode == 1 &&
+                 !status->has_piece) {
+        // Disk mode is deep blue
+        SendColors(0.05, 0.1, 0.5);
+      } else {
+        SendColors(0.0, 0.0, 0.0);
+      }
     }
   }
 }
diff --git a/y2019/control_loops/superstructure/superstructure.h b/y2019/control_loops/superstructure/superstructure.h
index 626c84b..2df9026 100644
--- a/y2019/control_loops/superstructure/superstructure.h
+++ b/y2019/control_loops/superstructure/superstructure.h
@@ -50,6 +50,8 @@
 
   CollisionAvoidance collision_avoidance_;
 
+  int line_blink_count_ = 0;
+
   static constexpr double kMinIntakeAngleForRollers = -0.7;
 
   DISALLOW_COPY_AND_ASSIGN(Superstructure);
diff --git a/y2019/control_loops/superstructure/superstructure_lib_test.cc b/y2019/control_loops/superstructure/superstructure_lib_test.cc
index 4d3de51..dd327ee 100644
--- a/y2019/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2019/control_loops/superstructure/superstructure_lib_test.cc
@@ -6,16 +6,17 @@
 #include "aos/controls/control_loop_test.h"
 #include "aos/queue.h"
 #include "frc971/control_loops/capped_test_plant.h"
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
 #include "frc971/control_loops/position_sensor_sim.h"
 #include "frc971/control_loops/team_number_test_environment.h"
 #include "gtest/gtest.h"
 #include "y2019/constants.h"
-#include "y2019/status_light.q.h"
 #include "y2019/control_loops/superstructure/elevator/elevator_plant.h"
 #include "y2019/control_loops/superstructure/intake/intake_plant.h"
 #include "y2019/control_loops/superstructure/stilts/stilts_plant.h"
 #include "y2019/control_loops/superstructure/superstructure.h"
 #include "y2019/control_loops/superstructure/wrist/wrist_plant.h"
+#include "y2019/status_light.q.h"
 
 namespace y2019 {
 namespace control_loops {
@@ -290,6 +291,7 @@
             "position"),
         superstructure_(&event_loop_) {
     status_light.Clear();
+    ::frc971::control_loops::drivetrain_queue.status.Clear();
     set_team_id(::frc971::control_loops::testing::kTeamNumber);
   }
 
diff --git a/y2019/image_streamer/flip_image.cc b/y2019/image_streamer/flip_image.cc
index 6ff00ed..2db20b2 100644
--- a/y2019/image_streamer/flip_image.cc
+++ b/y2019/image_streamer/flip_image.cc
@@ -6,10 +6,12 @@
 #include "third_party/cimg/CImg.h"
 
 void flip_image(const char *input, const int input_size, JOCTET *buffer,
-                unsigned int *buffer_size) {
+                unsigned int *buffer_size, bool flip) {
   ::cimg_library::CImg<unsigned char> image;
   image.load_jpeg_buffer((JOCTET *)(input), input_size);
-  image.mirror("xy");
+  if (flip) {
+    image.mirror("xy");
+  }
 
   image.save_jpeg_buffer(buffer, *buffer_size, 80);
 }
diff --git a/y2019/image_streamer/flip_image.h b/y2019/image_streamer/flip_image.h
index 6a59e96..7c31774 100644
--- a/y2019/image_streamer/flip_image.h
+++ b/y2019/image_streamer/flip_image.h
@@ -7,6 +7,6 @@
 #include "third_party/libjpeg/jpeglib.h"
 
 void flip_image(const char *input, const int input_size, JOCTET *buffer,
-                unsigned int *buffer_size);
+                unsigned int *buffer_size, bool flip_image);
 
 #endif  // Y2019_IMAGE_STREAMER_FLIP_IMAGE_H
diff --git a/y2019/image_streamer/image_streamer.cc b/y2019/image_streamer/image_streamer.cc
index ed581e2..ebcd0b2 100644
--- a/y2019/image_streamer/image_streamer.cc
+++ b/y2019/image_streamer/image_streamer.cc
@@ -280,15 +280,12 @@
       sampling = 0;
     }
 
-    std::string image_out;
+    ::std::string image_out;
 
-    if (flip_) {
-      unsigned int out_size = image_buffer_out_.size();
-      flip_image(data.data(), data.size(), &image_buffer_out_[0], &out_size);
-      image_out.assign(&image_buffer_out_[0], &image_buffer_out_[out_size]);
-    } else {
-      image_out = std::string(data);
-    }
+    unsigned int out_size = image_buffer_out_.size();
+    flip_image(data.data(), data.size(), &image_buffer_out_[0], &out_size,
+               flip_);
+    image_out.assign(&image_buffer_out_[0], &image_buffer_out_[out_size]);
 
     if (active_) {
       auto frame = std::make_shared<Frame>(Frame{image_out});
diff --git a/y2019/joystick_reader.cc b/y2019/joystick_reader.cc
index c4a1caf..7b714be 100644
--- a/y2019/joystick_reader.cc
+++ b/y2019/joystick_reader.cc
@@ -22,11 +22,13 @@
 #include "frc971/control_loops/drivetrain/localizer.q.h"
 
 #include "y2019/control_loops/drivetrain/drivetrain_base.h"
+#include "y2019/control_loops/drivetrain/target_selector.q.h"
 #include "y2019/control_loops/superstructure/superstructure.q.h"
 #include "y2019/status_light.q.h"
 #include "y2019/vision.pb.h"
 
 using ::y2019::control_loops::superstructure::superstructure_queue;
+using ::y2019::control_loops::drivetrain::target_selector_hint;
 using ::frc971::control_loops::drivetrain::localizer_control;
 using ::aos::input::driver_station::ButtonLocation;
 using ::aos::input::driver_station::ControlBit;
@@ -34,6 +36,8 @@
 using ::aos::input::driver_station::POVLocation;
 using ::aos::events::ProtoTXUdpSocket;
 
+namespace chrono = ::std::chrono;
+
 namespace y2019 {
 namespace input {
 namespace joysticks {
@@ -74,18 +78,21 @@
 const ButtonLocation kPanelHPIntakeBackward(5, 5);
 
 const ButtonLocation kRelease(2, 4);
-const ButtonLocation kResetLocalizer(4, 3);
+const ButtonLocation kResetLocalizerLeftForwards(3, 14);
+const ButtonLocation kResetLocalizerLeftBackwards(4, 12);
 
-const ButtonLocation kAutoPanel(3, 10);
-const ButtonLocation kAutoPanelIntermediate(4, 6);
+const ButtonLocation kResetLocalizerRightForwards(4, 1);
+const ButtonLocation kResetLocalizerRightBackwards(4, 11);
 
-const ElevatorWristPosition kAutoPanelPos{0.0, -M_PI / 2.0};
-const ElevatorWristPosition kAutoPanelIntermediatePos{0.34, -M_PI / 2.0};
+const ButtonLocation kNearCargoHint(3, 15);
+const ButtonLocation kMidCargoHint(3, 16);
+const ButtonLocation kFarCargoHint(4, 2);
 
 const ElevatorWristPosition kStowPos{0.36, 0.0};
+const ElevatorWristPosition kClimbPos{0.0, M_PI / 4.0};
 
-const ElevatorWristPosition kPanelHPIntakeForwrdPos{0.04, M_PI / 2.0};
-const ElevatorWristPosition kPanelHPIntakeBackwardPos{0.05, -M_PI / 2.0};
+const ElevatorWristPosition kPanelHPIntakeForwrdPos{0.01, M_PI / 2.0};
+const ElevatorWristPosition kPanelHPIntakeBackwardPos{0.015, -M_PI / 2.0};
 
 const ElevatorWristPosition kPanelForwardLowerPos{0.0, M_PI / 2.0};
 const ElevatorWristPosition kPanelBackwardLowerPos{0.0, -M_PI / 2.0};
@@ -99,17 +106,17 @@
 const ElevatorWristPosition kPanelCargoForwardPos{0.0, M_PI / 2.0};
 const ElevatorWristPosition kPanelCargoBackwardPos{0.0, -M_PI / 2.0};
 
-const ElevatorWristPosition kBallForwardLowerPos{0.46, M_PI / 2.0};
-const ElevatorWristPosition kBallBackwardLowerPos{0.15, -M_PI / 2.0};
+const ElevatorWristPosition kBallForwardLowerPos{0.42, M_PI / 2.0};
+const ElevatorWristPosition kBallBackwardLowerPos{0.14, -M_PI / 2.0};
 
 const ElevatorWristPosition kBallForwardMiddlePos{1.16, 1.546};
-const ElevatorWristPosition kBallBackwardMiddlePos{0.876021, -1.546};
+const ElevatorWristPosition kBallBackwardMiddlePos{0.90, -1.546};
 
-const ElevatorWristPosition kBallForwardUpperPos{1.50, 0.961};
-const ElevatorWristPosition kBallBackwardUpperPos{1.41, -1.217};
+const ElevatorWristPosition kBallForwardUpperPos{1.51, 0.961};
+const ElevatorWristPosition kBallBackwardUpperPos{1.44, -1.217};
 
-const ElevatorWristPosition kBallCargoForwardPos{0.699044, 1.353};
-const ElevatorWristPosition kBallCargoBackwardPos{0.828265, -1.999};
+const ElevatorWristPosition kBallCargoForwardPos{0.739044, 1.353};
+const ElevatorWristPosition kBallCargoBackwardPos{0.868265, -1.999};
 
 const ElevatorWristPosition kBallHPIntakeForwardPos{0.55, 1.097};
 const ElevatorWristPosition kBallHPIntakeBackwardPos{0.89, -2.018};
@@ -122,16 +129,28 @@
       : ::aos::input::ActionJoystickInput(
             event_loop,
             ::y2019::control_loops::drivetrain::GetDrivetrainConfig()) {
+    // Set teleop to immediately resume after auto ends for sandstorm mode.
+    set_run_teleop_in_auto(true);
+
     const uint16_t team = ::aos::network::GetTeamNumber();
     superstructure_queue.goal.FetchLatest();
     if (superstructure_queue.goal.get()) {
       grab_piece_ = superstructure_queue.goal->suction.grab_piece;
+      switch_ball_ = superstructure_queue.goal->suction.gamepiece_mode == 0;
     }
     video_tx_.reset(new ProtoTXUdpSocket<VisionControl>(
         StringPrintf("10.%d.%d.179", team / 100, team % 100), 5000));
   }
 
-  void HandleTeleop(const ::aos::input::driver_station::Data &data) {
+  void AutoEnded() override {
+    LOG(INFO, "Auto ended, assuming disc and have piece\n");
+    grab_piece_ = true;
+    switch_ball_ = false;
+  }
+
+  void HandleTeleop(const ::aos::input::driver_station::Data &data) override {
+    ::aos::monotonic_clock::time_point monotonic_now =
+        ::aos::monotonic_clock::now();
     superstructure_queue.position.FetchLatest();
     superstructure_queue.status.FetchLatest();
     if (!superstructure_queue.status.get() ||
@@ -140,13 +159,71 @@
       return;
     }
 
+    if (!superstructure_queue.status->has_piece) {
+      last_not_has_piece_ = monotonic_now;
+    }
+
     auto new_superstructure_goal = superstructure_queue.goal.MakeMessage();
 
-    if (data.PosEdge(kResetLocalizer)) {
+    {
+      auto target_hint = target_selector_hint.MakeMessage();
+      if (data.IsPressed(kNearCargoHint)) {
+        target_hint->suggested_target = 1;
+      } else if (data.IsPressed(kMidCargoHint)) {
+        target_hint->suggested_target = 2;
+      } else if (data.IsPressed(kFarCargoHint)) {
+        target_hint->suggested_target = 3;
+      } else {
+        target_hint->suggested_target = 0;
+      }
+      if (!target_hint.Send()) {
+        LOG(ERROR, "Failed to send target selector hint.\n");
+      }
+    }
+
+    if (data.PosEdge(kResetLocalizerLeftForwards)) {
       auto localizer_resetter = localizer_control.MakeMessage();
+      // Start at the left feeder station.
       localizer_resetter->x = 0.4;
       localizer_resetter->y = 3.4;
       localizer_resetter->theta = 0.0;
+
+      if (!localizer_resetter.Send()) {
+        LOG(ERROR, "Failed to reset localizer.\n");
+      }
+    }
+
+    if (data.PosEdge(kResetLocalizerLeftBackwards)) {
+      auto localizer_resetter = localizer_control.MakeMessage();
+      // Start at the left feeder station.
+      localizer_resetter->x = 0.4;
+      localizer_resetter->y = 3.4;
+      localizer_resetter->theta = M_PI;
+
+      if (!localizer_resetter.Send()) {
+        LOG(ERROR, "Failed to reset localizer.\n");
+      }
+    }
+
+    if (data.PosEdge(kResetLocalizerRightForwards)) {
+      auto localizer_resetter = localizer_control.MakeMessage();
+      // Start at the right feeder station.
+      localizer_resetter->x = 0.4;
+      localizer_resetter->y = -3.4;
+      localizer_resetter->theta = 0.0;
+
+      if (!localizer_resetter.Send()) {
+        LOG(ERROR, "Failed to reset localizer.\n");
+      }
+    }
+
+    if (data.PosEdge(kResetLocalizerRightBackwards)) {
+      auto localizer_resetter = localizer_control.MakeMessage();
+      // Start at the right feeder station.
+      localizer_resetter->x = 0.4;
+      localizer_resetter->y = -3.4;
+      localizer_resetter->theta = M_PI;
+
       if (!localizer_resetter.Send()) {
         LOG(ERROR, "Failed to reset localizer.\n");
       }
@@ -176,41 +253,6 @@
       switch_ball_ = true;
     }
 
-    // TODO(sabina): max height please?
-    if (data.IsPressed(kFallOver)) {
-      new_superstructure_goal->stilts.unsafe_goal = 0.71;
-      new_superstructure_goal->stilts.profile_params.max_velocity = 0.65;
-      new_superstructure_goal->stilts.profile_params.max_acceleration = 2.0;
-    } else if (data.IsPressed(kDeployStilt)) {
-      new_superstructure_goal->stilts.unsafe_goal = 0.50;
-      new_superstructure_goal->stilts.profile_params.max_velocity = 0.65;
-      if (stilts_was_above_) {
-        new_superstructure_goal->stilts.profile_params.max_acceleration = 0.75;
-      } else {
-        new_superstructure_goal->stilts.profile_params.max_acceleration = 2.0;
-      }
-    } else if (data.IsPressed(kHalfStilt)) {
-      new_superstructure_goal->stilts.unsafe_goal = 0.345;
-      new_superstructure_goal->stilts.profile_params.max_velocity = 0.65;
-      new_superstructure_goal->stilts.profile_params.max_acceleration = 0.75;
-    } else {
-      new_superstructure_goal->stilts.unsafe_goal = 0.005;
-      new_superstructure_goal->stilts.profile_params.max_velocity = 0.25;
-      new_superstructure_goal->stilts.profile_params.max_acceleration = 2.0;
-    }
-
-    if (superstructure_queue.status->stilts.position > 0.65) {
-      stilts_was_above_ = true;
-    } else if (superstructure_queue.status->stilts.position < 0.1) {
-      stilts_was_above_ = false;
-    }
-
-    if (data.IsPressed(kAutoPanel)) {
-      elevator_wrist_pos_ = kAutoPanelPos;
-    } else if (data.IsPressed(kAutoPanelIntermediate)) {
-      elevator_wrist_pos_ = kAutoPanelIntermediatePos;
-    }
-
     if (switch_ball_) {
       if (superstructure_queue.status->has_piece) {
         new_superstructure_goal->wrist.profile_params.max_acceleration = 20;
@@ -276,7 +318,8 @@
 
     if (switch_ball_) {
       if (kDoBallOutake ||
-          (kDoBallIntake && !superstructure_queue.status->has_piece)) {
+          (kDoBallIntake &&
+           monotonic_now < last_not_has_piece_ + chrono::milliseconds(100))) {
         new_superstructure_goal->intake.unsafe_goal = 0.959327;
       }
 
@@ -288,12 +331,42 @@
         if (kDoBallOutake) {
           new_superstructure_goal->roller_voltage = -6.0;
         } else {
-          new_superstructure_goal->intake.unsafe_goal = -1.2;
           new_superstructure_goal->roller_voltage = 0.0;
         }
       }
     }
 
+    constexpr double kDeployStiltPosition = 0.5;
+
+    // TODO(sabina): max height please?
+    if (data.IsPressed(kFallOver)) {
+      new_superstructure_goal->stilts.unsafe_goal = 0.71;
+      new_superstructure_goal->stilts.profile_params.max_velocity = 0.65;
+      new_superstructure_goal->stilts.profile_params.max_acceleration = 1.25;
+    } else if (data.IsPressed(kDeployStilt)) {
+      new_superstructure_goal->stilts.unsafe_goal = kDeployStiltPosition;
+      new_superstructure_goal->stilts.profile_params.max_velocity = 0.65;
+      new_superstructure_goal->stilts.profile_params.max_acceleration = 2.0;
+    } else if (data.IsPressed(kHalfStilt)) {
+      new_superstructure_goal->stilts.unsafe_goal = 0.345;
+      new_superstructure_goal->stilts.profile_params.max_velocity = 0.65;
+    } else {
+      new_superstructure_goal->stilts.unsafe_goal = 0.005;
+      new_superstructure_goal->stilts.profile_params.max_velocity = 0.65;
+      new_superstructure_goal->stilts.profile_params.max_acceleration = 2.0;
+    }
+
+    if (superstructure_queue.status->stilts.position > 0.3) {
+      elevator_wrist_pos_ = kClimbPos;
+    }
+
+    if (superstructure_queue.status->stilts.position > kDeployStiltPosition &&
+        new_superstructure_goal->stilts.unsafe_goal == kDeployStiltPosition) {
+      new_superstructure_goal->stilts.profile_params.max_velocity = 0.30;
+      new_superstructure_goal->stilts.profile_params.max_acceleration = 0.75;
+    }
+
+
     if (data.IsPressed(kRelease)) {
       grab_piece_ = false;
     }
@@ -317,10 +390,10 @@
       LOG(ERROR, "Sending superstructure goal failed.\n");
     }
 
-    auto time_now = ::aos::monotonic_clock::now();
-    if (time_now > last_vision_control_ + ::std::chrono::milliseconds(50)) {
+    if (monotonic_now >
+        last_vision_control_ + ::std::chrono::milliseconds(50)) {
       video_tx_->Send(vision_control_);
-      last_vision_control_ = time_now;
+      last_vision_control_ = monotonic_now;
     }
   }
 
@@ -330,12 +403,15 @@
   bool grab_piece_ = false;
 
   bool switch_ball_ = false;
-  bool stilts_was_above_ = false;
 
   VisionControl vision_control_;
   ::std::unique_ptr<ProtoTXUdpSocket<VisionControl>> video_tx_;
   ::aos::monotonic_clock::time_point last_vision_control_ =
       ::aos::monotonic_clock::time_point::min();
+
+  // Time at which we last did not have a game piece.
+  ::aos::monotonic_clock::time_point last_not_has_piece_ =
+      ::aos::monotonic_clock::time_point::min();
 };
 
 }  // namespace joysticks
diff --git a/y2019/vision/BUILD b/y2019/vision/BUILD
index 5cfc52b..344e4da 100644
--- a/y2019/vision/BUILD
+++ b/y2019/vision/BUILD
@@ -60,6 +60,7 @@
     restricted_to = VISION_TARGETS,
     deps = [
         ":constants",
+        "//aos/util:math",
         "//aos/vision/blob:contour",
         "//aos/vision/blob:hierarchical_contour_merge",
         "//aos/vision/blob:region_alloc",
diff --git a/y2019/vision/calibrate_9971.sh b/y2019/vision/calibrate_9971.sh
index 9a05ce2..5951059 100755
--- a/y2019/vision/calibrate_9971.sh
+++ b/y2019/vision/calibrate_9971.sh
@@ -17,7 +17,7 @@
 calibration \
     --camera_id 1 \
     --tape_start_x=-12.5 \
-    --tape_start_y=0.0 \
+    --tape_start_y=-1.0 \
     --tape_direction_x=-1.0 \
     --tape_direction_y=0.0 \
     --beginning_tape_measure_reading=16 \
diff --git a/y2019/vision/constants.cc b/y2019/vision/constants.cc
index 310faf6..36694f8 100644
--- a/y2019/vision/constants.cc
+++ b/y2019/vision/constants.cc
@@ -7,16 +7,16 @@
 
 CameraCalibration camera_1 = {
     {
-        -0.873939 / 180.0 * M_PI, 338.976, 2.44587 / 180.0 * M_PI,
+        -1.01208 / 180.0 * M_PI, 342.679, 1.79649 / 180.0 * M_PI,
     },
     {
-        {{-5.46283 * kInchesToMeters, 2.98951 * kInchesToMeters,
-          33.0848 * kInchesToMeters}},
-        181.951 / 180.0 * M_PI,
+        {{-5.08996 * kInchesToMeters, 1.82468 * kInchesToMeters,
+          33.2047 * kInchesToMeters}},
+        -178.111 / 180.0 * M_PI,
     },
     {
         1,
-        {{-12.5 * kInchesToMeters, 0.0}},
+        {{-12.5 * kInchesToMeters, -1 * kInchesToMeters}},
         {{-1 * kInchesToMeters, 0.0}},
         16,
         "/home/alex/cam1/debug_viewer_jpeg_",
diff --git a/y2019/vision/constants.h b/y2019/vision/constants.h
index faa16e1..b61bff7 100644
--- a/y2019/vision/constants.h
+++ b/y2019/vision/constants.h
@@ -82,6 +82,7 @@
 // Serial number of the teensy for each robot.
 constexpr uint32_t CodeBotTeensyId() { return 0xffff322e; }
 constexpr uint32_t PracticeBotTeensyId() { return 0xffff3215; }
+constexpr uint32_t CompBotTeensyId() { return 0xffff3210; }
 
 // Get the IDs of the cameras in each port for a particular teensy board.
 // inlined so that we don't have to deal with including it in the autogenerated
@@ -92,6 +93,8 @@
       return {{0, 0, 0, 16, 19}};
     case PracticeBotTeensyId():
       return {{14, 15, 18, 17, 1}};
+    case CompBotTeensyId():
+      return {{6, 7, 8, 9, 10}};
     default:
       return {{0, 0, 0, 0, 0}};
   }
diff --git a/y2019/vision/server/BUILD b/y2019/vision/server/BUILD
new file mode 100644
index 0000000..180b41e
--- /dev/null
+++ b/y2019/vision/server/BUILD
@@ -0,0 +1,50 @@
+load("//aos/seasocks:gen_embedded.bzl", "gen_embedded")
+load("//aos/downloader:downloader.bzl", "aos_downloader_dir")
+load("@build_bazel_rules_typescript//:defs.bzl", "ts_library")
+load("@build_bazel_rules_nodejs//:defs.bzl", "rollup_bundle")
+
+ts_library(
+    name = "demo",
+    srcs = [
+        "demo.ts",
+    ],
+)
+
+gen_embedded(
+    name = "gen_embedded",
+    srcs = glob(
+        include = ["www_defaults/**/*"],
+        exclude = ["www/**/*"],
+    ),
+)
+
+aos_downloader_dir(
+    name = "www_files",
+    srcs = [
+        "//y2019/vision/server/www:visualizer_bundle",
+        "//y2019/vision/server/www:files",
+    ],
+    dir = "www",
+    visibility = ["//visibility:public"],
+)
+
+cc_binary(
+    name = "server",
+    srcs = [
+        "server.cc",
+    ],
+    data = [
+        "//y2019/vision/server/www:visualizer_bundle",
+        "//y2019/vision/server/www:files",
+    ],
+    visibility = ["//visibility:public"],
+    deps = [
+        ":gen_embedded",
+        "//aos:init",
+        "//aos/logging",
+        "//aos/time",
+        "//frc971/control_loops/drivetrain:drivetrain_queue",
+        "//third_party/seasocks",
+        "//y2019/control_loops/drivetrain:camera_queue",
+    ],
+)
diff --git a/y2019/vision/server/demo.ts b/y2019/vision/server/demo.ts
new file mode 100644
index 0000000..b310758
--- /dev/null
+++ b/y2019/vision/server/demo.ts
@@ -0,0 +1,5 @@
+declare var foo: number;
+
+foo = 5;
+
+console.log("Half the number of widgets is " + (foo / 2));
diff --git a/y2019/vision/server/server.cc b/y2019/vision/server/server.cc
new file mode 100644
index 0000000..54eb399
--- /dev/null
+++ b/y2019/vision/server/server.cc
@@ -0,0 +1,214 @@
+#include <sys/stat.h>
+#include <sys/types.h>
+#include <unistd.h>
+#include <array>
+#include <memory>
+#include <set>
+#include <sstream>
+
+#include "aos/init.h"
+#include "aos/logging/logging.h"
+#include "aos/time/time.h"
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+#include "internal/Embedded.h"
+#include "seasocks/PrintfLogger.h"
+#include "seasocks/Server.h"
+#include "seasocks/StringUtil.h"
+#include "seasocks/WebSocket.h"
+#include "y2019/control_loops/drivetrain/camera.q.h"
+
+namespace y2019 {
+namespace vision {
+
+class WebsocketHandler : public seasocks::WebSocket::Handler {
+ public:
+  WebsocketHandler();
+  void onConnect(seasocks::WebSocket* connection) override;
+  void onData(seasocks::WebSocket* connection, const char* data) override;
+  void onDisconnect(seasocks::WebSocket* connection) override;
+
+  void SendData(const std::string &data);
+
+ private:
+  std::set<seasocks::WebSocket *> connections_;
+};
+
+WebsocketHandler::WebsocketHandler() {
+}
+
+void WebsocketHandler::onConnect(seasocks::WebSocket *connection) {
+  connections_.insert(connection);
+  LOG(INFO, "Connected: %s : %s\n", connection->getRequestUri().c_str(),
+      seasocks::formatAddress(connection->getRemoteAddress()).c_str());
+}
+
+void WebsocketHandler::onData(seasocks::WebSocket * /*connection*/,
+                              const char *data) {
+  LOG(INFO, "Got data: %s\n", data);
+}
+
+void WebsocketHandler::onDisconnect(seasocks::WebSocket *connection) {
+  connections_.erase(connection);
+  LOG(INFO, "Disconnected: %s : %s\n", connection->getRequestUri().c_str(),
+      seasocks::formatAddress(connection->getRemoteAddress()).c_str());
+}
+
+void WebsocketHandler::SendData(const std::string &data) {
+  for (seasocks::WebSocket *websocket : connections_) {
+    websocket->send(reinterpret_cast<const uint8_t *>(data.data()),
+                    data.size());
+  }
+}
+
+// TODO(Brian): Put this somewhere shared.
+class SeasocksLogger : public seasocks::PrintfLogger {
+ public:
+  SeasocksLogger(Level min_level_to_log) : PrintfLogger(min_level_to_log) {}
+  void log(Level level, const char* message) override;
+};
+
+void SeasocksLogger::log(Level level, const char *message) {
+  // Convert Seasocks error codes to AOS.
+  log_level aos_level;
+  switch (level) {
+    case seasocks::Logger::INFO:
+      aos_level = INFO;
+      break;
+    case seasocks::Logger::WARNING:
+      aos_level = WARNING;
+      break;
+    case seasocks::Logger::ERROR:
+    case seasocks::Logger::SEVERE:
+      aos_level = ERROR;
+      break;
+    case seasocks::Logger::DEBUG:
+    case seasocks::Logger::ACCESS:
+    default:
+      aos_level = DEBUG;
+      break;
+  }
+  LOG(aos_level, "Seasocks: %s\n", message);
+}
+
+struct LocalCameraTarget {
+  double x, y, theta;
+};
+
+struct LocalCameraFrame {
+  aos::monotonic_clock::time_point capture_time =
+      aos::monotonic_clock::min_time;
+  std::vector<LocalCameraTarget> targets;
+
+  bool IsValid(aos::monotonic_clock::time_point now) {
+    return capture_time + std::chrono::seconds(1) > now;
+  }
+};
+
+// Sends a new chunk of data to all the websocket clients.
+class UpdateData : public seasocks::Server::Runnable {
+ public:
+  UpdateData(WebsocketHandler *websocket_handler, std::string &&data)
+      : websocket_handler_(websocket_handler), data_(std::move(data)) {}
+  ~UpdateData() override = default;
+  UpdateData(const UpdateData &) = delete;
+  UpdateData &operator=(const UpdateData &) = delete;
+
+  void run() override { websocket_handler_->SendData(data_); }
+
+ private:
+  WebsocketHandler *const websocket_handler_;
+  const std::string data_;
+};
+
+void DataThread(seasocks::Server *server, WebsocketHandler *websocket_handler) {
+  auto &camera_frames = y2019::control_loops::drivetrain::camera_frames;
+  auto &drivetrain_status = frc971::control_loops::drivetrain_queue.status;
+
+  std::array<LocalCameraFrame, 5> latest_frames;
+  aos::monotonic_clock::time_point last_send_time = aos::monotonic_clock::now();
+
+  while (true) {
+    camera_frames.FetchNextBlocking();
+    drivetrain_status.FetchLatest();
+    if (!drivetrain_status.get()) {
+      // Try again if we don't have any drivetrain statuses.
+      continue;
+    }
+
+    {
+      const auto &new_frame = *camera_frames;
+      if (new_frame.camera < latest_frames.size()) {
+        latest_frames[new_frame.camera].capture_time =
+            aos::monotonic_clock::time_point(
+                std::chrono::nanoseconds(new_frame.timestamp));
+        latest_frames[new_frame.camera].targets.clear();
+        for (int target = 0; target < new_frame.num_targets; ++target) {
+          latest_frames[new_frame.camera].targets.emplace_back();
+          // TODO: Do something useful.
+        }
+      }
+    }
+
+    const auto now = aos::monotonic_clock::now();
+    if (now > last_send_time + std::chrono::milliseconds(100)) {
+      last_send_time = now;
+      std::ostringstream stream;
+      stream << "{\n";
+
+      stream << "\"robot\": {";
+      stream << "\"x\": " << drivetrain_status->x << ",";
+      stream << "\"y\": " << drivetrain_status->y << ",";
+      stream << "\"theta\": " << drivetrain_status->theta;
+      stream << "}\n";
+      stream << ",\"target\": {";
+      stream << "\"x\": " << drivetrain_status->line_follow_logging.x << ",";
+      stream << "\"y\": " << drivetrain_status->line_follow_logging.y << ",";
+      stream << "\"theta\": " << drivetrain_status->line_follow_logging.theta
+             << ",";
+      stream << "\"frozen\": " << drivetrain_status->line_follow_logging.frozen
+             << ",";
+      stream << "\"have_target\": "
+             << drivetrain_status->line_follow_logging.have_target;
+      stream << "} ";
+
+      stream << "}";
+      server->execute(
+          std::make_shared<UpdateData>(websocket_handler, stream.str()));
+    }
+  }
+}
+
+}  // namespace vision
+}  // namespace y2019
+
+int main(int, char *[]) {
+  // Make sure to reference this to force the linker to include it.
+  findEmbeddedContent("");
+
+  aos::InitNRT();
+
+  seasocks::Server server(::std::shared_ptr<seasocks::Logger>(
+      new y2019::vision::SeasocksLogger(seasocks::Logger::INFO)));
+
+  auto websocket_handler = std::make_shared<y2019::vision::WebsocketHandler>();
+  server.addWebSocketHandler("/ws", websocket_handler);
+
+  std::thread data_thread{[&server, websocket_handler]() {
+    y2019::vision::DataThread(&server, websocket_handler.get());
+  }};
+
+  // See if we are on a robot.  If so, serve the robot www folder.
+  bool serve_www = false;
+  {
+    struct stat result;
+    if (stat("/home/admin/robot_code/www", &result) == 0) {
+      serve_www = true;
+    }
+  }
+
+  server.serve(
+      serve_www ? "/home/admin/robot_code/www" : "y2019/vision/server/www",
+      1180);
+
+  return 0;
+}
diff --git a/y2019/vision/server/www/BUILD b/y2019/vision/server/www/BUILD
new file mode 100644
index 0000000..937b495
--- /dev/null
+++ b/y2019/vision/server/www/BUILD
@@ -0,0 +1,26 @@
+load("@build_bazel_rules_typescript//:defs.bzl", "ts_library")
+load("@build_bazel_rules_nodejs//:defs.bzl", "rollup_bundle")
+
+package(default_visibility = ["//visibility:public"])
+
+filegroup(
+    name = "files",
+    srcs = glob([
+        "**/*",
+    ]),
+)
+
+ts_library(
+    name = "visualizer",
+    srcs = glob([
+        "*.ts",
+    ]),
+)
+
+rollup_bundle(
+    name = "visualizer_bundle",
+    entry_point = "y2019/vision/server/www/main",
+    deps = [
+        ":visualizer",
+    ],
+)
diff --git a/y2019/vision/server/www/constants.ts b/y2019/vision/server/www/constants.ts
new file mode 100644
index 0000000..6180df1
--- /dev/null
+++ b/y2019/vision/server/www/constants.ts
@@ -0,0 +1,5 @@
+// Conversion constants to meters
+export const IN_TO_M = 0.0254;
+export const FT_TO_M = 0.3048;
+// Width of the field in meters
+export const FIELD_WIDTH = 27 * FT_TO_M;
diff --git a/y2019/vision/server/www/field.ts b/y2019/vision/server/www/field.ts
new file mode 100644
index 0000000..8cb1282
--- /dev/null
+++ b/y2019/vision/server/www/field.ts
@@ -0,0 +1,94 @@
+import {IN_TO_M, FT_TO_M} from './constants';
+
+const CENTER_FIELD_X = 27 * FT_TO_M + 1.125 * IN_TO_M;
+
+const FAR_CARGO_X = CENTER_FIELD_X - 20.875 * IN_TO_M;
+const MID_CARGO_X = FAR_CARGO_X - 21.75 * IN_TO_M;
+const NEAR_CARGO_X = MID_CARGO_X - 21.75 * IN_TO_M;
+const SIDE_CARGO_Y = (24 + 3 + 0.875) * IN_TO_M;
+const SIDE_CARGO_THETA = -Math.PI / 2;
+
+const FACE_CARGO_X = CENTER_FIELD_X - (7 * 12 + 11.75 + 9) * IN_TO_M;
+const FACE_CARGO_Y = (10.875) * IN_TO_M;
+const FACE_CARGO_THETA = 0;
+
+const ROCKET_X = CENTER_FIELD_X - 8 * FT_TO_M;
+const ROCKET_Y = (26 * 12 + 10.5) / 2.0 * IN_TO_M;
+
+const ROCKET_PORT_X = ROCKET_X;
+const ROCKET_PORT_Y = ROCKET_Y - 0.7;
+const ROCKET_PORT_THETA = Math.PI / 2;
+
+const ROCKET_HATCH_X_OFFSET = 14.634 * IN_TO_M;
+const ROCKET_HATCH_Y = ROCKET_PORT_Y + 9.326 * IN_TO_M;
+const ROCKET_NEAR_X = ROCKET_X - ROCKET_HATCH_X_OFFSET;
+const ROCKET_FAR_X = ROCKET_X + ROCKET_HATCH_X_OFFSET;
+const ROCKET_NEAR_THETA = -28.5 * 180 / Math.PI;
+const ROCKET_FAR_THETA = Math.PI - ROCKET_NEAR_THETA;
+
+const HP_Y = ((26 * 12 + 10.5) / 2 - 25.9) * IN_TO_M;
+const HP_THETA = Math.PI;
+
+export function drawField(ctx : CanvasRenderingContext2D) : void {
+  drawTargets(ctx);
+}
+
+function drawHab(ctx : CanvasRenderingContext2D) : void {
+  ctx.fillstyle = 'rgb(100,100,100)';
+  const habLeft = 5 * FT_TO_M;
+  const habWidth = 5 * FT_TO_M;
+  const habTop = -5 * FT_TO_M;
+  const habHeight = 10 * FT_TO_M;
+  ctx.fillRect(habLeft,habTop,habWidth,habHeight);
+}
+
+function drawTargets(ctx : CanvasRenderingContext2D) : void {
+  drawHalfCargo(ctx);
+  drawRocket(ctx);
+  drawHP(ctx);
+  ctx.save();
+
+  ctx.scale(1, -1);
+  drawHalfCargo(ctx);
+  drawRocket(ctx);
+  drawHP(ctx);
+
+  ctx.restore();
+}
+
+function drawHP(ctx : CanvasRenderingContext2D) : void {
+  drawTarget(ctx, 0, HP_Y, HP_THETA);
+}
+
+function drawRocket(ctx : CanvasRenderingContext2D) : void {
+  drawTarget(ctx, ROCKET_PORT_X, ROCKET_PORT_Y, ROCKET_PORT_THETA);
+
+  drawTarget(ctx, ROCKET_NEAR_X, ROCKET_HATCH_Y, ROCKET_NEAR_THETA);
+
+  drawTarget(ctx, ROCKET_FAR_X, ROCKET_HATCH_Y, ROCKET_FAR_THETA);
+}
+
+function drawHalfCargo(ctx : CanvasRenderingContext2D) : void {
+  drawTarget(ctx, FAR_CARGO_X, SIDE_CARGO_Y, SIDE_CARGO_THETA);
+
+  drawTarget(ctx, MID_CARGO_X, SIDE_CARGO_Y, SIDE_CARGO_THETA);
+
+  drawTarget(ctx, NEAR_CARGO_X, SIDE_CARGO_Y, SIDE_CARGO_THETA);
+
+  drawTarget(ctx, FACE_CARGO_X, FACE_CARGO_Y, FACE_CARGO_THETA);
+}
+
+export function drawTarget(ctx : CanvasRenderingContext2D, x: number, y: number, theta: number) : void {
+  ctx.save();
+  ctx.translate(x, y);
+  ctx.rotate(theta);
+
+  ctx.beginPath();
+  ctx.moveTo(0, -0.15);
+  ctx.lineTo(0, 0.15);
+  ctx.moveTo(0, 0);
+  ctx.lineTo(-0.15, 0);
+  ctx.stroke();
+
+  ctx.restore();
+}
diff --git a/y2019/vision/server/www/index.html b/y2019/vision/server/www/index.html
new file mode 100644
index 0000000..4e6e316
--- /dev/null
+++ b/y2019/vision/server/www/index.html
@@ -0,0 +1,10 @@
+<!doctype html>
+<html>
+  <head>
+    <title>Vision Debug Server</title>
+  </head>
+  <body style="overflow:hidden">
+    <canvas id="field" style="border: 1px solid"></canvas>
+  </body>
+  <script src="visualizer_bundle.min.js"></script>
+</html>
diff --git a/y2019/vision/server/www/main.ts b/y2019/vision/server/www/main.ts
new file mode 100644
index 0000000..8dc0ea9
--- /dev/null
+++ b/y2019/vision/server/www/main.ts
@@ -0,0 +1,81 @@
+import {FT_TO_M, FIELD_WIDTH} from './constants';
+import {drawField, drawTarget} from './field';
+import {drawRobot} from './robot';
+
+const FIELD_WIDTH = 27 * FT_TO_M;
+
+function main(): void {
+  const vis = new Visualiser();
+}
+
+class Visualiser {
+  private x = 3;
+  private y = 0;
+  private theta = 0;
+
+  private drawLocked = false;
+  private lockedX = 0;
+  private lockedY = 0;
+  private lockedTheta = 0;
+
+  constructor() {
+    const canvas = <HTMLCanvasElement>document.getElementById('field');
+    const ctx = canvas.getContext('2d');
+
+    const server = location.host;
+    const socket = new WebSocket(`ws://${server}/ws`);
+    const reader = new FileReader();
+    reader.addEventListener('loadend', (e) => {
+      const text = e.srcElement.result;
+      const j = JSON.parse(text);
+      this.x = j.robot.x;
+      this.y = j.robot.y;
+      this.theta = j.robot.theta;
+
+      if(j.target) {
+        this.targetLocked = j.target.frozen && j.target.have_target;
+        this.targetX = j.target.x;
+        this.targetY = j.target.y;
+        this.targetTheta = j.target.theta;
+      }
+    });
+    socket.addEventListener('message', (event) => {
+      reader.readAsText(event.data);
+    });
+    window.requestAnimationFrame(() => this.draw(ctx));
+  }
+
+  reset(ctx : CanvasRenderingContext2D) : void {
+    ctx.setTransform(1,0,0,1,0,0);
+    const size = Math.min(window.innerHeight, window.innerWidth) * 0.98;
+    ctx.canvas.height = size;
+    ctx.canvas.width = size;
+    ctx.clearRect(0,0,size,size);
+
+    ctx.translate(size/2, size);
+    ctx.rotate(-Math.PI / 2);
+    ctx.scale(1, -1);
+    const M_TO_PX = size / FIELD_WIDTH
+    ctx.scale(M_TO_PX, M_TO_PX);
+    ctx.lineWidth = 1 / M_TO_PX;
+  }
+
+  draw(ctx : CanvasRenderingContext2D) : void {
+    this.reset(ctx);
+
+    drawField(ctx);
+    drawRobot(ctx, this.x, this.y, this.theta);
+    ctx.save();
+    ctx.lineWidth = 2.0 * ctx.lineWidth;
+    if (this.targetLocked) {
+      ctx.strokeStyle = 'blue';
+    } else {
+      ctx.strokeStyle = 'red';
+    }
+    drawTarget(ctx, this.targetX, this.targetY, this.targetTheta);
+    ctx.restore();
+    window.requestAnimationFrame(() => this.draw(ctx));
+  }
+}
+
+main();
diff --git a/y2019/vision/server/www/robot.ts b/y2019/vision/server/www/robot.ts
new file mode 100644
index 0000000..bc1f47f
--- /dev/null
+++ b/y2019/vision/server/www/robot.ts
@@ -0,0 +1,21 @@
+import {IN_TO_M, FT_TO_M} from './constants';
+
+const ROBOT_WIDTH = 25 * IN_TO_M;
+const ROBOT_LENGTH = 31 * IN_TO_M;
+
+export function drawRobot(ctx : CanvasRenderingContext2D, x : number, y : number, theta : number) : void {
+  ctx.save();
+  ctx.translate(x, y);
+  ctx.rotate(theta);
+
+  ctx.fillStyle = 'blue';
+  ctx.fillRect(-ROBOT_LENGTH / 2, -ROBOT_WIDTH / 2, ROBOT_LENGTH, ROBOT_WIDTH);
+
+  ctx.moveTo(ROBOT_LENGTH / 2, -ROBOT_WIDTH/2);
+  ctx.lineTo(ROBOT_LENGTH / 2 + 0.1, 0);
+  ctx.lineTo(ROBOT_LENGTH / 2, ROBOT_WIDTH/2);
+  ctx.closePath();
+  ctx.stroke();
+
+  ctx.restore();
+}
diff --git a/y2019/vision/server/www_defaults/_404.png b/y2019/vision/server/www_defaults/_404.png
new file mode 100644
index 0000000..8a43cb8
--- /dev/null
+++ b/y2019/vision/server/www_defaults/_404.png
Binary files differ
diff --git a/y2019/vision/server/www_defaults/_error.css b/y2019/vision/server/www_defaults/_error.css
new file mode 100644
index 0000000..8238d6d
--- /dev/null
+++ b/y2019/vision/server/www_defaults/_error.css
@@ -0,0 +1,33 @@
+body {
+    font-family: segoe ui, tahoma, arial, sans-serif;
+    color: #ffffff;
+    background-color: #c21e29;
+    text-align: center;
+}
+
+a {
+    color: #ffff00;
+}
+
+.footer {
+    font-style: italic;
+}
+
+.message {
+    display: inline-block;
+    border: 1px solid white;
+    padding: 50px;
+    font-size: 20px;
+}
+
+.headline {
+    padding: 50px;
+    font-weight: bold;
+    font-size: 32px;
+}
+
+.footer {
+    padding-top: 50px;
+    font-size: 12px;
+}
+
diff --git a/y2019/vision/server/www_defaults/_error.html b/y2019/vision/server/www_defaults/_error.html
new file mode 100644
index 0000000..ecf5e32
--- /dev/null
+++ b/y2019/vision/server/www_defaults/_error.html
@@ -0,0 +1,15 @@
+<html DOCTYPE=html>
+<head>
+  <title>%%ERRORCODE%% - %%MESSAGE%% - Keep Calm And Carry On!</title>
+  <link href="/_error.css" rel="stylesheet">
+</head>
+<body>
+  <div class="message">
+    <img src="/_404.png" height="200" width="107">
+    <div class="headline">%%ERRORCODE%% &#8212; %%MESSAGE%%</div>
+    <div class="info">%%BODY%%</div>
+  </div>
+
+  <div class="footer">Powered by <a href="https://github.com/mattgodbolt/seasocks">SeaSocks</a></div>
+</body>
+</html>
diff --git a/y2019/vision/server/www_defaults/_jquery.min.js b/y2019/vision/server/www_defaults/_jquery.min.js
new file mode 100644
index 0000000..f78f96a
--- /dev/null
+++ b/y2019/vision/server/www_defaults/_jquery.min.js
@@ -0,0 +1,16 @@
+/*!
+ * jQuery JavaScript Library v1.5.2
+ * http://jquery.com/
+ *
+ * Copyright 2011, John Resig
+ * Dual licensed under the MIT or GPL Version 2 licenses.
+ * http://jquery.org/license
+ *
+ * Includes Sizzle.js
+ * http://sizzlejs.com/
+ * Copyright 2011, The Dojo Foundation
+ * Released under the MIT, BSD, and GPL Licenses.
+ *
+ * Date: Thu Mar 31 15:28:23 2011 -0400
+ */
+(function(a,b){function ci(a){return d.isWindow(a)?a:a.nodeType===9?a.defaultView||a.parentWindow:!1}function cf(a){if(!b_[a]){var b=d("<"+a+">").appendTo("body"),c=b.css("display");b.remove();if(c==="none"||c==="")c="block";b_[a]=c}return b_[a]}function ce(a,b){var c={};d.each(cd.concat.apply([],cd.slice(0,b)),function(){c[this]=a});return c}function b$(){try{return new a.ActiveXObject("Microsoft.XMLHTTP")}catch(b){}}function bZ(){try{return new a.XMLHttpRequest}catch(b){}}function bY(){d(a).unload(function(){for(var a in bW)bW[a](0,1)})}function bS(a,c){a.dataFilter&&(c=a.dataFilter(c,a.dataType));var e=a.dataTypes,f={},g,h,i=e.length,j,k=e[0],l,m,n,o,p;for(g=1;g<i;g++){if(g===1)for(h in a.converters)typeof h==="string"&&(f[h.toLowerCase()]=a.converters[h]);l=k,k=e[g];if(k==="*")k=l;else if(l!=="*"&&l!==k){m=l+" "+k,n=f[m]||f["* "+k];if(!n){p=b;for(o in f){j=o.split(" ");if(j[0]===l||j[0]==="*"){p=f[j[1]+" "+k];if(p){o=f[o],o===!0?n=p:p===!0&&(n=o);break}}}}!n&&!p&&d.error("No conversion from "+m.replace(" "," to ")),n!==!0&&(c=n?n(c):p(o(c)))}}return c}function bR(a,c,d){var e=a.contents,f=a.dataTypes,g=a.responseFields,h,i,j,k;for(i in g)i in d&&(c[g[i]]=d[i]);while(f[0]==="*")f.shift(),h===b&&(h=a.mimeType||c.getResponseHeader("content-type"));if(h)for(i in e)if(e[i]&&e[i].test(h)){f.unshift(i);break}if(f[0]in d)j=f[0];else{for(i in d){if(!f[0]||a.converters[i+" "+f[0]]){j=i;break}k||(k=i)}j=j||k}if(j){j!==f[0]&&f.unshift(j);return d[j]}}function bQ(a,b,c,e){if(d.isArray(b)&&b.length)d.each(b,function(b,f){c||bs.test(a)?e(a,f):bQ(a+"["+(typeof f==="object"||d.isArray(f)?b:"")+"]",f,c,e)});else if(c||b==null||typeof b!=="object")e(a,b);else if(d.isArray(b)||d.isEmptyObject(b))e(a,"");else for(var f in b)bQ(a+"["+f+"]",b[f],c,e)}function bP(a,c,d,e,f,g){f=f||c.dataTypes[0],g=g||{},g[f]=!0;var h=a[f],i=0,j=h?h.length:0,k=a===bJ,l;for(;i<j&&(k||!l);i++)l=h[i](c,d,e),typeof l==="string"&&(!k||g[l]?l=b:(c.dataTypes.unshift(l),l=bP(a,c,d,e,l,g)));(k||!l)&&!g["*"]&&(l=bP(a,c,d,e,"*",g));return l}function bO(a){return function(b,c){typeof b!=="string"&&(c=b,b="*");if(d.isFunction(c)){var e=b.toLowerCase().split(bD),f=0,g=e.length,h,i,j;for(;f<g;f++)h=e[f],j=/^\+/.test(h),j&&(h=h.substr(1)||"*"),i=a[h]=a[h]||[],i[j?"unshift":"push"](c)}}}function bq(a,b,c){var e=b==="width"?bk:bl,f=b==="width"?a.offsetWidth:a.offsetHeight;if(c==="border")return f;d.each(e,function(){c||(f-=parseFloat(d.css(a,"padding"+this))||0),c==="margin"?f+=parseFloat(d.css(a,"margin"+this))||0:f-=parseFloat(d.css(a,"border"+this+"Width"))||0});return f}function bc(a,b){b.src?d.ajax({url:b.src,async:!1,dataType:"script"}):d.globalEval(b.text||b.textContent||b.innerHTML||""),b.parentNode&&b.parentNode.removeChild(b)}function bb(a){return"getElementsByTagName"in a?a.getElementsByTagName("*"):"querySelectorAll"in a?a.querySelectorAll("*"):[]}function ba(a,b){if(b.nodeType===1){var c=b.nodeName.toLowerCase();b.clearAttributes(),b.mergeAttributes(a);if(c==="object")b.outerHTML=a.outerHTML;else if(c!=="input"||a.type!=="checkbox"&&a.type!=="radio"){if(c==="option")b.selected=a.defaultSelected;else if(c==="input"||c==="textarea")b.defaultValue=a.defaultValue}else a.checked&&(b.defaultChecked=b.checked=a.checked),b.value!==a.value&&(b.value=a.value);b.removeAttribute(d.expando)}}function _(a,b){if(b.nodeType===1&&d.hasData(a)){var c=d.expando,e=d.data(a),f=d.data(b,e);if(e=e[c]){var g=e.events;f=f[c]=d.extend({},e);if(g){delete f.handle,f.events={};for(var h in g)for(var i=0,j=g[h].length;i<j;i++)d.event.add(b,h+(g[h][i].namespace?".":"")+g[h][i].namespace,g[h][i],g[h][i].data)}}}}function $(a,b){return d.nodeName(a,"table")?a.getElementsByTagName("tbody")[0]||a.appendChild(a.ownerDocument.createElement("tbody")):a}function Q(a,b,c){if(d.isFunction(b))return d.grep(a,function(a,d){var e=!!b.call(a,d,a);return e===c});if(b.nodeType)return d.grep(a,function(a,d){return a===b===c});if(typeof b==="string"){var e=d.grep(a,function(a){return a.nodeType===1});if(L.test(b))return d.filter(b,e,!c);b=d.filter(b,e)}return d.grep(a,function(a,e){return d.inArray(a,b)>=0===c})}function P(a){return!a||!a.parentNode||a.parentNode.nodeType===11}function H(a,b){return(a&&a!=="*"?a+".":"")+b.replace(t,"`").replace(u,"&")}function G(a){var b,c,e,f,g,h,i,j,k,l,m,n,o,p=[],q=[],s=d._data(this,"events");if(a.liveFired!==this&&s&&s.live&&!a.target.disabled&&(!a.button||a.type!=="click")){a.namespace&&(n=new RegExp("(^|\\.)"+a.namespace.split(".").join("\\.(?:.*\\.)?")+"(\\.|$)")),a.liveFired=this;var t=s.live.slice(0);for(i=0;i<t.length;i++)g=t[i],g.origType.replace(r,"")===a.type?q.push(g.selector):t.splice(i--,1);f=d(a.target).closest(q,a.currentTarget);for(j=0,k=f.length;j<k;j++){m=f[j];for(i=0;i<t.length;i++){g=t[i];if(m.selector===g.selector&&(!n||n.test(g.namespace))&&!m.elem.disabled){h=m.elem,e=null;if(g.preType==="mouseenter"||g.preType==="mouseleave")a.type=g.preType,e=d(a.relatedTarget).closest(g.selector)[0];(!e||e!==h)&&p.push({elem:h,handleObj:g,level:m.level})}}}for(j=0,k=p.length;j<k;j++){f=p[j];if(c&&f.level>c)break;a.currentTarget=f.elem,a.data=f.handleObj.data,a.handleObj=f.handleObj,o=f.handleObj.origHandler.apply(f.elem,arguments);if(o===!1||a.isPropagationStopped()){c=f.level,o===!1&&(b=!1);if(a.isImmediatePropagationStopped())break}}return b}}function E(a,c,e){var f=d.extend({},e[0]);f.type=a,f.originalEvent={},f.liveFired=b,d.event.handle.call(c,f),f.isDefaultPrevented()&&e[0].preventDefault()}function y(){return!0}function x(){return!1}function i(a){for(var b in a)if(b!=="toJSON")return!1;return!0}function h(a,c,e){if(e===b&&a.nodeType===1){e=a.getAttribute("data-"+c);if(typeof e==="string"){try{e=e==="true"?!0:e==="false"?!1:e==="null"?null:d.isNaN(e)?g.test(e)?d.parseJSON(e):e:parseFloat(e)}catch(f){}d.data(a,c,e)}else e=b}return e}var c=a.document,d=function(){function G(){if(!d.isReady){try{c.documentElement.doScroll("left")}catch(a){setTimeout(G,1);return}d.ready()}}var d=function(a,b){return new d.fn.init(a,b,g)},e=a.jQuery,f=a.$,g,h=/^(?:[^<]*(<[\w\W]+>)[^>]*$|#([\w\-]+)$)/,i=/\S/,j=/^\s+/,k=/\s+$/,l=/\d/,m=/^<(\w+)\s*\/?>(?:<\/\1>)?$/,n=/^[\],:{}\s]*$/,o=/\\(?:["\\\/bfnrt]|u[0-9a-fA-F]{4})/g,p=/"[^"\\\n\r]*"|true|false|null|-?\d+(?:\.\d*)?(?:[eE][+\-]?\d+)?/g,q=/(?:^|:|,)(?:\s*\[)+/g,r=/(webkit)[ \/]([\w.]+)/,s=/(opera)(?:.*version)?[ \/]([\w.]+)/,t=/(msie) ([\w.]+)/,u=/(mozilla)(?:.*? rv:([\w.]+))?/,v=navigator.userAgent,w,x,y,z=Object.prototype.toString,A=Object.prototype.hasOwnProperty,B=Array.prototype.push,C=Array.prototype.slice,D=String.prototype.trim,E=Array.prototype.indexOf,F={};d.fn=d.prototype={constructor:d,init:function(a,e,f){var g,i,j,k;if(!a)return this;if(a.nodeType){this.context=this[0]=a,this.length=1;return this}if(a==="body"&&!e&&c.body){this.context=c,this[0]=c.body,this.selector="body",this.length=1;return this}if(typeof a==="string"){g=h.exec(a);if(!g||!g[1]&&e)return!e||e.jquery?(e||f).find(a):this.constructor(e).find(a);if(g[1]){e=e instanceof d?e[0]:e,k=e?e.ownerDocument||e:c,j=m.exec(a),j?d.isPlainObject(e)?(a=[c.createElement(j[1])],d.fn.attr.call(a,e,!0)):a=[k.createElement(j[1])]:(j=d.buildFragment([g[1]],[k]),a=(j.cacheable?d.clone(j.fragment):j.fragment).childNodes);return d.merge(this,a)}i=c.getElementById(g[2]);if(i&&i.parentNode){if(i.id!==g[2])return f.find(a);this.length=1,this[0]=i}this.context=c,this.selector=a;return this}if(d.isFunction(a))return f.ready(a);a.selector!==b&&(this.selector=a.selector,this.context=a.context);return d.makeArray(a,this)},selector:"",jquery:"1.5.2",length:0,size:function(){return this.length},toArray:function(){return C.call(this,0)},get:function(a){return a==null?this.toArray():a<0?this[this.length+a]:this[a]},pushStack:function(a,b,c){var e=this.constructor();d.isArray(a)?B.apply(e,a):d.merge(e,a),e.prevObject=this,e.context=this.context,b==="find"?e.selector=this.selector+(this.selector?" ":"")+c:b&&(e.selector=this.selector+"."+b+"("+c+")");return e},each:function(a,b){return d.each(this,a,b)},ready:function(a){d.bindReady(),x.done(a);return this},eq:function(a){return a===-1?this.slice(a):this.slice(a,+a+1)},first:function(){return this.eq(0)},last:function(){return this.eq(-1)},slice:function(){return this.pushStack(C.apply(this,arguments),"slice",C.call(arguments).join(","))},map:function(a){return this.pushStack(d.map(this,function(b,c){return a.call(b,c,b)}))},end:function(){return this.prevObject||this.constructor(null)},push:B,sort:[].sort,splice:[].splice},d.fn.init.prototype=d.fn,d.extend=d.fn.extend=function(){var a,c,e,f,g,h,i=arguments[0]||{},j=1,k=arguments.length,l=!1;typeof i==="boolean"&&(l=i,i=arguments[1]||{},j=2),typeof i!=="object"&&!d.isFunction(i)&&(i={}),k===j&&(i=this,--j);for(;j<k;j++)if((a=arguments[j])!=null)for(c in a){e=i[c],f=a[c];if(i===f)continue;l&&f&&(d.isPlainObject(f)||(g=d.isArray(f)))?(g?(g=!1,h=e&&d.isArray(e)?e:[]):h=e&&d.isPlainObject(e)?e:{},i[c]=d.extend(l,h,f)):f!==b&&(i[c]=f)}return i},d.extend({noConflict:function(b){a.$=f,b&&(a.jQuery=e);return d},isReady:!1,readyWait:1,ready:function(a){a===!0&&d.readyWait--;if(!d.readyWait||a!==!0&&!d.isReady){if(!c.body)return setTimeout(d.ready,1);d.isReady=!0;if(a!==!0&&--d.readyWait>0)return;x.resolveWith(c,[d]),d.fn.trigger&&d(c).trigger("ready").unbind("ready")}},bindReady:function(){if(!x){x=d._Deferred();if(c.readyState==="complete")return setTimeout(d.ready,1);if(c.addEventListener)c.addEventListener("DOMContentLoaded",y,!1),a.addEventListener("load",d.ready,!1);else if(c.attachEvent){c.attachEvent("onreadystatechange",y),a.attachEvent("onload",d.ready);var b=!1;try{b=a.frameElement==null}catch(e){}c.documentElement.doScroll&&b&&G()}}},isFunction:function(a){return d.type(a)==="function"},isArray:Array.isArray||function(a){return d.type(a)==="array"},isWindow:function(a){return a&&typeof a==="object"&&"setInterval"in a},isNaN:function(a){return a==null||!l.test(a)||isNaN(a)},type:function(a){return a==null?String(a):F[z.call(a)]||"object"},isPlainObject:function(a){if(!a||d.type(a)!=="object"||a.nodeType||d.isWindow(a))return!1;if(a.constructor&&!A.call(a,"constructor")&&!A.call(a.constructor.prototype,"isPrototypeOf"))return!1;var c;for(c in a){}return c===b||A.call(a,c)},isEmptyObject:function(a){for(var b in a)return!1;return!0},error:function(a){throw a},parseJSON:function(b){if(typeof b!=="string"||!b)return null;b=d.trim(b);if(n.test(b.replace(o,"@").replace(p,"]").replace(q,"")))return a.JSON&&a.JSON.parse?a.JSON.parse(b):(new Function("return "+b))();d.error("Invalid JSON: "+b)},parseXML:function(b,c,e){a.DOMParser?(e=new DOMParser,c=e.parseFromString(b,"text/xml")):(c=new ActiveXObject("Microsoft.XMLDOM"),c.async="false",c.loadXML(b)),e=c.documentElement,(!e||!e.nodeName||e.nodeName==="parsererror")&&d.error("Invalid XML: "+b);return c},noop:function(){},globalEval:function(a){if(a&&i.test(a)){var b=c.head||c.getElementsByTagName("head")[0]||c.documentElement,e=c.createElement("script");d.support.scriptEval()?e.appendChild(c.createTextNode(a)):e.text=a,b.insertBefore(e,b.firstChild),b.removeChild(e)}},nodeName:function(a,b){return a.nodeName&&a.nodeName.toUpperCase()===b.toUpperCase()},each:function(a,c,e){var f,g=0,h=a.length,i=h===b||d.isFunction(a);if(e){if(i){for(f in a)if(c.apply(a[f],e)===!1)break}else for(;g<h;)if(c.apply(a[g++],e)===!1)break}else if(i){for(f in a)if(c.call(a[f],f,a[f])===!1)break}else for(var j=a[0];g<h&&c.call(j,g,j)!==!1;j=a[++g]){}return a},trim:D?function(a){return a==null?"":D.call(a)}:function(a){return a==null?"":(a+"").replace(j,"").replace(k,"")},makeArray:function(a,b){var c=b||[];if(a!=null){var e=d.type(a);a.length==null||e==="string"||e==="function"||e==="regexp"||d.isWindow(a)?B.call(c,a):d.merge(c,a)}return c},inArray:function(a,b){if(b.indexOf)return b.indexOf(a);for(var c=0,d=b.length;c<d;c++)if(b[c]===a)return c;return-1},merge:function(a,c){var d=a.length,e=0;if(typeof c.length==="number")for(var f=c.length;e<f;e++)a[d++]=c[e];else while(c[e]!==b)a[d++]=c[e++];a.length=d;return a},grep:function(a,b,c){var d=[],e;c=!!c;for(var f=0,g=a.length;f<g;f++)e=!!b(a[f],f),c!==e&&d.push(a[f]);return d},map:function(a,b,c){var d=[],e;for(var f=0,g=a.length;f<g;f++)e=b(a[f],f,c),e!=null&&(d[d.length]=e);return d.concat.apply([],d)},guid:1,proxy:function(a,c,e){arguments.length===2&&(typeof c==="string"?(e=a,a=e[c],c=b):c&&!d.isFunction(c)&&(e=c,c=b)),!c&&a&&(c=function(){return a.apply(e||this,arguments)}),a&&(c.guid=a.guid=a.guid||c.guid||d.guid++);return c},access:function(a,c,e,f,g,h){var i=a.length;if(typeof c==="object"){for(var j in c)d.access(a,j,c[j],f,g,e);return a}if(e!==b){f=!h&&f&&d.isFunction(e);for(var k=0;k<i;k++)g(a[k],c,f?e.call(a[k],k,g(a[k],c)):e,h);return a}return i?g(a[0],c):b},now:function(){return(new Date).getTime()},uaMatch:function(a){a=a.toLowerCase();var b=r.exec(a)||s.exec(a)||t.exec(a)||a.indexOf("compatible")<0&&u.exec(a)||[];return{browser:b[1]||"",version:b[2]||"0"}},sub:function(){function a(b,c){return new a.fn.init(b,c)}d.extend(!0,a,this),a.superclass=this,a.fn=a.prototype=this(),a.fn.constructor=a,a.subclass=this.subclass,a.fn.init=function b(b,c){c&&c instanceof d&&!(c instanceof a)&&(c=a(c));return d.fn.init.call(this,b,c,e)},a.fn.init.prototype=a.fn;var e=a(c);return a},browser:{}}),d.each("Boolean Number String Function Array Date RegExp Object".split(" "),function(a,b){F["[object "+b+"]"]=b.toLowerCase()}),w=d.uaMatch(v),w.browser&&(d.browser[w.browser]=!0,d.browser.version=w.version),d.browser.webkit&&(d.browser.safari=!0),E&&(d.inArray=function(a,b){return E.call(b,a)}),i.test(" ")&&(j=/^[\s\xA0]+/,k=/[\s\xA0]+$/),g=d(c),c.addEventListener?y=function(){c.removeEventListener("DOMContentLoaded",y,!1),d.ready()}:c.attachEvent&&(y=function(){c.readyState==="complete"&&(c.detachEvent("onreadystatechange",y),d.ready())});return d}(),e="then done fail isResolved isRejected promise".split(" "),f=[].slice;d.extend({_Deferred:function(){var a=[],b,c,e,f={done:function(){if(!e){var c=arguments,g,h,i,j,k;b&&(k=b,b=0);for(g=0,h=c.length;g<h;g++)i=c[g],j=d.type(i),j==="array"?f.done.apply(f,i):j==="function"&&a.push(i);k&&f.resolveWith(k[0],k[1])}return this},resolveWith:function(d,f){if(!e&&!b&&!c){f=f||[],c=1;try{while(a[0])a.shift().apply(d,f)}finally{b=[d,f],c=0}}return this},resolve:function(){f.resolveWith(this,arguments);return this},isResolved:function(){return c||b},cancel:function(){e=1,a=[];return this}};return f},Deferred:function(a){var b=d._Deferred(),c=d._Deferred(),f;d.extend(b,{then:function(a,c){b.done(a).fail(c);return this},fail:c.done,rejectWith:c.resolveWith,reject:c.resolve,isRejected:c.isResolved,promise:function(a){if(a==null){if(f)return f;f=a={}}var c=e.length;while(c--)a[e[c]]=b[e[c]];return a}}),b.done(c.cancel).fail(b.cancel),delete b.cancel,a&&a.call(b,b);return b},when:function(a){function i(a){return function(c){b[a]=arguments.length>1?f.call(arguments,0):c,--g||h.resolveWith(h,f.call(b,0))}}var b=arguments,c=0,e=b.length,g=e,h=e<=1&&a&&d.isFunction(a.promise)?a:d.Deferred();if(e>1){for(;c<e;c++)b[c]&&d.isFunction(b[c].promise)?b[c].promise().then(i(c),h.reject):--g;g||h.resolveWith(h,b)}else h!==a&&h.resolveWith(h,e?[a]:[]);return h.promise()}}),function(){d.support={};var b=c.createElement("div");b.style.display="none",b.innerHTML="   <link/><table></table><a href='/a' style='color:red;float:left;opacity:.55;'>a</a><input type='checkbox'/>";var e=b.getElementsByTagName("*"),f=b.getElementsByTagName("a")[0],g=c.createElement("select"),h=g.appendChild(c.createElement("option")),i=b.getElementsByTagName("input")[0];if(e&&e.length&&f){d.support={leadingWhitespace:b.firstChild.nodeType===3,tbody:!b.getElementsByTagName("tbody").length,htmlSerialize:!!b.getElementsByTagName("link").length,style:/red/.test(f.getAttribute("style")),hrefNormalized:f.getAttribute("href")==="/a",opacity:/^0.55$/.test(f.style.opacity),cssFloat:!!f.style.cssFloat,checkOn:i.value==="on",optSelected:h.selected,deleteExpando:!0,optDisabled:!1,checkClone:!1,noCloneEvent:!0,noCloneChecked:!0,boxModel:null,inlineBlockNeedsLayout:!1,shrinkWrapBlocks:!1,reliableHiddenOffsets:!0,reliableMarginRight:!0},i.checked=!0,d.support.noCloneChecked=i.cloneNode(!0).checked,g.disabled=!0,d.support.optDisabled=!h.disabled;var j=null;d.support.scriptEval=function(){if(j===null){var b=c.documentElement,e=c.createElement("script"),f="script"+d.now();try{e.appendChild(c.createTextNode("window."+f+"=1;"))}catch(g){}b.insertBefore(e,b.firstChild),a[f]?(j=!0,delete a[f]):j=!1,b.removeChild(e)}return j};try{delete b.test}catch(k){d.support.deleteExpando=!1}!b.addEventListener&&b.attachEvent&&b.fireEvent&&(b.attachEvent("onclick",function l(){d.support.noCloneEvent=!1,b.detachEvent("onclick",l)}),b.cloneNode(!0).fireEvent("onclick")),b=c.createElement("div"),b.innerHTML="<input type='radio' name='radiotest' checked='checked'/>";var m=c.createDocumentFragment();m.appendChild(b.firstChild),d.support.checkClone=m.cloneNode(!0).cloneNode(!0).lastChild.checked,d(function(){var a=c.createElement("div"),b=c.getElementsByTagName("body")[0];if(b){a.style.width=a.style.paddingLeft="1px",b.appendChild(a),d.boxModel=d.support.boxModel=a.offsetWidth===2,"zoom"in a.style&&(a.style.display="inline",a.style.zoom=1,d.support.inlineBlockNeedsLayout=a.offsetWidth===2,a.style.display="",a.innerHTML="<div style='width:4px;'></div>",d.support.shrinkWrapBlocks=a.offsetWidth!==2),a.innerHTML="<table><tr><td style='padding:0;border:0;display:none'></td><td>t</td></tr></table>";var e=a.getElementsByTagName("td");d.support.reliableHiddenOffsets=e[0].offsetHeight===0,e[0].style.display="",e[1].style.display="none",d.support.reliableHiddenOffsets=d.support.reliableHiddenOffsets&&e[0].offsetHeight===0,a.innerHTML="",c.defaultView&&c.defaultView.getComputedStyle&&(a.style.width="1px",a.style.marginRight="0",d.support.reliableMarginRight=(parseInt(c.defaultView.getComputedStyle(a,null).marginRight,10)||0)===0),b.removeChild(a).style.display="none",a=e=null}});var n=function(a){var b=c.createElement("div");a="on"+a;if(!b.attachEvent)return!0;var d=a in b;d||(b.setAttribute(a,"return;"),d=typeof b[a]==="function");return d};d.support.submitBubbles=n("submit"),d.support.changeBubbles=n("change"),b=e=f=null}}();var g=/^(?:\{.*\}|\[.*\])$/;d.extend({cache:{},uuid:0,expando:"jQuery"+(d.fn.jquery+Math.random()).replace(/\D/g,""),noData:{embed:!0,object:"clsid:D27CDB6E-AE6D-11cf-96B8-444553540000",applet:!0},hasData:function(a){a=a.nodeType?d.cache[a[d.expando]]:a[d.expando];return!!a&&!i(a)},data:function(a,c,e,f){if(d.acceptData(a)){var g=d.expando,h=typeof c==="string",i,j=a.nodeType,k=j?d.cache:a,l=j?a[d.expando]:a[d.expando]&&d.expando;if((!l||f&&l&&!k[l][g])&&h&&e===b)return;l||(j?a[d.expando]=l=++d.uuid:l=d.expando),k[l]||(k[l]={},j||(k[l].toJSON=d.noop));if(typeof c==="object"||typeof c==="function")f?k[l][g]=d.extend(k[l][g],c):k[l]=d.extend(k[l],c);i=k[l],f&&(i[g]||(i[g]={}),i=i[g]),e!==b&&(i[c]=e);if(c==="events"&&!i[c])return i[g]&&i[g].events;return h?i[c]:i}},removeData:function(b,c,e){if(d.acceptData(b)){var f=d.expando,g=b.nodeType,h=g?d.cache:b,j=g?b[d.expando]:d.expando;if(!h[j])return;if(c){var k=e?h[j][f]:h[j];if(k){delete k[c];if(!i(k))return}}if(e){delete h[j][f];if(!i(h[j]))return}var l=h[j][f];d.support.deleteExpando||h!=a?delete h[j]:h[j]=null,l?(h[j]={},g||(h[j].toJSON=d.noop),h[j][f]=l):g&&(d.support.deleteExpando?delete b[d.expando]:b.removeAttribute?b.removeAttribute(d.expando):b[d.expando]=null)}},_data:function(a,b,c){return d.data(a,b,c,!0)},acceptData:function(a){if(a.nodeName){var b=d.noData[a.nodeName.toLowerCase()];if(b)return b!==!0&&a.getAttribute("classid")===b}return!0}}),d.fn.extend({data:function(a,c){var e=null;if(typeof a==="undefined"){if(this.length){e=d.data(this[0]);if(this[0].nodeType===1){var f=this[0].attributes,g;for(var i=0,j=f.length;i<j;i++)g=f[i].name,g.indexOf("data-")===0&&(g=g.substr(5),h(this[0],g,e[g]))}}return e}if(typeof a==="object")return this.each(function(){d.data(this,a)});var k=a.split(".");k[1]=k[1]?"."+k[1]:"";if(c===b){e=this.triggerHandler("getData"+k[1]+"!",[k[0]]),e===b&&this.length&&(e=d.data(this[0],a),e=h(this[0],a,e));return e===b&&k[1]?this.data(k[0]):e}return this.each(function(){var b=d(this),e=[k[0],c];b.triggerHandler("setData"+k[1]+"!",e),d.data(this,a,c),b.triggerHandler("changeData"+k[1]+"!",e)})},removeData:function(a){return this.each(function(){d.removeData(this,a)})}}),d.extend({queue:function(a,b,c){if(a){b=(b||"fx")+"queue";var e=d._data(a,b);if(!c)return e||[];!e||d.isArray(c)?e=d._data(a,b,d.makeArray(c)):e.push(c);return e}},dequeue:function(a,b){b=b||"fx";var c=d.queue(a,b),e=c.shift();e==="inprogress"&&(e=c.shift()),e&&(b==="fx"&&c.unshift("inprogress"),e.call(a,function(){d.dequeue(a,b)})),c.length||d.removeData(a,b+"queue",!0)}}),d.fn.extend({queue:function(a,c){typeof a!=="string"&&(c=a,a="fx");if(c===b)return d.queue(this[0],a);return this.each(function(b){var e=d.queue(this,a,c);a==="fx"&&e[0]!=="inprogress"&&d.dequeue(this,a)})},dequeue:function(a){return this.each(function(){d.dequeue(this,a)})},delay:function(a,b){a=d.fx?d.fx.speeds[a]||a:a,b=b||"fx";return this.queue(b,function(){var c=this;setTimeout(function(){d.dequeue(c,b)},a)})},clearQueue:function(a){return this.queue(a||"fx",[])}});var j=/[\n\t\r]/g,k=/\s+/,l=/\r/g,m=/^(?:href|src|style)$/,n=/^(?:button|input)$/i,o=/^(?:button|input|object|select|textarea)$/i,p=/^a(?:rea)?$/i,q=/^(?:radio|checkbox)$/i;d.props={"for":"htmlFor","class":"className",readonly:"readOnly",maxlength:"maxLength",cellspacing:"cellSpacing",rowspan:"rowSpan",colspan:"colSpan",tabindex:"tabIndex",usemap:"useMap",frameborder:"frameBorder"},d.fn.extend({attr:function(a,b){return d.access(this,a,b,!0,d.attr)},removeAttr:function(a,b){return this.each(function(){d.attr(this,a,""),this.nodeType===1&&this.removeAttribute(a)})},addClass:function(a){if(d.isFunction(a))return this.each(function(b){var c=d(this);c.addClass(a.call(this,b,c.attr("class")))});if(a&&typeof a==="string"){var b=(a||"").split(k);for(var c=0,e=this.length;c<e;c++){var f=this[c];if(f.nodeType===1)if(f.className){var g=" "+f.className+" ",h=f.className;for(var i=0,j=b.length;i<j;i++)g.indexOf(" "+b[i]+" ")<0&&(h+=" "+b[i]);f.className=d.trim(h)}else f.className=a}}return this},removeClass:function(a){if(d.isFunction(a))return this.each(function(b){var c=d(this);c.removeClass(a.call(this,b,c.attr("class")))});if(a&&typeof a==="string"||a===b){var c=(a||"").split(k);for(var e=0,f=this.length;e<f;e++){var g=this[e];if(g.nodeType===1&&g.className)if(a){var h=(" "+g.className+" ").replace(j," ");for(var i=0,l=c.length;i<l;i++)h=h.replace(" "+c[i]+" "," ");g.className=d.trim(h)}else g.className=""}}return this},toggleClass:function(a,b){var c=typeof a,e=typeof b==="boolean";if(d.isFunction(a))return this.each(function(c){var e=d(this);e.toggleClass(a.call(this,c,e.attr("class"),b),b)});return this.each(function(){if(c==="string"){var f,g=0,h=d(this),i=b,j=a.split(k);while(f=j[g++])i=e?i:!h.hasClass(f),h[i?"addClass":"removeClass"](f)}else if(c==="undefined"||c==="boolean")this.className&&d._data(this,"__className__",this.className),this.className=this.className||a===!1?"":d._data(this,"__className__")||""})},hasClass:function(a){var b=" "+a+" ";for(var c=0,d=this.length;c<d;c++)if((" "+this[c].className+" ").replace(j," ").indexOf(b)>-1)return!0;return!1},val:function(a){if(!arguments.length){var c=this[0];if(c){if(d.nodeName(c,"option")){var e=c.attributes.value;return!e||e.specified?c.value:c.text}if(d.nodeName(c,"select")){var f=c.selectedIndex,g=[],h=c.options,i=c.type==="select-one";if(f<0)return null;for(var j=i?f:0,k=i?f+1:h.length;j<k;j++){var m=h[j];if(m.selected&&(d.support.optDisabled?!m.disabled:m.getAttribute("disabled")===null)&&(!m.parentNode.disabled||!d.nodeName(m.parentNode,"optgroup"))){a=d(m).val();if(i)return a;g.push(a)}}if(i&&!g.length&&h.length)return d(h[f]).val();return g}if(q.test(c.type)&&!d.support.checkOn)return c.getAttribute("value")===null?"on":c.value;return(c.value||"").replace(l,"")}return b}var n=d.isFunction(a);return this.each(function(b){var c=d(this),e=a;if(this.nodeType===1){n&&(e=a.call(this,b,c.val())),e==null?e="":typeof e==="number"?e+="":d.isArray(e)&&(e=d.map(e,function(a){return a==null?"":a+""}));if(d.isArray(e)&&q.test(this.type))this.checked=d.inArray(c.val(),e)>=0;else if(d.nodeName(this,"select")){var f=d.makeArray(e);d("option",this).each(function(){this.selected=d.inArray(d(this).val(),f)>=0}),f.length||(this.selectedIndex=-1)}else this.value=e}})}}),d.extend({attrFn:{val:!0,css:!0,html:!0,text:!0,data:!0,width:!0,height:!0,offset:!0},attr:function(a,c,e,f){if(!a||a.nodeType===3||a.nodeType===8||a.nodeType===2)return b;if(f&&c in d.attrFn)return d(a)[c](e);var g=a.nodeType!==1||!d.isXMLDoc(a),h=e!==b;c=g&&d.props[c]||c;if(a.nodeType===1){var i=m.test(c);if(c==="selected"&&!d.support.optSelected){var j=a.parentNode;j&&(j.selectedIndex,j.parentNode&&j.parentNode.selectedIndex)}if((c in a||a[c]!==b)&&g&&!i){h&&(c==="type"&&n.test(a.nodeName)&&a.parentNode&&d.error("type property can't be changed"),e===null?a.nodeType===1&&a.removeAttribute(c):a[c]=e);if(d.nodeName(a,"form")&&a.getAttributeNode(c))return a.getAttributeNode(c).nodeValue;if(c==="tabIndex"){var k=a.getAttributeNode("tabIndex");return k&&k.specified?k.value:o.test(a.nodeName)||p.test(a.nodeName)&&a.href?0:b}return a[c]}if(!d.support.style&&g&&c==="style"){h&&(a.style.cssText=""+e);return a.style.cssText}h&&a.setAttribute(c,""+e);if(!a.attributes[c]&&(a.hasAttribute&&!a.hasAttribute(c)))return b;var l=!d.support.hrefNormalized&&g&&i?a.getAttribute(c,2):a.getAttribute(c);return l===null?b:l}h&&(a[c]=e);return a[c]}});var r=/\.(.*)$/,s=/^(?:textarea|input|select)$/i,t=/\./g,u=/ /g,v=/[^\w\s.|`]/g,w=function(a){return a.replace(v,"\\$&")};d.event={add:function(c,e,f,g){if(c.nodeType!==3&&c.nodeType!==8){try{d.isWindow(c)&&(c!==a&&!c.frameElement)&&(c=a)}catch(h){}if(f===!1)f=x;else if(!f)return;var i,j;f.handler&&(i=f,f=i.handler),f.guid||(f.guid=d.guid++);var k=d._data(c);if(!k)return;var l=k.events,m=k.handle;l||(k.events=l={}),m||(k.handle=m=function(a){return typeof d!=="undefined"&&d.event.triggered!==a.type?d.event.handle.apply(m.elem,arguments):b}),m.elem=c,e=e.split(" ");var n,o=0,p;while(n=e[o++]){j=i?d.extend({},i):{handler:f,data:g},n.indexOf(".")>-1?(p=n.split("."),n=p.shift(),j.namespace=p.slice(0).sort().join(".")):(p=[],j.namespace=""),j.type=n,j.guid||(j.guid=f.guid);var q=l[n],r=d.event.special[n]||{};if(!q){q=l[n]=[];if(!r.setup||r.setup.call(c,g,p,m)===!1)c.addEventListener?c.addEventListener(n,m,!1):c.attachEvent&&c.attachEvent("on"+n,m)}r.add&&(r.add.call(c,j),j.handler.guid||(j.handler.guid=f.guid)),q.push(j),d.event.global[n]=!0}c=null}},global:{},remove:function(a,c,e,f){if(a.nodeType!==3&&a.nodeType!==8){e===!1&&(e=x);var g,h,i,j,k=0,l,m,n,o,p,q,r,s=d.hasData(a)&&d._data(a),t=s&&s.events;if(!s||!t)return;c&&c.type&&(e=c.handler,c=c.type);if(!c||typeof c==="string"&&c.charAt(0)==="."){c=c||"";for(h in t)d.event.remove(a,h+c);return}c=c.split(" ");while(h=c[k++]){r=h,q=null,l=h.indexOf(".")<0,m=[],l||(m=h.split("."),h=m.shift(),n=new RegExp("(^|\\.)"+d.map(m.slice(0).sort(),w).join("\\.(?:.*\\.)?")+"(\\.|$)")),p=t[h];if(!p)continue;if(!e){for(j=0;j<p.length;j++){q=p[j];if(l||n.test(q.namespace))d.event.remove(a,r,q.handler,j),p.splice(j--,1)}continue}o=d.event.special[h]||{};for(j=f||0;j<p.length;j++){q=p[j];if(e.guid===q.guid){if(l||n.test(q.namespace))f==null&&p.splice(j--,1),o.remove&&o.remove.call(a,q);if(f!=null)break}}if(p.length===0||f!=null&&p.length===1)(!o.teardown||o.teardown.call(a,m)===!1)&&d.removeEvent(a,h,s.handle),g=null,delete t[h]}if(d.isEmptyObject(t)){var u=s.handle;u&&(u.elem=null),delete s.events,delete s.handle,d.isEmptyObject(s)&&d.removeData(a,b,!0)}}},trigger:function(a,c,e){var f=a.type||a,g=arguments[3];if(!g){a=typeof a==="object"?a[d.expando]?a:d.extend(d.Event(f),a):d.Event(f),f.indexOf("!")>=0&&(a.type=f=f.slice(0,-1),a.exclusive=!0),e||(a.stopPropagation(),d.event.global[f]&&d.each(d.cache,function(){var b=d.expando,e=this[b];e&&e.events&&e.events[f]&&d.event.trigger(a,c,e.handle.elem)}));if(!e||e.nodeType===3||e.nodeType===8)return b;a.result=b,a.target=e,c=d.makeArray(c),c.unshift(a)}a.currentTarget=e;var h=d._data(e,"handle");h&&h.apply(e,c);var i=e.parentNode||e.ownerDocument;try{e&&e.nodeName&&d.noData[e.nodeName.toLowerCase()]||e["on"+f]&&e["on"+f].apply(e,c)===!1&&(a.result=!1,a.preventDefault())}catch(j){}if(!a.isPropagationStopped()&&i)d.event.trigger(a,c,i,!0);else if(!a.isDefaultPrevented()){var k,l=a.target,m=f.replace(r,""),n=d.nodeName(l,"a")&&m==="click",o=d.event.special[m]||{};if((!o._default||o._default.call(e,a)===!1)&&!n&&!(l&&l.nodeName&&d.noData[l.nodeName.toLowerCase()])){try{l[m]&&(k=l["on"+m],k&&(l["on"+m]=null),d.event.triggered=a.type,l[m]())}catch(p){}k&&(l["on"+m]=k),d.event.triggered=b}}},handle:function(c){var e,f,g,h,i,j=[],k=d.makeArray(arguments);c=k[0]=d.event.fix(c||a.event),c.currentTarget=this,e=c.type.indexOf(".")<0&&!c.exclusive,e||(g=c.type.split("."),c.type=g.shift(),j=g.slice(0).sort(),h=new RegExp("(^|\\.)"+j.join("\\.(?:.*\\.)?")+"(\\.|$)")),c.namespace=c.namespace||j.join("."),i=d._data(this,"events"),f=(i||{})[c.type];if(i&&f){f=f.slice(0);for(var l=0,m=f.length;l<m;l++){var n=f[l];if(e||h.test(n.namespace)){c.handler=n.handler,c.data=n.data,c.handleObj=n;var o=n.handler.apply(this,k);o!==b&&(c.result=o,o===!1&&(c.preventDefault(),c.stopPropagation()));if(c.isImmediatePropagationStopped())break}}}return c.result},props:"altKey attrChange attrName bubbles button cancelable charCode clientX clientY ctrlKey currentTarget data detail eventPhase fromElement handler keyCode layerX layerY metaKey newValue offsetX offsetY pageX pageY prevValue relatedNode relatedTarget screenX screenY shiftKey srcElement target toElement view wheelDelta which".split(" "),fix:function(a){if(a[d.expando])return a;var e=a;a=d.Event(e);for(var f=this.props.length,g;f;)g=this.props[--f],a[g]=e[g];a.target||(a.target=a.srcElement||c),a.target.nodeType===3&&(a.target=a.target.parentNode),!a.relatedTarget&&a.fromElement&&(a.relatedTarget=a.fromElement===a.target?a.toElement:a.fromElement);if(a.pageX==null&&a.clientX!=null){var h=c.documentElement,i=c.body;a.pageX=a.clientX+(h&&h.scrollLeft||i&&i.scrollLeft||0)-(h&&h.clientLeft||i&&i.clientLeft||0),a.pageY=a.clientY+(h&&h.scrollTop||i&&i.scrollTop||0)-(h&&h.clientTop||i&&i.clientTop||0)}a.which==null&&(a.charCode!=null||a.keyCode!=null)&&(a.which=a.charCode!=null?a.charCode:a.keyCode),!a.metaKey&&a.ctrlKey&&(a.metaKey=a.ctrlKey),!a.which&&a.button!==b&&(a.which=a.button&1?1:a.button&2?3:a.button&4?2:0);return a},guid:1e8,proxy:d.proxy,special:{ready:{setup:d.bindReady,teardown:d.noop},live:{add:function(a){d.event.add(this,H(a.origType,a.selector),d.extend({},a,{handler:G,guid:a.handler.guid}))},remove:function(a){d.event.remove(this,H(a.origType,a.selector),a)}},beforeunload:{setup:function(a,b,c){d.isWindow(this)&&(this.onbeforeunload=c)},teardown:function(a,b){this.onbeforeunload===b&&(this.onbeforeunload=null)}}}},d.removeEvent=c.removeEventListener?function(a,b,c){a.removeEventListener&&a.removeEventListener(b,c,!1)}:function(a,b,c){a.detachEvent&&a.detachEvent("on"+b,c)},d.Event=function(a){if(!this.preventDefault)return new d.Event(a);a&&a.type?(this.originalEvent=a,this.type=a.type,this.isDefaultPrevented=a.defaultPrevented||a.returnValue===!1||a.getPreventDefault&&a.getPreventDefault()?y:x):this.type=a,this.timeStamp=d.now(),this[d.expando]=!0},d.Event.prototype={preventDefault:function(){this.isDefaultPrevented=y;var a=this.originalEvent;a&&(a.preventDefault?a.preventDefault():a.returnValue=!1)},stopPropagation:function(){this.isPropagationStopped=y;var a=this.originalEvent;a&&(a.stopPropagation&&a.stopPropagation(),a.cancelBubble=!0)},stopImmediatePropagation:function(){this.isImmediatePropagationStopped=y,this.stopPropagation()},isDefaultPrevented:x,isPropagationStopped:x,isImmediatePropagationStopped:x};var z=function(a){var b=a.relatedTarget;try{if(b&&b!==c&&!b.parentNode)return;while(b&&b!==this)b=b.parentNode;b!==this&&(a.type=a.data,d.event.handle.apply(this,arguments))}catch(e){}},A=function(a){a.type=a.data,d.event.handle.apply(this,arguments)};d.each({mouseenter:"mouseover",mouseleave:"mouseout"},function(a,b){d.event.special[a]={setup:function(c){d.event.add(this,b,c&&c.selector?A:z,a)},teardown:function(a){d.event.remove(this,b,a&&a.selector?A:z)}}}),d.support.submitBubbles||(d.event.special.submit={setup:function(a,b){if(this.nodeName&&this.nodeName.toLowerCase()!=="form")d.event.add(this,"click.specialSubmit",function(a){var b=a.target,c=b.type;(c==="submit"||c==="image")&&d(b).closest("form").length&&E("submit",this,arguments)}),d.event.add(this,"keypress.specialSubmit",function(a){var b=a.target,c=b.type;(c==="text"||c==="password")&&d(b).closest("form").length&&a.keyCode===13&&E("submit",this,arguments)});else return!1},teardown:function(a){d.event.remove(this,".specialSubmit")}});if(!d.support.changeBubbles){var B,C=function(a){var b=a.type,c=a.value;b==="radio"||b==="checkbox"?c=a.checked:b==="select-multiple"?c=a.selectedIndex>-1?d.map(a.options,function(a){return a.selected}).join("-"):"":a.nodeName.toLowerCase()==="select"&&(c=a.selectedIndex);return c},D=function D(a){var c=a.target,e,f;if(s.test(c.nodeName)&&!c.readOnly){e=d._data(c,"_change_data"),f=C(c),(a.type!=="focusout"||c.type!=="radio")&&d._data(c,"_change_data",f);if(e===b||f===e)return;if(e!=null||f)a.type="change",a.liveFired=b,d.event.trigger(a,arguments[1],c)}};d.event.special.change={filters:{focusout:D,beforedeactivate:D,click:function(a){var b=a.target,c=b.type;(c==="radio"||c==="checkbox"||b.nodeName.toLowerCase()==="select")&&D.call(this,a)},keydown:function(a){var b=a.target,c=b.type;(a.keyCode===13&&b.nodeName.toLowerCase()!=="textarea"||a.keyCode===32&&(c==="checkbox"||c==="radio")||c==="select-multiple")&&D.call(this,a)},beforeactivate:function(a){var b=a.target;d._data(b,"_change_data",C(b))}},setup:function(a,b){if(this.type==="file")return!1;for(var c in B)d.event.add(this,c+".specialChange",B[c]);return s.test(this.nodeName)},teardown:function(a){d.event.remove(this,".specialChange");return s.test(this.nodeName)}},B=d.event.special.change.filters,B.focus=B.beforeactivate}c.addEventListener&&d.each({focus:"focusin",blur:"focusout"},function(a,b){function f(a){var c=d.event.fix(a);c.type=b,c.originalEvent={},d.event.trigger(c,null,c.target),c.isDefaultPrevented()&&a.preventDefault()}var e=0;d.event.special[b]={setup:function(){e++===0&&c.addEventListener(a,f,!0)},teardown:function(){--e===0&&c.removeEventListener(a,f,!0)}}}),d.each(["bind","one"],function(a,c){d.fn[c]=function(a,e,f){if(typeof a==="object"){for(var g in a)this[c](g,e,a[g],f);return this}if(d.isFunction(e)||e===!1)f=e,e=b;var h=c==="one"?d.proxy(f,function(a){d(this).unbind(a,h);return f.apply(this,arguments)}):f;if(a==="unload"&&c!=="one")this.one(a,e,f);else for(var i=0,j=this.length;i<j;i++)d.event.add(this[i],a,h,e);return this}}),d.fn.extend({unbind:function(a,b){if(typeof a!=="object"||a.preventDefault)for(var e=0,f=this.length;e<f;e++)d.event.remove(this[e],a,b);else for(var c in a)this.unbind(c,a[c]);return this},delegate:function(a,b,c,d){return this.live(b,c,d,a)},undelegate:function(a,b,c){return arguments.length===0?this.unbind("live"):this.die(b,null,c,a)},trigger:function(a,b){return this.each(function(){d.event.trigger(a,b,this)})},triggerHandler:function(a,b){if(this[0]){var c=d.Event(a);c.preventDefault(),c.stopPropagation(),d.event.trigger(c,b,this[0]);return c.result}},toggle:function(a){var b=arguments,c=1;while(c<b.length)d.proxy(a,b[c++]);return this.click(d.proxy(a,function(e){var f=(d._data(this,"lastToggle"+a.guid)||0)%c;d._data(this,"lastToggle"+a.guid,f+1),e.preventDefault();return b[f].apply(this,arguments)||!1}))},hover:function(a,b){return this.mouseenter(a).mouseleave(b||a)}});var F={focus:"focusin",blur:"focusout",mouseenter:"mouseover",mouseleave:"mouseout"};d.each(["live","die"],function(a,c){d.fn[c]=function(a,e,f,g){var h,i=0,j,k,l,m=g||this.selector,n=g?this:d(this.context);if(typeof a==="object"&&!a.preventDefault){for(var o in a)n[c](o,e,a[o],m);return this}d.isFunction(e)&&(f=e,e=b),a=(a||"").split(" ");while((h=a[i++])!=null){j=r.exec(h),k="",j&&(k=j[0],h=h.replace(r,""));if(h==="hover"){a.push("mouseenter"+k,"mouseleave"+k);continue}l=h,h==="focus"||h==="blur"?(a.push(F[h]+k),h=h+k):h=(F[h]||h)+k;if(c==="live")for(var p=0,q=n.length;p<q;p++)d.event.add(n[p],"live."+H(h,m),{data:e,selector:m,handler:f,origType:h,origHandler:f,preType:l});else n.unbind("live."+H(h,m),f)}return this}}),d.each("blur focus focusin focusout load resize scroll unload click dblclick mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave change select submit keydown keypress keyup error".split(" "),function(a,b){d.fn[b]=function(a,c){c==null&&(c=a,a=null);return arguments.length>0?this.bind(b,a,c):this.trigger(b)},d.attrFn&&(d.attrFn[b]=!0)}),function(){function u(a,b,c,d,e,f){for(var g=0,h=d.length;g<h;g++){var i=d[g];if(i){var j=!1;i=i[a];while(i){if(i.sizcache===c){j=d[i.sizset];break}if(i.nodeType===1){f||(i.sizcache=c,i.sizset=g);if(typeof b!=="string"){if(i===b){j=!0;break}}else if(k.filter(b,[i]).length>0){j=i;break}}i=i[a]}d[g]=j}}}function t(a,b,c,d,e,f){for(var g=0,h=d.length;g<h;g++){var i=d[g];if(i){var j=!1;i=i[a];while(i){if(i.sizcache===c){j=d[i.sizset];break}i.nodeType===1&&!f&&(i.sizcache=c,i.sizset=g);if(i.nodeName.toLowerCase()===b){j=i;break}i=i[a]}d[g]=j}}}var a=/((?:\((?:\([^()]+\)|[^()]+)+\)|\[(?:\[[^\[\]]*\]|['"][^'"]*['"]|[^\[\]'"]+)+\]|\\.|[^ >+~,(\[\\]+)+|[>+~])(\s*,\s*)?((?:.|\r|\n)*)/g,e=0,f=Object.prototype.toString,g=!1,h=!0,i=/\\/g,j=/\W/;[0,0].sort(function(){h=!1;return 0});var k=function(b,d,e,g){e=e||[],d=d||c;var h=d;if(d.nodeType!==1&&d.nodeType!==9)return[];if(!b||typeof b!=="string")return e;var i,j,n,o,q,r,s,t,u=!0,w=k.isXML(d),x=[],y=b;do{a.exec(""),i=a.exec(y);if(i){y=i[3],x.push(i[1]);if(i[2]){o=i[3];break}}}while(i);if(x.length>1&&m.exec(b))if(x.length===2&&l.relative[x[0]])j=v(x[0]+x[1],d);else{j=l.relative[x[0]]?[d]:k(x.shift(),d);while(x.length)b=x.shift(),l.relative[b]&&(b+=x.shift()),j=v(b,j)}else{!g&&x.length>1&&d.nodeType===9&&!w&&l.match.ID.test(x[0])&&!l.match.ID.test(x[x.length-1])&&(q=k.find(x.shift(),d,w),d=q.expr?k.filter(q.expr,q.set)[0]:q.set[0]);if(d){q=g?{expr:x.pop(),set:p(g)}:k.find(x.pop(),x.length===1&&(x[0]==="~"||x[0]==="+")&&d.parentNode?d.parentNode:d,w),j=q.expr?k.filter(q.expr,q.set):q.set,x.length>0?n=p(j):u=!1;while(x.length)r=x.pop(),s=r,l.relative[r]?s=x.pop():r="",s==null&&(s=d),l.relative[r](n,s,w)}else n=x=[]}n||(n=j),n||k.error(r||b);if(f.call(n)==="[object Array]")if(u)if(d&&d.nodeType===1)for(t=0;n[t]!=null;t++)n[t]&&(n[t]===!0||n[t].nodeType===1&&k.contains(d,n[t]))&&e.push(j[t]);else for(t=0;n[t]!=null;t++)n[t]&&n[t].nodeType===1&&e.push(j[t]);else e.push.apply(e,n);else p(n,e);o&&(k(o,h,e,g),k.uniqueSort(e));return e};k.uniqueSort=function(a){if(r){g=h,a.sort(r);if(g)for(var b=1;b<a.length;b++)a[b]===a[b-1]&&a.splice(b--,1)}return a},k.matches=function(a,b){return k(a,null,null,b)},k.matchesSelector=function(a,b){return k(b,null,null,[a]).length>0},k.find=function(a,b,c){var d;if(!a)return[];for(var e=0,f=l.order.length;e<f;e++){var g,h=l.order[e];if(g=l.leftMatch[h].exec(a)){var j=g[1];g.splice(1,1);if(j.substr(j.length-1)!=="\\"){g[1]=(g[1]||"").replace(i,""),d=l.find[h](g,b,c);if(d!=null){a=a.replace(l.match[h],"");break}}}}d||(d=typeof b.getElementsByTagName!=="undefined"?b.getElementsByTagName("*"):[]);return{set:d,expr:a}},k.filter=function(a,c,d,e){var f,g,h=a,i=[],j=c,m=c&&c[0]&&k.isXML(c[0]);while(a&&c.length){for(var n in l.filter)if((f=l.leftMatch[n].exec(a))!=null&&f[2]){var o,p,q=l.filter[n],r=f[1];g=!1,f.splice(1,1);if(r.substr(r.length-1)==="\\")continue;j===i&&(i=[]);if(l.preFilter[n]){f=l.preFilter[n](f,j,d,i,e,m);if(f){if(f===!0)continue}else g=o=!0}if(f)for(var s=0;(p=j[s])!=null;s++)if(p){o=q(p,f,s,j);var t=e^!!o;d&&o!=null?t?g=!0:j[s]=!1:t&&(i.push(p),g=!0)}if(o!==b){d||(j=i),a=a.replace(l.match[n],"");if(!g)return[];break}}if(a===h)if(g==null)k.error(a);else break;h=a}return j},k.error=function(a){throw"Syntax error, unrecognized expression: "+a};var l=k.selectors={order:["ID","NAME","TAG"],match:{ID:/#((?:[\w\u00c0-\uFFFF\-]|\\.)+)/,CLASS:/\.((?:[\w\u00c0-\uFFFF\-]|\\.)+)/,NAME:/\[name=['"]*((?:[\w\u00c0-\uFFFF\-]|\\.)+)['"]*\]/,ATTR:/\[\s*((?:[\w\u00c0-\uFFFF\-]|\\.)+)\s*(?:(\S?=)\s*(?:(['"])(.*?)\3|(#?(?:[\w\u00c0-\uFFFF\-]|\\.)*)|)|)\s*\]/,TAG:/^((?:[\w\u00c0-\uFFFF\*\-]|\\.)+)/,CHILD:/:(only|nth|last|first)-child(?:\(\s*(even|odd|(?:[+\-]?\d+|(?:[+\-]?\d*)?n\s*(?:[+\-]\s*\d+)?))\s*\))?/,POS:/:(nth|eq|gt|lt|first|last|even|odd)(?:\((\d*)\))?(?=[^\-]|$)/,PSEUDO:/:((?:[\w\u00c0-\uFFFF\-]|\\.)+)(?:\((['"]?)((?:\([^\)]+\)|[^\(\)]*)+)\2\))?/},leftMatch:{},attrMap:{"class":"className","for":"htmlFor"},attrHandle:{href:function(a){return a.getAttribute("href")},type:function(a){return a.getAttribute("type")}},relative:{"+":function(a,b){var c=typeof b==="string",d=c&&!j.test(b),e=c&&!d;d&&(b=b.toLowerCase());for(var f=0,g=a.length,h;f<g;f++)if(h=a[f]){while((h=h.previousSibling)&&h.nodeType!==1){}a[f]=e||h&&h.nodeName.toLowerCase()===b?h||!1:h===b}e&&k.filter(b,a,!0)},">":function(a,b){var c,d=typeof b==="string",e=0,f=a.length;if(d&&!j.test(b)){b=b.toLowerCase();for(;e<f;e++){c=a[e];if(c){var g=c.parentNode;a[e]=g.nodeName.toLowerCase()===b?g:!1}}}else{for(;e<f;e++)c=a[e],c&&(a[e]=d?c.parentNode:c.parentNode===b);d&&k.filter(b,a,!0)}},"":function(a,b,c){var d,f=e++,g=u;typeof b==="string"&&!j.test(b)&&(b=b.toLowerCase(),d=b,g=t),g("parentNode",b,f,a,d,c)},"~":function(a,b,c){var d,f=e++,g=u;typeof b==="string"&&!j.test(b)&&(b=b.toLowerCase(),d=b,g=t),g("previousSibling",b,f,a,d,c)}},find:{ID:function(a,b,c){if(typeof b.getElementById!=="undefined"&&!c){var d=b.getElementById(a[1]);return d&&d.parentNode?[d]:[]}},NAME:function(a,b){if(typeof b.getElementsByName!=="undefined"){var c=[],d=b.getElementsByName(a[1]);for(var e=0,f=d.length;e<f;e++)d[e].getAttribute("name")===a[1]&&c.push(d[e]);return c.length===0?null:c}},TAG:function(a,b){if(typeof b.getElementsByTagName!=="undefined")return b.getElementsByTagName(a[1])}},preFilter:{CLASS:function(a,b,c,d,e,f){a=" "+a[1].replace(i,"")+" ";if(f)return a;for(var g=0,h;(h=b[g])!=null;g++)h&&(e^(h.className&&(" "+h.className+" ").replace(/[\t\n\r]/g," ").indexOf(a)>=0)?c||d.push(h):c&&(b[g]=!1));return!1},ID:function(a){return a[1].replace(i,"")},TAG:function(a,b){return a[1].replace(i,"").toLowerCase()},CHILD:function(a){if(a[1]==="nth"){a[2]||k.error(a[0]),a[2]=a[2].replace(/^\+|\s*/g,"");var b=/(-?)(\d*)(?:n([+\-]?\d*))?/.exec(a[2]==="even"&&"2n"||a[2]==="odd"&&"2n+1"||!/\D/.test(a[2])&&"0n+"+a[2]||a[2]);a[2]=b[1]+(b[2]||1)-0,a[3]=b[3]-0}else a[2]&&k.error(a[0]);a[0]=e++;return a},ATTR:function(a,b,c,d,e,f){var g=a[1]=a[1].replace(i,"");!f&&l.attrMap[g]&&(a[1]=l.attrMap[g]),a[4]=(a[4]||a[5]||"").replace(i,""),a[2]==="~="&&(a[4]=" "+a[4]+" ");return a},PSEUDO:function(b,c,d,e,f){if(b[1]==="not")if((a.exec(b[3])||"").length>1||/^\w/.test(b[3]))b[3]=k(b[3],null,null,c);else{var g=k.filter(b[3],c,d,!0^f);d||e.push.apply(e,g);return!1}else if(l.match.POS.test(b[0])||l.match.CHILD.test(b[0]))return!0;return b},POS:function(a){a.unshift(!0);return a}},filters:{enabled:function(a){return a.disabled===!1&&a.type!=="hidden"},disabled:function(a){return a.disabled===!0},checked:function(a){return a.checked===!0},selected:function(a){a.parentNode&&a.parentNode.selectedIndex;return a.selected===!0},parent:function(a){return!!a.firstChild},empty:function(a){return!a.firstChild},has:function(a,b,c){return!!k(c[3],a).length},header:function(a){return/h\d/i.test(a.nodeName)},text:function(a){var b=a.getAttribute("type"),c=a.type;return"text"===c&&(b===c||b===null)},radio:function(a){return"radio"===a.type},checkbox:function(a){return"checkbox"===a.type},file:function(a){return"file"===a.type},password:function(a){return"password"===a.type},submit:function(a){return"submit"===a.type},image:function(a){return"image"===a.type},reset:function(a){return"reset"===a.type},button:function(a){return"button"===a.type||a.nodeName.toLowerCase()==="button"},input:function(a){return/input|select|textarea|button/i.test(a.nodeName)}},setFilters:{first:function(a,b){return b===0},last:function(a,b,c,d){return b===d.length-1},even:function(a,b){return b%2===0},odd:function(a,b){return b%2===1},lt:function(a,b,c){return b<c[3]-0},gt:function(a,b,c){return b>c[3]-0},nth:function(a,b,c){return c[3]-0===b},eq:function(a,b,c){return c[3]-0===b}},filter:{PSEUDO:function(a,b,c,d){var e=b[1],f=l.filters[e];if(f)return f(a,c,b,d);if(e==="contains")return(a.textContent||a.innerText||k.getText([a])||"").indexOf(b[3])>=0;if(e==="not"){var g=b[3];for(var h=0,i=g.length;h<i;h++)if(g[h]===a)return!1;return!0}k.error(e)},CHILD:function(a,b){var c=b[1],d=a;switch(c){case"only":case"first":while(d=d.previousSibling)if(d.nodeType===1)return!1;if(c==="first")return!0;d=a;case"last":while(d=d.nextSibling)if(d.nodeType===1)return!1;return!0;case"nth":var e=b[2],f=b[3];if(e===1&&f===0)return!0;var g=b[0],h=a.parentNode;if(h&&(h.sizcache!==g||!a.nodeIndex)){var i=0;for(d=h.firstChild;d;d=d.nextSibling)d.nodeType===1&&(d.nodeIndex=++i);h.sizcache=g}var j=a.nodeIndex-f;return e===0?j===0:j%e===0&&j/e>=0}},ID:function(a,b){return a.nodeType===1&&a.getAttribute("id")===b},TAG:function(a,b){return b==="*"&&a.nodeType===1||a.nodeName.toLowerCase()===b},CLASS:function(a,b){return(" "+(a.className||a.getAttribute("class"))+" ").indexOf(b)>-1},ATTR:function(a,b){var c=b[1],d=l.attrHandle[c]?l.attrHandle[c](a):a[c]!=null?a[c]:a.getAttribute(c),e=d+"",f=b[2],g=b[4];return d==null?f==="!=":f==="="?e===g:f==="*="?e.indexOf(g)>=0:f==="~="?(" "+e+" ").indexOf(g)>=0:g?f==="!="?e!==g:f==="^="?e.indexOf(g)===0:f==="$="?e.substr(e.length-g.length)===g:f==="|="?e===g||e.substr(0,g.length+1)===g+"-":!1:e&&d!==!1},POS:function(a,b,c,d){var e=b[2],f=l.setFilters[e];if(f)return f(a,c,b,d)}}},m=l.match.POS,n=function(a,b){return"\\"+(b-0+1)};for(var o in l.match)l.match[o]=new RegExp(l.match[o].source+/(?![^\[]*\])(?![^\(]*\))/.source),l.leftMatch[o]=new RegExp(/(^(?:.|\r|\n)*?)/.source+l.match[o].source.replace(/\\(\d+)/g,n));var p=function(a,b){a=Array.prototype.slice.call(a,0);if(b){b.push.apply(b,a);return b}return a};try{Array.prototype.slice.call(c.documentElement.childNodes,0)[0].nodeType}catch(q){p=function(a,b){var c=0,d=b||[];if(f.call(a)==="[object Array]")Array.prototype.push.apply(d,a);else if(typeof a.length==="number")for(var e=a.length;c<e;c++)d.push(a[c]);else for(;a[c];c++)d.push(a[c]);return d}}var r,s;c.documentElement.compareDocumentPosition?r=function(a,b){if(a===b){g=!0;return 0}if(!a.compareDocumentPosition||!b.compareDocumentPosition)return a.compareDocumentPosition?-1:1;return a.compareDocumentPosition(b)&4?-1:1}:(r=function(a,b){var c,d,e=[],f=[],h=a.parentNode,i=b.parentNode,j=h;if(a===b){g=!0;return 0}if(h===i)return s(a,b);if(!h)return-1;if(!i)return 1;while(j)e.unshift(j),j=j.parentNode;j=i;while(j)f.unshift(j),j=j.parentNode;c=e.length,d=f.length;for(var k=0;k<c&&k<d;k++)if(e[k]!==f[k])return s(e[k],f[k]);return k===c?s(a,f[k],-1):s(e[k],b,1)},s=function(a,b,c){if(a===b)return c;var d=a.nextSibling;while(d){if(d===b)return-1;d=d.nextSibling}return 1}),k.getText=function(a){var b="",c;for(var d=0;a[d];d++)c=a[d],c.nodeType===3||c.nodeType===4?b+=c.nodeValue:c.nodeType!==8&&(b+=k.getText(c.childNodes));return b},function(){var a=c.createElement("div"),d="script"+(new Date).getTime(),e=c.documentElement;a.innerHTML="<a name='"+d+"'/>",e.insertBefore(a,e.firstChild),c.getElementById(d)&&(l.find.ID=function(a,c,d){if(typeof c.getElementById!=="undefined"&&!d){var e=c.getElementById(a[1]);return e?e.id===a[1]||typeof e.getAttributeNode!=="undefined"&&e.getAttributeNode("id").nodeValue===a[1]?[e]:b:[]}},l.filter.ID=function(a,b){var c=typeof a.getAttributeNode!=="undefined"&&a.getAttributeNode("id");return a.nodeType===1&&c&&c.nodeValue===b}),e.removeChild(a),e=a=null}(),function(){var a=c.createElement("div");a.appendChild(c.createComment("")),a.getElementsByTagName("*").length>0&&(l.find.TAG=function(a,b){var c=b.getElementsByTagName(a[1]);if(a[1]==="*"){var d=[];for(var e=0;c[e];e++)c[e].nodeType===1&&d.push(c[e]);c=d}return c}),a.innerHTML="<a href='#'></a>",a.firstChild&&typeof a.firstChild.getAttribute!=="undefined"&&a.firstChild.getAttribute("href")!=="#"&&(l.attrHandle.href=function(a){return a.getAttribute("href",2)}),a=null}(),c.querySelectorAll&&function(){var a=k,b=c.createElement("div"),d="__sizzle__";b.innerHTML="<p class='TEST'></p>";if(!b.querySelectorAll||b.querySelectorAll(".TEST").length!==0){k=function(b,e,f,g){e=e||c;if(!g&&!k.isXML(e)){var h=/^(\w+$)|^\.([\w\-]+$)|^#([\w\-]+$)/.exec(b);if(h&&(e.nodeType===1||e.nodeType===9)){if(h[1])return p(e.getElementsByTagName(b),f);if(h[2]&&l.find.CLASS&&e.getElementsByClassName)return p(e.getElementsByClassName(h[2]),f)}if(e.nodeType===9){if(b==="body"&&e.body)return p([e.body],f);if(h&&h[3]){var i=e.getElementById(h[3]);if(!i||!i.parentNode)return p([],f);if(i.id===h[3])return p([i],f)}try{return p(e.querySelectorAll(b),f)}catch(j){}}else if(e.nodeType===1&&e.nodeName.toLowerCase()!=="object"){var m=e,n=e.getAttribute("id"),o=n||d,q=e.parentNode,r=/^\s*[+~]/.test(b);n?o=o.replace(/'/g,"\\$&"):e.setAttribute("id",o),r&&q&&(e=e.parentNode);try{if(!r||q)return p(e.querySelectorAll("[id='"+o+"'] "+b),f)}catch(s){}finally{n||m.removeAttribute("id")}}}return a(b,e,f,g)};for(var e in a)k[e]=a[e];b=null}}(),function(){var a=c.documentElement,b=a.matchesSelector||a.mozMatchesSelector||a.webkitMatchesSelector||a.msMatchesSelector;if(b){var d=!b.call(c.createElement("div"),"div"),e=!1;try{b.call(c.documentElement,"[test!='']:sizzle")}catch(f){e=!0}k.matchesSelector=function(a,c){c=c.replace(/\=\s*([^'"\]]*)\s*\]/g,"='$1']");if(!k.isXML(a))try{if(e||!l.match.PSEUDO.test(c)&&!/!=/.test(c)){var f=b.call(a,c);if(f||!d||a.document&&a.document.nodeType!==11)return f}}catch(g){}return k(c,null,null,[a]).length>0}}}(),function(){var a=c.createElement("div");a.innerHTML="<div class='test e'></div><div class='test'></div>";if(a.getElementsByClassName&&a.getElementsByClassName("e").length!==0){a.lastChild.className="e";if(a.getElementsByClassName("e").length===1)return;l.order.splice(1,0,"CLASS"),l.find.CLASS=function(a,b,c){if(typeof b.getElementsByClassName!=="undefined"&&!c)return b.getElementsByClassName(a[1])},a=null}}(),c.documentElement.contains?k.contains=function(a,b){return a!==b&&(a.contains?a.contains(b):!0)}:c.documentElement.compareDocumentPosition?k.contains=function(a,b){return!!(a.compareDocumentPosition(b)&16)}:k.contains=function(){return!1},k.isXML=function(a){var b=(a?a.ownerDocument||a:0).documentElement;return b?b.nodeName!=="HTML":!1};var v=function(a,b){var c,d=[],e="",f=b.nodeType?[b]:b;while(c=l.match.PSEUDO.exec(a))e+=c[0],a=a.replace(l.match.PSEUDO,"");a=l.relative[a]?a+"*":a;for(var g=0,h=f.length;g<h;g++)k(a,f[g],d);return k.filter(e,d)};d.find=k,d.expr=k.selectors,d.expr[":"]=d.expr.filters,d.unique=k.uniqueSort,d.text=k.getText,d.isXMLDoc=k.isXML,d.contains=k.contains}();var I=/Until$/,J=/^(?:parents|prevUntil|prevAll)/,K=/,/,L=/^.[^:#\[\.,]*$/,M=Array.prototype.slice,N=d.expr.match.POS,O={children:!0,contents:!0,next:!0,prev:!0};d.fn.extend({find:function(a){var b=this.pushStack("","find",a),c=0;for(var e=0,f=this.length;e<f;e++){c=b.length,d.find(a,this[e],b);if(e>0)for(var g=c;g<b.length;g++)for(var h=0;h<c;h++)if(b[h]===b[g]){b.splice(g--,1);break}}return b},has:function(a){var b=d(a);return this.filter(function(){for(var a=0,c=b.length;a<c;a++)if(d.contains(this,b[a]))return!0})},not:function(a){return this.pushStack(Q(this,a,!1),"not",a)},filter:function(a){return this.pushStack(Q(this,a,!0),"filter",a)},is:function(a){return!!a&&d.filter(a,this).length>0},closest:function(a,b){var c=[],e,f,g=this[0];if(d.isArray(a)){var h,i,j={},k=1;if(g&&a.length){for(e=0,f=a.length;e<f;e++)i=a[e],j[i]||(j[i]=d.expr.match.POS.test(i)?d(i,b||this.context):i);while(g&&g.ownerDocument&&g!==b){for(i in j)h=j[i],(h.jquery?h.index(g)>-1:d(g).is(h))&&c.push({selector:i,elem:g,level:k});g=g.parentNode,k++}}return c}var l=N.test(a)?d(a,b||this.context):null;for(e=0,f=this.length;e<f;e++){g=this[e];while(g){if(l?l.index(g)>-1:d.find.matchesSelector(g,a)){c.push(g);break}g=g.parentNode;if(!g||!g.ownerDocument||g===b)break}}c=c.length>1?d.unique(c):c;return this.pushStack(c,"closest",a)},index:function(a){if(!a||typeof a==="string")return d.inArray(this[0],a?d(a):this.parent().children());return d.inArray(a.jquery?a[0]:a,this)},add:function(a,b){var c=typeof a==="string"?d(a,b):d.makeArray(a),e=d.merge(this.get(),c);return this.pushStack(P(c[0])||P(e[0])?e:d.unique(e))},andSelf:function(){return this.add(this.prevObject)}}),d.each({parent:function(a){var b=a.parentNode;return b&&b.nodeType!==11?b:null},parents:function(a){return d.dir(a,"parentNode")},parentsUntil:function(a,b,c){return d.dir(a,"parentNode",c)},next:function(a){return d.nth(a,2,"nextSibling")},prev:function(a){return d.nth(a,2,"previousSibling")},nextAll:function(a){return d.dir(a,"nextSibling")},prevAll:function(a){return d.dir(a,"previousSibling")},nextUntil:function(a,b,c){return d.dir(a,"nextSibling",c)},prevUntil:function(a,b,c){return d.dir(a,"previousSibling",c)},siblings:function(a){return d.sibling(a.parentNode.firstChild,a)},children:function(a){return d.sibling(a.firstChild)},contents:function(a){return d.nodeName(a,"iframe")?a.contentDocument||a.contentWindow.document:d.makeArray(a.childNodes)}},function(a,b){d.fn[a]=function(c,e){var f=d.map(this,b,c),g=M.call(arguments);I.test(a)||(e=c),e&&typeof e==="string"&&(f=d.filter(e,f)),f=this.length>1&&!O[a]?d.unique(f):f,(this.length>1||K.test(e))&&J.test(a)&&(f=f.reverse());return this.pushStack(f,a,g.join(","))}}),d.extend({filter:function(a,b,c){c&&(a=":not("+a+")");return b.length===1?d.find.matchesSelector(b[0],a)?[b[0]]:[]:d.find.matches(a,b)},dir:function(a,c,e){var f=[],g=a[c];while(g&&g.nodeType!==9&&(e===b||g.nodeType!==1||!d(g).is(e)))g.nodeType===1&&f.push(g),g=g[c];return f},nth:function(a,b,c,d){b=b||1;var e=0;for(;a;a=a[c])if(a.nodeType===1&&++e===b)break;return a},sibling:function(a,b){var c=[];for(;a;a=a.nextSibling)a.nodeType===1&&a!==b&&c.push(a);return c}});var R=/ jQuery\d+="(?:\d+|null)"/g,S=/^\s+/,T=/<(?!area|br|col|embed|hr|img|input|link|meta|param)(([\w:]+)[^>]*)\/>/ig,U=/<([\w:]+)/,V=/<tbody/i,W=/<|&#?\w+;/,X=/<(?:script|object|embed|option|style)/i,Y=/checked\s*(?:[^=]|=\s*.checked.)/i,Z={option:[1,"<select multiple='multiple'>","</select>"],legend:[1,"<fieldset>","</fieldset>"],thead:[1,"<table>","</table>"],tr:[2,"<table><tbody>","</tbody></table>"],td:[3,"<table><tbody><tr>","</tr></tbody></table>"],col:[2,"<table><tbody></tbody><colgroup>","</colgroup></table>"],area:[1,"<map>","</map>"],_default:[0,"",""]};Z.optgroup=Z.option,Z.tbody=Z.tfoot=Z.colgroup=Z.caption=Z.thead,Z.th=Z.td,d.support.htmlSerialize||(Z._default=[1,"div<div>","</div>"]),d.fn.extend({text:function(a){if(d.isFunction(a))return this.each(function(b){var c=d(this);c.text(a.call(this,b,c.text()))});if(typeof a!=="object"&&a!==b)return this.empty().append((this[0]&&this[0].ownerDocument||c).createTextNode(a));return d.text(this)},wrapAll:function(a){if(d.isFunction(a))return this.each(function(b){d(this).wrapAll(a.call(this,b))});if(this[0]){var b=d(a,this[0].ownerDocument).eq(0).clone(!0);this[0].parentNode&&b.insertBefore(this[0]),b.map(function(){var a=this;while(a.firstChild&&a.firstChild.nodeType===1)a=a.firstChild;return a}).append(this)}return this},wrapInner:function(a){if(d.isFunction(a))return this.each(function(b){d(this).wrapInner(a.call(this,b))});return this.each(function(){var b=d(this),c=b.contents();c.length?c.wrapAll(a):b.append(a)})},wrap:function(a){return this.each(function(){d(this).wrapAll(a)})},unwrap:function(){return this.parent().each(function(){d.nodeName(this,"body")||d(this).replaceWith(this.childNodes)}).end()},append:function(){return this.domManip(arguments,!0,function(a){this.nodeType===1&&this.appendChild(a)})},prepend:function(){return this.domManip(arguments,!0,function(a){this.nodeType===1&&this.insertBefore(a,this.firstChild)})},before:function(){if(this[0]&&this[0].parentNode)return this.domManip(arguments,!1,function(a){this.parentNode.insertBefore(a,this)});if(arguments.length){var a=d(arguments[0]);a.push.apply(a,this.toArray());return this.pushStack(a,"before",arguments)}},after:function(){if(this[0]&&this[0].parentNode)return this.domManip(arguments,!1,function(a){this.parentNode.insertBefore(a,this.nextSibling)});if(arguments.length){var a=this.pushStack(this,"after",arguments);a.push.apply(a,d(arguments[0]).toArray());return a}},remove:function(a,b){for(var c=0,e;(e=this[c])!=null;c++)if(!a||d.filter(a,[e]).length)!b&&e.nodeType===1&&(d.cleanData(e.getElementsByTagName("*")),d.cleanData([e])),e.parentNode&&e.parentNode.removeChild(e);return this},empty:function(){for(var a=0,b;(b=this[a])!=null;a++){b.nodeType===1&&d.cleanData(b.getElementsByTagName("*"));while(b.firstChild)b.removeChild(b.firstChild)}return this},clone:function(a,b){a=a==null?!1:a,b=b==null?a:b;return this.map(function(){return d.clone(this,a,b)})},html:function(a){if(a===b)return this[0]&&this[0].nodeType===1?this[0].innerHTML.replace(R,""):null;if(typeof a!=="string"||X.test(a)||!d.support.leadingWhitespace&&S.test(a)||Z[(U.exec(a)||["",""])[1].toLowerCase()])d.isFunction(a)?this.each(function(b){var c=d(this);c.html(a.call(this,b,c.html()))}):this.empty().append(a);else{a=a.replace(T,"<$1></$2>");try{for(var c=0,e=this.length;c<e;c++)this[c].nodeType===1&&(d.cleanData(this[c].getElementsByTagName("*")),this[c].innerHTML=a)}catch(f){this.empty().append(a)}}return this},replaceWith:function(a){if(this[0]&&this[0].parentNode){if(d.isFunction(a))return this.each(function(b){var c=d(this),e=c.html();c.replaceWith(a.call(this,b,e))});typeof a!=="string"&&(a=d(a).detach());return this.each(function(){var b=this.nextSibling,c=this.parentNode;d(this).remove(),b?d(b).before(a):d(c).append(a)})}return this.length?this.pushStack(d(d.isFunction(a)?a():a),"replaceWith",a):this},detach:function(a){return this.remove(a,!0)},domManip:function(a,c,e){var f,g,h,i,j=a[0],k=[];if(!d.support.checkClone&&arguments.length===3&&typeof j==="string"&&Y.test(j))return this.each(function(){d(this).domManip(a,c,e,!0)});if(d.isFunction(j))return this.each(function(f){var g=d(this);a[0]=j.call(this,f,c?g.html():b),g.domManip(a,c,e)});if(this[0]){i=j&&j.parentNode,d.support.parentNode&&i&&i.nodeType===11&&i.childNodes.length===this.length?f={fragment:i}:f=d.buildFragment(a,this,k),h=f.fragment,h.childNodes.length===1?g=h=h.firstChild:g=h.firstChild;if(g){c=c&&d.nodeName(g,"tr");for(var l=0,m=this.length,n=m-1;l<m;l++)e.call(c?$(this[l],g):this[l],f.cacheable||m>1&&l<n?d.clone(h,!0,!0):h)}k.length&&d.each(k,bc)}return this}}),d.buildFragment=function(a,b,e){var f,g,h,i=b&&b[0]?b[0].ownerDocument||b[0]:c;a.length===1&&typeof a[0]==="string"&&a[0].length<512&&i===c&&a[0].charAt(0)==="<"&&!X.test(a[0])&&(d.support.checkClone||!Y.test(a[0]))&&(g=!0,h=d.fragments[a[0]],h&&(h!==1&&(f=h))),f||(f=i.createDocumentFragment(),d.clean(a,i,f,e)),g&&(d.fragments[a[0]]=h?f:1);return{fragment:f,cacheable:g}},d.fragments={},d.each({appendTo:"append",prependTo:"prepend",insertBefore:"before",insertAfter:"after",replaceAll:"replaceWith"},function(a,b){d.fn[a]=function(c){var e=[],f=d(c),g=this.length===1&&this[0].parentNode;if(g&&g.nodeType===11&&g.childNodes.length===1&&f.length===1){f[b](this[0]);return this}for(var h=0,i=f.length;h<i;h++){var j=(h>0?this.clone(!0):this).get();d(f[h])[b](j),e=e.concat(j)}return this.pushStack(e,a,f.selector)}}),d.extend({clone:function(a,b,c){var e=a.cloneNode(!0),f,g,h;if((!d.support.noCloneEvent||!d.support.noCloneChecked)&&(a.nodeType===1||a.nodeType===11)&&!d.isXMLDoc(a)){ba(a,e),f=bb(a),g=bb(e);for(h=0;f[h];++h)ba(f[h],g[h])}if(b){_(a,e);if(c){f=bb(a),g=bb(e);for(h=0;f[h];++h)_(f[h],g[h])}}return e},clean:function(a,b,e,f){b=b||c,typeof b.createElement==="undefined"&&(b=b.ownerDocument||b[0]&&b[0].ownerDocument||c);var g=[];for(var h=0,i;(i=a[h])!=null;h++){typeof i==="number"&&(i+="");if(!i)continue;if(typeof i!=="string"||W.test(i)){if(typeof i==="string"){i=i.replace(T,"<$1></$2>");var j=(U.exec(i)||["",""])[1].toLowerCase(),k=Z[j]||Z._default,l=k[0],m=b.createElement("div");m.innerHTML=k[1]+i+k[2];while(l--)m=m.lastChild;if(!d.support.tbody){var n=V.test(i),o=j==="table"&&!n?m.firstChild&&m.firstChild.childNodes:k[1]==="<table>"&&!n?m.childNodes:[];for(var p=o.length-1;p>=0;--p)d.nodeName(o[p],"tbody")&&!o[p].childNodes.length&&o[p].parentNode.removeChild(o[p])}!d.support.leadingWhitespace&&S.test(i)&&m.insertBefore(b.createTextNode(S.exec(i)[0]),m.firstChild),i=m.childNodes}}else i=b.createTextNode(i);i.nodeType?g.push(i):g=d.merge(g,i)}if(e)for(h=0;g[h];h++)!f||!d.nodeName(g[h],"script")||g[h].type&&g[h].type.toLowerCase()!=="text/javascript"?(g[h].nodeType===1&&g.splice.apply(g,[h+1,0].concat(d.makeArray(g[h].getElementsByTagName("script")))),e.appendChild(g[h])):f.push(g[h].parentNode?g[h].parentNode.removeChild(g[h]):g[h]);return g},cleanData:function(a){var b,c,e=d.cache,f=d.expando,g=d.event.special,h=d.support.deleteExpando;for(var i=0,j;(j=a[i])!=null;i++){if(j.nodeName&&d.noData[j.nodeName.toLowerCase()])continue;c=j[d.expando];if(c){b=e[c]&&e[c][f];if(b&&b.events){for(var k in b.events)g[k]?d.event.remove(j,k):d.removeEvent(j,k,b.handle);b.handle&&(b.handle.elem=null)}h?delete j[d.expando]:j.removeAttribute&&j.removeAttribute(d.expando),delete e[c]}}}});var bd=/alpha\([^)]*\)/i,be=/opacity=([^)]*)/,bf=/-([a-z])/ig,bg=/([A-Z]|^ms)/g,bh=/^-?\d+(?:px)?$/i,bi=/^-?\d/,bj={position:"absolute",visibility:"hidden",display:"block"},bk=["Left","Right"],bl=["Top","Bottom"],bm,bn,bo,bp=function(a,b){return b.toUpperCase()};d.fn.css=function(a,c){if(arguments.length===2&&c===b)return this;return d.access(this,a,c,!0,function(a,c,e){return e!==b?d.style(a,c,e):d.css(a,c)})},d.extend({cssHooks:{opacity:{get:function(a,b){if(b){var c=bm(a,"opacity","opacity");return c===""?"1":c}return a.style.opacity}}},cssNumber:{zIndex:!0,fontWeight:!0,opacity:!0,zoom:!0,lineHeight:!0},cssProps:{"float":d.support.cssFloat?"cssFloat":"styleFloat"},style:function(a,c,e,f){if(a&&a.nodeType!==3&&a.nodeType!==8&&a.style){var g,h=d.camelCase(c),i=a.style,j=d.cssHooks[h];c=d.cssProps[h]||h;if(e===b){if(j&&"get"in j&&(g=j.get(a,!1,f))!==b)return g;return i[c]}if(typeof e==="number"&&isNaN(e)||e==null)return;typeof e==="number"&&!d.cssNumber[h]&&(e+="px");if(!j||!("set"in j)||(e=j.set(a,e))!==b)try{i[c]=e}catch(k){}}},css:function(a,c,e){var f,g=d.camelCase(c),h=d.cssHooks[g];c=d.cssProps[g]||g;if(h&&"get"in h&&(f=h.get(a,!0,e))!==b)return f;if(bm)return bm(a,c,g)},swap:function(a,b,c){var d={};for(var e in b)d[e]=a.style[e],a.style[e]=b[e];c.call(a);for(e in b)a.style[e]=d[e]},camelCase:function(a){return a.replace(bf,bp)}}),d.curCSS=d.css,d.each(["height","width"],function(a,b){d.cssHooks[b]={get:function(a,c,e){var f;if(c){a.offsetWidth!==0?f=bq(a,b,e):d.swap(a,bj,function(){f=bq(a,b,e)});if(f<=0){f=bm(a,b,b),f==="0px"&&bo&&(f=bo(a,b,b));if(f!=null)return f===""||f==="auto"?"0px":f}if(f<0||f==null){f=a.style[b];return f===""||f==="auto"?"0px":f}return typeof f==="string"?f:f+"px"}},set:function(a,b){if(!bh.test(b))return b;b=parseFloat(b);if(b>=0)return b+"px"}}}),d.support.opacity||(d.cssHooks.opacity={get:function(a,b){return be.test((b&&a.currentStyle?a.currentStyle.filter:a.style.filter)||"")?parseFloat(RegExp.$1)/100+"":b?"1":""},set:function(a,b){var c=a.style;c.zoom=1;var e=d.isNaN(b)?"":"alpha(opacity="+b*100+")",f=c.filter||"";c.filter=bd.test(f)?f.replace(bd,e):c.filter+" "+e}}),d(function(){d.support.reliableMarginRight||(d.cssHooks.marginRight={get:function(a,b){var c;d.swap(a,{display:"inline-block"},function(){b?c=bm(a,"margin-right","marginRight"):c=a.style.marginRight});return c}})}),c.defaultView&&c.defaultView.getComputedStyle&&(bn=function(a,c,e){var f,g,h;e=e.replace(bg,"-$1").toLowerCase();if(!(g=a.ownerDocument.defaultView))return b;if(h=g.getComputedStyle(a,null))f=h.getPropertyValue(e),f===""&&!d.contains(a.ownerDocument.documentElement,a)&&(f=d.style(a,e));return f}),c.documentElement.currentStyle&&(bo=function(a,b){var c,d=a.currentStyle&&a.currentStyle[b],e=a.runtimeStyle&&a.runtimeStyle[b],f=a.style;!bh.test(d)&&bi.test(d)&&(c=f.left,e&&(a.runtimeStyle.left=a.currentStyle.left),f.left=b==="fontSize"?"1em":d||0,d=f.pixelLeft+"px",f.left=c,e&&(a.runtimeStyle.left=e));return d===""?"auto":d}),bm=bn||bo,d.expr&&d.expr.filters&&(d.expr.filters.hidden=function(a){var b=a.offsetWidth,c=a.offsetHeight;return b===0&&c===0||!d.support.reliableHiddenOffsets&&(a.style.display||d.css(a,"display"))==="none"},d.expr.filters.visible=function(a){return!d.expr.filters.hidden(a)});var br=/%20/g,bs=/\[\]$/,bt=/\r?\n/g,bu=/#.*$/,bv=/^(.*?):[ \t]*([^\r\n]*)\r?$/mg,bw=/^(?:color|date|datetime|email|hidden|month|number|password|range|search|tel|text|time|url|week)$/i,bx=/^(?:about|app|app\-storage|.+\-extension|file|widget):$/,by=/^(?:GET|HEAD)$/,bz=/^\/\//,bA=/\?/,bB=/<script\b[^<]*(?:(?!<\/script>)<[^<]*)*<\/script>/gi,bC=/^(?:select|textarea)/i,bD=/\s+/,bE=/([?&])_=[^&]*/,bF=/(^|\-)([a-z])/g,bG=function(a,b,c){return b+c.toUpperCase()},bH=/^([\w\+\.\-]+:)(?:\/\/([^\/?#:]*)(?::(\d+))?)?/,bI=d.fn.load,bJ={},bK={},bL,bM;try{bL=c.location.href}catch(bN){bL=c.createElement("a"),bL.href="",bL=bL.href}bM=bH.exec(bL.toLowerCase())||[],d.fn.extend({load:function(a,c,e){if(typeof a!=="string"&&bI)return bI.apply(this,arguments);if(!this.length)return this;var f=a.indexOf(" ");if(f>=0){var g=a.slice(f,a.length);a=a.slice(0,f)}var h="GET";c&&(d.isFunction(c)?(e=c,c=b):typeof c==="object"&&(c=d.param(c,d.ajaxSettings.traditional),h="POST"));var i=this;d.ajax({url:a,type:h,dataType:"html",data:c,complete:function(a,b,c){c=a.responseText,a.isResolved()&&(a.done(function(a){c=a}),i.html(g?d("<div>").append(c.replace(bB,"")).find(g):c)),e&&i.each(e,[c,b,a])}});return this},serialize:function(){return d.param(this.serializeArray())},serializeArray:function(){return this.map(function(){return this.elements?d.makeArray(this.elements):this}).filter(function(){return this.name&&!this.disabled&&(this.checked||bC.test(this.nodeName)||bw.test(this.type))}).map(function(a,b){var c=d(this).val();return c==null?null:d.isArray(c)?d.map(c,function(a,c){return{name:b.name,value:a.replace(bt,"\r\n")}}):{name:b.name,value:c.replace(bt,"\r\n")}}).get()}}),d.each("ajaxStart ajaxStop ajaxComplete ajaxError ajaxSuccess ajaxSend".split(" "),function(a,b){d.fn[b]=function(a){return this.bind(b,a)}}),d.each(["get","post"],function(a,c){d[c]=function(a,e,f,g){d.isFunction(e)&&(g=g||f,f=e,e=b);return d.ajax({type:c,url:a,data:e,success:f,dataType:g})}}),d.extend({getScript:function(a,c){return d.get(a,b,c,"script")},getJSON:function(a,b,c){return d.get(a,b,c,"json")},ajaxSetup:function(a,b){b?d.extend(!0,a,d.ajaxSettings,b):(b=a,a=d.extend(!0,d.ajaxSettings,b));for(var c in {context:1,url:1})c in b?a[c]=b[c]:c in d.ajaxSettings&&(a[c]=d.ajaxSettings[c]);return a},ajaxSettings:{url:bL,isLocal:bx.test(bM[1]),global:!0,type:"GET",contentType:"application/x-www-form-urlencoded",processData:!0,async:!0,accepts:{xml:"application/xml, text/xml",html:"text/html",text:"text/plain",json:"application/json, text/javascript","*":"*/*"},contents:{xml:/xml/,html:/html/,json:/json/},responseFields:{xml:"responseXML",text:"responseText"},converters:{"* text":a.String,"text html":!0,"text json":d.parseJSON,"text xml":d.parseXML}},ajaxPrefilter:bO(bJ),ajaxTransport:bO(bK),ajax:function(a,c){function v(a,c,l,n){if(r!==2){r=2,p&&clearTimeout(p),o=b,m=n||"",u.readyState=a?4:0;var q,t,v,w=l?bR(e,u,l):b,x,y;if(a>=200&&a<300||a===304){if(e.ifModified){if(x=u.getResponseHeader("Last-Modified"))d.lastModified[k]=x;if(y=u.getResponseHeader("Etag"))d.etag[k]=y}if(a===304)c="notmodified",q=!0;else try{t=bS(e,w),c="success",q=!0}catch(z){c="parsererror",v=z}}else{v=c;if(!c||a)c="error",a<0&&(a=0)}u.status=a,u.statusText=c,q?h.resolveWith(f,[t,c,u]):h.rejectWith(f,[u,c,v]),u.statusCode(j),j=b,s&&g.trigger("ajax"+(q?"Success":"Error"),[u,e,q?t:v]),i.resolveWith(f,[u,c]),s&&(g.trigger("ajaxComplete",[u,e]),--d.active||d.event.trigger("ajaxStop"))}}typeof a==="object"&&(c=a,a=b),c=c||{};var e=d.ajaxSetup({},c),f=e.context||e,g=f!==e&&(f.nodeType||f instanceof d)?d(f):d.event,h=d.Deferred(),i=d._Deferred(),j=e.statusCode||{},k,l={},m,n,o,p,q,r=0,s,t,u={readyState:0,setRequestHeader:function(a,b){r||(l[a.toLowerCase().replace(bF,bG)]=b);return this},getAllResponseHeaders:function(){return r===2?m:null},getResponseHeader:function(a){var c;if(r===2){if(!n){n={};while(c=bv.exec(m))n[c[1].toLowerCase()]=c[2]}c=n[a.toLowerCase()]}return c===b?null:c},overrideMimeType:function(a){r||(e.mimeType=a);return this},abort:function(a){a=a||"abort",o&&o.abort(a),v(0,a);return this}};h.promise(u),u.success=u.done,u.error=u.fail,u.complete=i.done,u.statusCode=function(a){if(a){var b;if(r<2)for(b in a)j[b]=[j[b],a[b]];else b=a[u.status],u.then(b,b)}return this},e.url=((a||e.url)+"").replace(bu,"").replace(bz,bM[1]+"//"),e.dataTypes=d.trim(e.dataType||"*").toLowerCase().split(bD),e.crossDomain==null&&(q=bH.exec(e.url.toLowerCase()),e.crossDomain=q&&(q[1]!=bM[1]||q[2]!=bM[2]||(q[3]||(q[1]==="http:"?80:443))!=(bM[3]||(bM[1]==="http:"?80:443)))),e.data&&e.processData&&typeof e.data!=="string"&&(e.data=d.param(e.data,e.traditional)),bP(bJ,e,c,u);if(r===2)return!1;s=e.global,e.type=e.type.toUpperCase(),e.hasContent=!by.test(e.type),s&&d.active++===0&&d.event.trigger("ajaxStart");if(!e.hasContent){e.data&&(e.url+=(bA.test(e.url)?"&":"?")+e.data),k=e.url;if(e.cache===!1){var w=d.now(),x=e.url.replace(bE,"$1_="+w);e.url=x+(x===e.url?(bA.test(e.url)?"&":"?")+"_="+w:"")}}if(e.data&&e.hasContent&&e.contentType!==!1||c.contentType)l["Content-Type"]=e.contentType;e.ifModified&&(k=k||e.url,d.lastModified[k]&&(l["If-Modified-Since"]=d.lastModified[k]),d.etag[k]&&(l["If-None-Match"]=d.etag[k])),l.Accept=e.dataTypes[0]&&e.accepts[e.dataTypes[0]]?e.accepts[e.dataTypes[0]]+(e.dataTypes[0]!=="*"?", */*; q=0.01":""):e.accepts["*"];for(t in e.headers)u.setRequestHeader(t,e.headers[t]);if(e.beforeSend&&(e.beforeSend.call(f,u,e)===!1||r===2)){u.abort();return!1}for(t in {success:1,error:1,complete:1})u[t](e[t]);o=bP(bK,e,c,u);if(o){u.readyState=1,s&&g.trigger("ajaxSend",[u,e]),e.async&&e.timeout>0&&(p=setTimeout(function(){u.abort("timeout")},e.timeout));try{r=1,o.send(l,v)}catch(y){status<2?v(-1,y):d.error(y)}}else v(-1,"No Transport");return u},param:function(a,c){var e=[],f=function(a,b){b=d.isFunction(b)?b():b,e[e.length]=encodeURIComponent(a)+"="+encodeURIComponent(b)};c===b&&(c=d.ajaxSettings.traditional);if(d.isArray(a)||a.jquery&&!d.isPlainObject(a))d.each(a,function(){f(this.name,this.value)});else for(var g in a)bQ(g,a[g],c,f);return e.join("&").replace(br,"+")}}),d.extend({active:0,lastModified:{},etag:{}});var bT=d.now(),bU=/(\=)\?(&|$)|\?\?/i;d.ajaxSetup({jsonp:"callback",jsonpCallback:function(){return d.expando+"_"+bT++}}),d.ajaxPrefilter("json jsonp",function(b,c,e){var f=typeof b.data==="string";if(b.dataTypes[0]==="jsonp"||c.jsonpCallback||c.jsonp!=null||b.jsonp!==!1&&(bU.test(b.url)||f&&bU.test(b.data))){var g,h=b.jsonpCallback=d.isFunction(b.jsonpCallback)?b.jsonpCallback():b.jsonpCallback,i=a[h],j=b.url,k=b.data,l="$1"+h+"$2",m=function(){a[h]=i,g&&d.isFunction(i)&&a[h](g[0])};b.jsonp!==!1&&(j=j.replace(bU,l),b.url===j&&(f&&(k=k.replace(bU,l)),b.data===k&&(j+=(/\?/.test(j)?"&":"?")+b.jsonp+"="+h))),b.url=j,b.data=k,a[h]=function(a){g=[a]},e.then(m,m),b.converters["script json"]=function(){g||d.error(h+" was not called");return g[0]},b.dataTypes[0]="json";return"script"}}),d.ajaxSetup({accepts:{script:"text/javascript, application/javascript, application/ecmascript, application/x-ecmascript"},contents:{script:/javascript|ecmascript/},converters:{"text script":function(a){d.globalEval(a);return a}}}),d.ajaxPrefilter("script",function(a){a.cache===b&&(a.cache=!1),a.crossDomain&&(a.type="GET",a.global=!1)}),d.ajaxTransport("script",function(a){if(a.crossDomain){var d,e=c.head||c.getElementsByTagName("head")[0]||c.documentElement;return{send:function(f,g){d=c.createElement("script"),d.async="async",a.scriptCharset&&(d.charset=a.scriptCharset),d.src=a.url,d.onload=d.onreadystatechange=function(a,c){if(!d.readyState||/loaded|complete/.test(d.readyState))d.onload=d.onreadystatechange=null,e&&d.parentNode&&e.removeChild(d),d=b,c||g(200,"success")},e.insertBefore(d,e.firstChild)},abort:function(){d&&d.onload(0,1)}}}});var bV=d.now(),bW,bX;d.ajaxSettings.xhr=a.ActiveXObject?function(){return!this.isLocal&&bZ()||b$()}:bZ,bX=d.ajaxSettings.xhr(),d.support.ajax=!!bX,d.support.cors=bX&&"withCredentials"in bX,bX=b,d.support.ajax&&d.ajaxTransport(function(a){if(!a.crossDomain||d.support.cors){var c;return{send:function(e,f){var g=a.xhr(),h,i;a.username?g.open(a.type,a.url,a.async,a.username,a.password):g.open(a.type,a.url,a.async);if(a.xhrFields)for(i in a.xhrFields)g[i]=a.xhrFields[i];a.mimeType&&g.overrideMimeType&&g.overrideMimeType(a.mimeType),!a.crossDomain&&!e["X-Requested-With"]&&(e["X-Requested-With"]="XMLHttpRequest");try{for(i in e)g.setRequestHeader(i,e[i])}catch(j){}g.send(a.hasContent&&a.data||null),c=function(e,i){var j,k,l,m,n;try{if(c&&(i||g.readyState===4)){c=b,h&&(g.onreadystatechange=d.noop,delete bW[h]);if(i)g.readyState!==4&&g.abort();else{j=g.status,l=g.getAllResponseHeaders(),m={},n=g.responseXML,n&&n.documentElement&&(m.xml=n),m.text=g.responseText;try{k=g.statusText}catch(o){k=""}j||!a.isLocal||a.crossDomain?j===1223&&(j=204):j=m.text?200:404}}}catch(p){i||f(-1,p)}m&&f(j,k,m,l)},a.async&&g.readyState!==4?(bW||(bW={},bY()),h=bV++,g.onreadystatechange=bW[h]=c):c()},abort:function(){c&&c(0,1)}}}});var b_={},ca=/^(?:toggle|show|hide)$/,cb=/^([+\-]=)?([\d+.\-]+)([a-z%]*)$/i,cc,cd=[["height","marginTop","marginBottom","paddingTop","paddingBottom"],["width","marginLeft","marginRight","paddingLeft","paddingRight"],["opacity"]];d.fn.extend({show:function(a,b,c){var e,f;if(a||a===0)return this.animate(ce("show",3),a,b,c);for(var g=0,h=this.length;g<h;g++)e=this[g],f=e.style.display,!d._data(e,"olddisplay")&&f==="none"&&(f=e.style.display=""),f===""&&d.css(e,"display")==="none"&&d._data(e,"olddisplay",cf(e.nodeName));for(g=0;g<h;g++){e=this[g],f=e.style.display;if(f===""||f==="none")e.style.display=d._data(e,"olddisplay")||""}return this},hide:function(a,b,c){if(a||a===0)return this.animate(ce("hide",3),a,b,c);for(var e=0,f=this.length;e<f;e++){var g=d.css(this[e],"display");g!=="none"&&!d._data(this[e],"olddisplay")&&d._data(this[e],"olddisplay",g)}for(e=0;e<f;e++)this[e].style.display="none";return this},_toggle:d.fn.toggle,toggle:function(a,b,c){var e=typeof a==="boolean";d.isFunction(a)&&d.isFunction(b)?this._toggle.apply(this,arguments):a==null||e?this.each(function(){var b=e?a:d(this).is(":hidden");d(this)[b?"show":"hide"]()}):this.animate(ce("toggle",3),a,b,c);return this},fadeTo:function(a,b,c,d){return this.filter(":hidden").css("opacity",0).show().end().animate({opacity:b},a,c,d)},animate:function(a,b,c,e){var f=d.speed(b,c,e);if(d.isEmptyObject(a))return this.each(f.complete);return this[f.queue===!1?"each":"queue"](function(){var b=d.extend({},f),c,e=this.nodeType===1,g=e&&d(this).is(":hidden"),h=this;for(c in a){var i=d.camelCase(c);c!==i&&(a[i]=a[c],delete a[c],c=i);if(a[c]==="hide"&&g||a[c]==="show"&&!g)return b.complete.call(this);if(e&&(c==="height"||c==="width")){b.overflow=[this.style.overflow,this.style.overflowX,this.style.overflowY];if(d.css(this,"display")==="inline"&&d.css(this,"float")==="none")if(d.support.inlineBlockNeedsLayout){var j=cf(this.nodeName);j==="inline"?this.style.display="inline-block":(this.style.display="inline",this.style.zoom=1)}else this.style.display="inline-block"}d.isArray(a[c])&&((b.specialEasing=b.specialEasing||{})[c]=a[c][1],a[c]=a[c][0])}b.overflow!=null&&(this.style.overflow="hidden"),b.curAnim=d.extend({},a),d.each(a,function(c,e){var f=new d.fx(h,b,c);if(ca.test(e))f[e==="toggle"?g?"show":"hide":e](a);else{var i=cb.exec(e),j=f.cur();if(i){var k=parseFloat(i[2]),l=i[3]||(d.cssNumber[c]?"":"px");l!=="px"&&(d.style(h,c,(k||1)+l),j=(k||1)/f.cur()*j,d.style(h,c,j+l)),i[1]&&(k=(i[1]==="-="?-1:1)*k+j),f.custom(j,k,l)}else f.custom(j,e,"")}});return!0})},stop:function(a,b){var c=d.timers;a&&this.queue([]),this.each(function(){for(var a=c.length-1;a>=0;a--)c[a].elem===this&&(b&&c[a](!0),c.splice(a,1))}),b||this.dequeue();return this}}),d.each({slideDown:ce("show",1),slideUp:ce("hide",1),slideToggle:ce("toggle",1),fadeIn:{opacity:"show"},fadeOut:{opacity:"hide"},fadeToggle:{opacity:"toggle"}},function(a,b){d.fn[a]=function(a,c,d){return this.animate(b,a,c,d)}}),d.extend({speed:function(a,b,c){var e=a&&typeof a==="object"?d.extend({},a):{complete:c||!c&&b||d.isFunction(a)&&a,duration:a,easing:c&&b||b&&!d.isFunction(b)&&b};e.duration=d.fx.off?0:typeof e.duration==="number"?e.duration:e.duration in d.fx.speeds?d.fx.speeds[e.duration]:d.fx.speeds._default,e.old=e.complete,e.complete=function(){e.queue!==!1&&d(this).dequeue(),d.isFunction(e.old)&&e.old.call(this)};return e},easing:{linear:function(a,b,c,d){return c+d*a},swing:function(a,b,c,d){return(-Math.cos(a*Math.PI)/2+.5)*d+c}},timers:[],fx:function(a,b,c){this.options=b,this.elem=a,this.prop=c,b.orig||(b.orig={})}}),d.fx.prototype={update:function(){this.options.step&&this.options.step.call(this.elem,this.now,this),(d.fx.step[this.prop]||d.fx.step._default)(this)},cur:function(){if(this.elem[this.prop]!=null&&(!this.elem.style||this.elem.style[this.prop]==null))return this.elem[this.prop];var a,b=d.css(this.elem,this.prop);return isNaN(a=parseFloat(b))?!b||b==="auto"?0:b:a},custom:function(a,b,c){function g(a){return e.step(a)}var e=this,f=d.fx;this.startTime=d.now(),this.start=a,this.end=b,this.unit=c||this.unit||(d.cssNumber[this.prop]?"":"px"),this.now=this.start,this.pos=this.state=0,g.elem=this.elem,g()&&d.timers.push(g)&&!cc&&(cc=setInterval(f.tick,f.interval))},show:function(){this.options.orig[this.prop]=d.style(this.elem,this.prop),this.options.show=!0,this.custom(this.prop==="width"||this.prop==="height"?1:0,this.cur()),d(this.elem).show()},hide:function(){this.options.orig[this.prop]=d.style(this.elem,this.prop),this.options.hide=!0,this.custom(this.cur(),0)},step:function(a){var b=d.now(),c=!0;if(a||b>=this.options.duration+this.startTime){this.now=this.end,this.pos=this.state=1,this.update(),this.options.curAnim[this.prop]=!0;for(var e in this.options.curAnim)this.options.curAnim[e]!==!0&&(c=!1);if(c){if(this.options.overflow!=null&&!d.support.shrinkWrapBlocks){var f=this.elem,g=this.options;d.each(["","X","Y"],function(a,b){f.style["overflow"+b]=g.overflow[a]})}this.options.hide&&d(this.elem).hide();if(this.options.hide||this.options.show)for(var h in this.options.curAnim)d.style(this.elem,h,this.options.orig[h]);this.options.complete.call(this.elem)}return!1}var i=b-this.startTime;this.state=i/this.options.duration;var j=this.options.specialEasing&&this.options.specialEasing[this.prop],k=this.options.easing||(d.easing.swing?"swing":"linear");this.pos=d.easing[j||k](this.state,i,0,1,this.options.duration),this.now=this.start+(this.end-this.start)*this.pos,this.update();return!0}},d.extend(d.fx,{tick:function(){var a=d.timers;for(var b=0;b<a.length;b++)a[b]()||a.splice(b--,1);a.length||d.fx.stop()},interval:13,stop:function(){clearInterval(cc),cc=null},speeds:{slow:600,fast:200,_default:400},step:{opacity:function(a){d.style(a.elem,"opacity",a.now)},_default:function(a){a.elem.style&&a.elem.style[a.prop]!=null?a.elem.style[a.prop]=(a.prop==="width"||a.prop==="height"?Math.max(0,a.now):a.now)+a.unit:a.elem[a.prop]=a.now}}}),d.expr&&d.expr.filters&&(d.expr.filters.animated=function(a){return d.grep(d.timers,function(b){return a===b.elem}).length});var cg=/^t(?:able|d|h)$/i,ch=/^(?:body|html)$/i;"getBoundingClientRect"in c.documentElement?d.fn.offset=function(a){var b=this[0],c;if(a)return this.each(function(b){d.offset.setOffset(this,a,b)});if(!b||!b.ownerDocument)return null;if(b===b.ownerDocument.body)return d.offset.bodyOffset(b);try{c=b.getBoundingClientRect()}catch(e){}var f=b.ownerDocument,g=f.documentElement;if(!c||!d.contains(g,b))return c?{top:c.top,left:c.left}:{top:0,left:0};var h=f.body,i=ci(f),j=g.clientTop||h.clientTop||0,k=g.clientLeft||h.clientLeft||0,l=i.pageYOffset||d.support.boxModel&&g.scrollTop||h.scrollTop,m=i.pageXOffset||d.support.boxModel&&g.scrollLeft||h.scrollLeft,n=c.top+l-j,o=c.left+m-k;return{top:n,left:o}}:d.fn.offset=function(a){var b=this[0];if(a)return this.each(function(b){d.offset.setOffset(this,a,b)});if(!b||!b.ownerDocument)return null;if(b===b.ownerDocument.body)return d.offset.bodyOffset(b);d.offset.initialize();var c,e=b.offsetParent,f=b,g=b.ownerDocument,h=g.documentElement,i=g.body,j=g.defaultView,k=j?j.getComputedStyle(b,null):b.currentStyle,l=b.offsetTop,m=b.offsetLeft;while((b=b.parentNode)&&b!==i&&b!==h){if(d.offset.supportsFixedPosition&&k.position==="fixed")break;c=j?j.getComputedStyle(b,null):b.currentStyle,l-=b.scrollTop,m-=b.scrollLeft,b===e&&(l+=b.offsetTop,m+=b.offsetLeft,d.offset.doesNotAddBorder&&(!d.offset.doesAddBorderForTableAndCells||!cg.test(b.nodeName))&&(l+=parseFloat(c.borderTopWidth)||0,m+=parseFloat(c.borderLeftWidth)||0),f=e,e=b.offsetParent),d.offset.subtractsBorderForOverflowNotVisible&&c.overflow!=="visible"&&(l+=parseFloat(c.borderTopWidth)||0,m+=parseFloat(c.borderLeftWidth)||0),k=c}if(k.position==="relative"||k.position==="static")l+=i.offsetTop,m+=i.offsetLeft;d.offset.supportsFixedPosition&&k.position==="fixed"&&(l+=Math.max(h.scrollTop,i.scrollTop),m+=Math.max(h.scrollLeft,i.scrollLeft));return{top:l,left:m}},d.offset={initialize:function(){var a=c.body,b=c.createElement("div"),e,f,g,h,i=parseFloat(d.css(a,"marginTop"))||0,j="<div style='position:absolute;top:0;left:0;margin:0;border:5px solid #000;padding:0;width:1px;height:1px;'><div></div></div><table style='position:absolute;top:0;left:0;margin:0;border:5px solid #000;padding:0;width:1px;height:1px;' cellpadding='0' cellspacing='0'><tr><td></td></tr></table>";d.extend(b.style,{position:"absolute",top:0,left:0,margin:0,border:0,width:"1px",height:"1px",visibility:"hidden"}),b.innerHTML=j,a.insertBefore(b,a.firstChild),e=b.firstChild,f=e.firstChild,h=e.nextSibling.firstChild.firstChild,this.doesNotAddBorder=f.offsetTop!==5,this.doesAddBorderForTableAndCells=h.offsetTop===5,f.style.position="fixed",f.style.top="20px",this.supportsFixedPosition=f.offsetTop===20||f.offsetTop===15,f.style.position=f.style.top="",e.style.overflow="hidden",e.style.position="relative",this.subtractsBorderForOverflowNotVisible=f.offsetTop===-5,this.doesNotIncludeMarginInBodyOffset=a.offsetTop!==i,a.removeChild(b),d.offset.initialize=d.noop},bodyOffset:function(a){var b=a.offsetTop,c=a.offsetLeft;d.offset.initialize(),d.offset.doesNotIncludeMarginInBodyOffset&&(b+=parseFloat(d.css(a,"marginTop"))||0,c+=parseFloat(d.css(a,"marginLeft"))||0);return{top:b,left:c}},setOffset:function(a,b,c){var e=d.css(a,"position");e==="static"&&(a.style.position="relative");var f=d(a),g=f.offset(),h=d.css(a,"top"),i=d.css(a,"left"),j=(e==="absolute"||e==="fixed")&&d.inArray("auto",[h,i])>-1,k={},l={},m,n;j&&(l=f.position()),m=j?l.top:parseInt(h,10)||0,n=j?l.left:parseInt(i,10)||0,d.isFunction(b)&&(b=b.call(a,c,g)),b.top!=null&&(k.top=b.top-g.top+m),b.left!=null&&(k.left=b.left-g.left+n),"using"in b?b.using.call(a,k):f.css(k)}},d.fn.extend({position:function(){if(!this[0])return null;var a=this[0],b=this.offsetParent(),c=this.offset(),e=ch.test(b[0].nodeName)?{top:0,left:0}:b.offset();c.top-=parseFloat(d.css(a,"marginTop"))||0,c.left-=parseFloat(d.css(a,"marginLeft"))||0,e.top+=parseFloat(d.css(b[0],"borderTopWidth"))||0,e.left+=parseFloat(d.css(b[0],"borderLeftWidth"))||0;return{top:c.top-e.top,left:c.left-e.left}},offsetParent:function(){return this.map(function(){var a=this.offsetParent||c.body;while(a&&(!ch.test(a.nodeName)&&d.css(a,"position")==="static"))a=a.offsetParent;return a})}}),d.each(["Left","Top"],function(a,c){var e="scroll"+c;d.fn[e]=function(c){var f=this[0],g;if(!f)return null;if(c!==b)return this.each(function(){g=ci(this),g?g.scrollTo(a?d(g).scrollLeft():c,a?c:d(g).scrollTop()):this[e]=c});g=ci(f);return g?"pageXOffset"in g?g[a?"pageYOffset":"pageXOffset"]:d.support.boxModel&&g.document.documentElement[e]||g.document.body[e]:f[e]}}),d.each(["Height","Width"],function(a,c){var e=c.toLowerCase();d.fn["inner"+c]=function(){return this[0]?parseFloat(d.css(this[0],e,"padding")):null},d.fn["outer"+c]=function(a){return this[0]?parseFloat(d.css(this[0],e,a?"margin":"border")):null},d.fn[e]=function(a){var f=this[0];if(!f)return a==null?null:this;if(d.isFunction(a))return this.each(function(b){var c=d(this);c[e](a.call(this,b,c[e]()))});if(d.isWindow(f)){var g=f.document.documentElement["client"+c];return f.document.compatMode==="CSS1Compat"&&g||f.document.body["client"+c]||g}if(f.nodeType===9)return Math.max(f.documentElement["client"+c],f.body["scroll"+c],f.documentElement["scroll"+c],f.body["offset"+c],f.documentElement["offset"+c]);if(a===b){var h=d.css(f,e),i=parseFloat(h);return d.isNaN(i)?h:i}return this.css(e,typeof a==="string"?a:a+"px")}}),a.jQuery=a.$=d})(window);
\ No newline at end of file
diff --git a/y2019/vision/server/www_defaults/_seasocks.css b/y2019/vision/server/www_defaults/_seasocks.css
new file mode 100644
index 0000000..03a7287
--- /dev/null
+++ b/y2019/vision/server/www_defaults/_seasocks.css
@@ -0,0 +1,22 @@
+body {
+    font-family: segoe ui, tahoma, arial, sans-serif;
+    font-size: 12px;
+    color: #ffffff;
+    background-color: #333333;
+    margin: 0;
+}
+
+a {
+    color: #ffff00;
+}
+
+table {
+    border-collapse: collapse;
+    width: 100%;
+    text-align: center;
+}
+
+.template {
+    display: none;
+}
+
diff --git a/y2019/vision/server/www_defaults/_stats.html b/y2019/vision/server/www_defaults/_stats.html
new file mode 100644
index 0000000..d34e932
--- /dev/null
+++ b/y2019/vision/server/www_defaults/_stats.html
@@ -0,0 +1,60 @@
+<html DOCTYPE=html>
+<head>
+  <title>SeaSocks Stats</title>
+  <link href="/_seasocks.css" rel="stylesheet">
+  <script src="/_jquery.min.js" type="text/javascript"></script>
+  <script>
+  function clear() {
+    $('#cx tbody tr:visible').remove();
+  }
+  function connection(stats) {
+  	c = $('#cx .template').clone().removeClass('template').appendTo('#cx');
+  	for (stat in stats) {
+  	  c.find('.' + stat).text(stats[stat]);
+    }
+  }
+  function refresh() {
+  		var stats = new XMLHttpRequest();
+		stats.open("GET", "/_livestats.js", false);
+		stats.send(null);
+		eval(stats.responseText);
+  }
+  $(function() {
+  	setInterval(refresh, 1000);
+  	refresh();		
+  });
+  </script>
+</head>
+<body><h1>SeaSocks Stats</h1></body>
+
+<h2>Connections</h2>
+<table id="cx">
+  <thead>
+    <tr>
+      <th>Connection time</th>
+      <th>Fd</th>
+      <th>Addr</th>
+      <th>URI</th>
+      <th>Username</th>
+      <th>Pending read</th>
+      <th>Bytes read</th>
+      <th>Pending send</th>
+      <th>Bytes sent</th>
+    </tr>
+  </thead>
+  <tbody>
+    <tr class="template">
+      <td class="since"></td>
+      <td class="fd"></td>
+      <td class="addr"></td>
+      <td class="uri"></td>
+      <td class="user"></td>
+      <td class="input"></td>
+      <td class="read"></td>
+      <td class="output"></td>
+      <td class="written"></td>
+    </tr>
+  </tbody>
+</table>
+
+</body></html>
diff --git a/y2019/vision/server/www_defaults/favicon.ico b/y2019/vision/server/www_defaults/favicon.ico
new file mode 100644
index 0000000..30a95b9
--- /dev/null
+++ b/y2019/vision/server/www_defaults/favicon.ico
Binary files differ
diff --git a/y2019/vision/target_finder.cc b/y2019/vision/target_finder.cc
index a56d82c..77806d5 100644
--- a/y2019/vision/target_finder.cc
+++ b/y2019/vision/target_finder.cc
@@ -1,13 +1,18 @@
 #include "y2019/vision/target_finder.h"
 
 #include "aos/vision/blob/hierarchical_contour_merge.h"
+#include "ceres/ceres.h"
 
 using namespace aos::vision;
 
 namespace y2019 {
 namespace vision {
 
-TargetFinder::TargetFinder() : target_template_(Target::MakeTemplate()) {}
+TargetFinder::TargetFinder()
+    : target_template_(Target::MakeTemplate()),
+      ceres_context_(ceres::Context::Create()) {}
+
+TargetFinder::~TargetFinder() {}
 
 aos::vision::RangeImage TargetFinder::Threshold(aos::vision::ImagePtr image) {
   const uint8_t threshold_value = GetThresholdValue();
@@ -512,7 +517,7 @@
   // Based on a linear regression between error and distance to target.
   // Closer targets can have a higher error because they are bigger.
   const double acceptable_error =
-      std::max(2 * (21 - 12 * result->extrinsics.z), 50.0);
+      std::max(2 * (75 - 12 * result->extrinsics.z), 75.0);
   if (result->solver_error < acceptable_error) {
     if (verbose) {
       printf("Using an 8 point solve: %f < %f \n", result->solver_error,
@@ -550,8 +555,9 @@
     valid_result_count_++;
   }
   if (print_rate > 0 && frame_count_ > print_rate) {
-    LOG(INFO, "Found (%zu / %zu)(%.2f) targets.\n", valid_result_count_,
-        frame_count_, (double)valid_result_count_ / (double)frame_count_);
+    LOG(INFO) << "Found (" << valid_result_count_ << " / " << frame_count_
+              << ")(" << ((double)valid_result_count_ / (double)frame_count_)
+              << " targets.";
     frame_count_ = 0;
     valid_result_count_ = 0;
   }
diff --git a/y2019/vision/target_finder.h b/y2019/vision/target_finder.h
index c7de67a..3da5373 100644
--- a/y2019/vision/target_finder.h
+++ b/y2019/vision/target_finder.h
@@ -1,14 +1,21 @@
 #ifndef _Y2019_VISION_TARGET_FINDER_H_
 #define _Y2019_VISION_TARGET_FINDER_H_
 
+#include <memory>
+
+#include "aos/vision/blob/contour.h"
 #include "aos/vision/blob/region_alloc.h"
 #include "aos/vision/blob/threshold.h"
 #include "aos/vision/blob/transpose.h"
-#include "aos/vision/blob/contour.h"
 #include "aos/vision/debug/overlay.h"
 #include "aos/vision/math/vector.h"
 #include "y2019/vision/target_types.h"
 
+namespace ceres {
+
+class Context;
+
+}  // namespace ceres
 namespace y2019 {
 namespace vision {
 
@@ -26,6 +33,8 @@
 class TargetFinder {
  public:
   TargetFinder();
+  ~TargetFinder();
+
   // Turn a raw image into blob range image.
   aos::vision::RangeImage Threshold(aos::vision::ImagePtr image);
 
@@ -88,6 +97,8 @@
 
   ExtrinsicParams default_extrinsics_;
 
+  const std::unique_ptr<ceres::Context> ceres_context_;
+
   // Counts for logging.
   size_t frame_count_;
   size_t valid_result_count_;
diff --git a/y2019/vision/target_geometry.cc b/y2019/vision/target_geometry.cc
index 6df1a27..e647f1f 100644
--- a/y2019/vision/target_geometry.cc
+++ b/y2019/vision/target_geometry.cc
@@ -4,6 +4,8 @@
 
 #include <math.h>
 
+#include "aos/util/math.h"
+
 using ceres::NumericDiffCostFunction;
 using ceres::CENTRAL;
 using ceres::CostFunction;
@@ -234,8 +236,10 @@
   double params_4point[ExtrinsicParams::kNumParams];
   default_extrinsics_.set(&params_4point[0]);
 
-  Problem problem_8point;
-  Problem problem_4point;
+  Problem::Options problem_options;
+  problem_options.context = ceres_context_.get();
+  Problem problem_8point(problem_options);
+  Problem problem_4point(problem_options);
 
   ::std::array<aos::vision::Vector<2>, 8> target_value = target.ToPointList();
   ::std::array<aos::vision::Vector<2>, 8> template_value =
@@ -306,6 +310,12 @@
   IR.backup_extrinsics = ExtrinsicParams::get(&params_4point[0]);
   IR.backup_solver_error = summary_4point2.final_cost;
 
+  // Normalize all angles to (-M_PI, M_PI]
+  IR.extrinsics.r1 = ::aos::math::NormalizeAngle(IR.extrinsics.r1);
+  IR.extrinsics.r2 = ::aos::math::NormalizeAngle(IR.extrinsics.r2);
+  IR.backup_extrinsics.r1 = ::aos::math::NormalizeAngle(IR.backup_extrinsics.r1);
+  IR.backup_extrinsics.r2 = ::aos::math::NormalizeAngle(IR.backup_extrinsics.r2);
+
   if (verbose) {
     std::cout << "rup = " << intrinsics_.mount_angle * 180 / M_PI << ";\n";
     std::cout << "fl = " << intrinsics_.focal_length << ";\n";
diff --git a/y2019/vision/target_sender.cc b/y2019/vision/target_sender.cc
index 3a6fbfe..52b81ad 100644
--- a/y2019/vision/target_sender.cc
+++ b/y2019/vision/target_sender.cc
@@ -95,7 +95,7 @@
                             monotonic_clock::time_point monotonic_now) {
     aos::vision::ImageFormat fmt{640, 480};
     aos::vision::BlobList imgs = aos::vision::FindBlobs(
-        aos::vision::SlowYuyvYThreshold(fmt, data.data(), 120));
+        aos::vision::FastYuyvYThreshold(fmt, data.data(), 120));
     finder_.PreFilter(&imgs);
     LOG(INFO, "Blobs: (%zu).\n", imgs.size());
 
@@ -103,7 +103,7 @@
     ::std::vector<Polygon> raw_polys;
     for (const RangeImage &blob : imgs) {
       // Convert blobs to contours in the corrected space.
-      ContourNode* contour = finder_.GetContour(blob);
+      ContourNode *contour = finder_.GetContour(blob);
       ::std::vector<::Eigen::Vector2f> unwarped_contour =
           finder_.UnWarpContour(contour);
       const Polygon polygon =
@@ -149,8 +149,8 @@
     frame.age = std::chrono::duration_cast<frc971::jevois::camera_duration>(
         aos::monotonic_clock::now() - monotonic_now);
 
-    // If we succeed in writing our delimiter, then write out the rest of the
-    // frame. If not, no point in continuing.
+    // If we succeed in writing our delimiter, then write out the rest of
+    // the frame. If not, no point in continuing.
     if (write(itsDev, "\0", 1) == 1) {
       const auto serialized_frame = frc971::jevois::UartPackToTeensy(frame);
       // We don't really care if this succeeds or not. If it fails for some
@@ -176,7 +176,6 @@
       char data[kBufferSize];
       ssize_t n = read(itsDev, &data[0], kBufferSize);
       if (n >= 1) {
-        LOG(INFO, "Serial bytes: %zd", n);
         cobs.ParseData(gsl::span<const char>(&data[0], n));
         auto packet = cobs.received_packet();
         if (!packet.empty()) {
diff --git a/y2019/vision/tools/deploy.sh b/y2019/vision/tools/deploy.sh
index 3c16b03..2538239 100755
--- a/y2019/vision/tools/deploy.sh
+++ b/y2019/vision/tools/deploy.sh
@@ -1,6 +1,19 @@
-#!/bin/sh
+#!/bin/bash
 set -e
 
+BRANCH=$(git rev-parse --symbolic-full-name --abbrev-ref HEAD)
+if [[ "$BRANCH" != "master" ]]; then
+  read -p "Not on master, deploy anyway (y/n) " ANSWER
+  if [[ $ANSWER =~ ^[Yy]$ ]]; then
+    echo "Master check overridden, deploying anyway"
+  else
+    echo "Cancelling deploy"
+    exit 1
+  fi
+else
+  echo "On master, deploying"
+fi
+
 echo "Building executables"
 readonly BAZEL_OPTIONS="-c opt --cpu=armhf-debian"
 readonly BAZEL_BIN="$(bazel info ${BAZEL_OPTIONS} bazel-bin)"
@@ -10,10 +23,46 @@
     //y2019/vision:target_sender \
     //y2019/vision:serial_waiter
 
-if [ ! -d "${TARGET_DIR}" ]
+JEVOIS_DEV="/dev/null"
+for dev in /dev/ttyACM*; do
+  if udevadm info -a -n "${dev}" | grep "JeVois-A33 Smart Camera" -q;
+  then
+    JEVOIS_DEV="${dev}"
+  fi
+done
+
+if [[ "${JEVOIS_DEV}" == "/dev/null" ]];
+then
+  echo "Can't find jevois"
+  exit 1;
+fi;
+
+if ! mount | grep "${TARGET_DIR}" -q
 then
   echo "Mount jevois at ${TARGET_DIR} ..."
-  ./jevois-cmd usbsd
+  ./jevois-cmd -d "${JEVOIS_DEV}" usbsd
+fi
+
+sleep 5
+
+JEVOIS_SD=
+for SD in /dev/sd[a-z]; do
+  if udevadm info -a -n "${SD}" | grep JeVois -q; then
+    echo "Jevois at ${SD}"
+    JEVOIS_SD="${SD}"
+    break
+  fi
+done
+if [[ -z ${JEVOIS_SD} ]]; then
+  echo "Failed to find Jevois. Stopping now"
+  exit 1
+fi
+
+if ! mount | grep "${TARGET_DIR}" -q
+then
+  sudo mkdir -p "${TARGET_DIR}"
+
+  sudo mount "${JEVOIS_SD}" "${TARGET_DIR}"
 fi
 
 echo "Waiting for fs ..."
@@ -24,16 +73,20 @@
 echo "OK"
 
 echo "Copying files ..."
-cp ./austin_cam.sh "${TARGET_DIR}"/
-cp ./launch.sh "${TARGET_DIR}"/deploy/
+sudo cp ./austin_cam.sh "${TARGET_DIR}"/
+sudo cp ./launch.sh "${TARGET_DIR}"/deploy/
 
-cp "${BAZEL_BIN}/y2019/vision/target_sender" \
+(echo "git log"; git log -1; echo "git status"; git status) > /tmp/jevois_deploy_version
+
+sudo cp /tmp/jevois_deploy_version "${TARGET_DIR}"/version
+
+sudo cp "${BAZEL_BIN}/y2019/vision/target_sender" \
   "${BAZEL_BIN}/y2019/vision/serial_waiter" \
   "${TARGET_DIR}"/deploy/
 
 echo "Unmount sd card ..."
-umount "${TARGET_DIR}"
+sudo umount "${TARGET_DIR}"
 echo "OK"
 
 echo "Rebooting Jevois."
-./jevois-cmd restart
+./jevois-cmd -d "${JEVOIS_DEV}" restart
diff --git a/y2019/wpilib_interface.cc b/y2019/wpilib_interface.cc
index 2a21274..fd9df73 100644
--- a/y2019/wpilib_interface.cc
+++ b/y2019/wpilib_interface.cc
@@ -563,20 +563,20 @@
       time_since_last_send = 0;
     }
     if (status_light.green != last_green_ || time_since_last_send == 0) {
-      canifier_.SetLEDOutput(1.0 - status_light.green,
-                             ::ctre::phoenix::CANifier::LEDChannelB);
+      canifier_.SetLEDOutput(status_light.green,
+                             ::ctre::phoenix::CANifier::LEDChannelA);
       last_green_ = status_light.green;
     }
 
     if (status_light.blue != last_blue_ || time_since_last_send == 0) {
-      canifier_.SetLEDOutput(1.0 - status_light.blue,
-                             ::ctre::phoenix::CANifier::LEDChannelA);
+      canifier_.SetLEDOutput(status_light.blue,
+                             ::ctre::phoenix::CANifier::LEDChannelC);
       last_blue_ = status_light.blue;
     }
 
     if (status_light.red != last_red_ || time_since_last_send == 0) {
-      canifier_.SetLEDOutput(1.0 - status_light.red,
-                             ::ctre::phoenix::CANifier::LEDChannelC);
+      canifier_.SetLEDOutput(status_light.red,
+                             ::ctre::phoenix::CANifier::LEDChannelB);
       last_red_ = status_light.red;
     }
   }
diff --git a/yarn.lock b/yarn.lock
new file mode 100644
index 0000000..5fb2c43
--- /dev/null
+++ b/yarn.lock
@@ -0,0 +1,246 @@
+# THIS IS AN AUTOGENERATED FILE. DO NOT EDIT THIS FILE DIRECTLY.
+# yarn lockfile v1
+
+
+"@bazel/bazel-darwin_x64@0.19.1":
+  version "0.19.1"
+  resolved "https://registry.yarnpkg.com/@bazel/bazel-darwin_x64/-/bazel-darwin_x64-0.19.1.tgz#58d779c8938bd1c136cab55e2f6473121f83741b"
+
+"@bazel/bazel-linux_x64@0.19.1":
+  version "0.19.1"
+  resolved "https://registry.yarnpkg.com/@bazel/bazel-linux_x64/-/bazel-linux_x64-0.19.1.tgz#aef363e0932d29d1bb48980da139d74bfb4b1ffb"
+
+"@bazel/bazel-win32_x64@0.19.1":
+  version "0.19.1"
+  resolved "https://registry.yarnpkg.com/@bazel/bazel-win32_x64/-/bazel-win32_x64-0.19.1.tgz#273c43b0febc11675614c402ec82ae44b519f9ee"
+
+"@bazel/bazel@^0.19.1":
+  version "0.19.1"
+  resolved "https://registry.yarnpkg.com/@bazel/bazel/-/bazel-0.19.1.tgz#22ce225b5172a4ad2a94496be66b14b7c7facca2"
+  optionalDependencies:
+    "@bazel/bazel-darwin_x64" "0.19.1"
+    "@bazel/bazel-linux_x64" "0.19.1"
+    "@bazel/bazel-win32_x64" "0.19.1"
+
+"@bazel/typescript@0.21.0":
+  version "0.21.0"
+  resolved "https://registry.yarnpkg.com/@bazel/typescript/-/typescript-0.21.0.tgz#41c304f77a42c6a016280d0f4c20e0749c3f4b2a"
+  dependencies:
+    protobufjs "5.0.3"
+    source-map-support "0.5.9"
+    tsutils "2.27.2"
+
+ansi-regex@^2.0.0:
+  version "2.1.1"
+  resolved "https://registry.yarnpkg.com/ansi-regex/-/ansi-regex-2.1.1.tgz#c3b33ab5ee360d86e0e628f0468ae7ef27d654df"
+
+ascli@~1:
+  version "1.0.1"
+  resolved "https://registry.yarnpkg.com/ascli/-/ascli-1.0.1.tgz#bcfa5974a62f18e81cabaeb49732ab4a88f906bc"
+  dependencies:
+    colour "~0.7.1"
+    optjs "~3.2.2"
+
+balanced-match@^1.0.0:
+  version "1.0.0"
+  resolved "https://registry.yarnpkg.com/balanced-match/-/balanced-match-1.0.0.tgz#89b4d199ab2bee49de164ea02b89ce462d71b767"
+
+brace-expansion@^1.1.7:
+  version "1.1.11"
+  resolved "https://registry.yarnpkg.com/brace-expansion/-/brace-expansion-1.1.11.tgz#3c7fcbf529d87226f3d2f52b966ff5271eb441dd"
+  dependencies:
+    balanced-match "^1.0.0"
+    concat-map "0.0.1"
+
+buffer-from@^1.0.0:
+  version "1.1.1"
+  resolved "https://registry.yarnpkg.com/buffer-from/-/buffer-from-1.1.1.tgz#32713bc028f75c02fdb710d7c7bcec1f2c6070ef"
+
+bytebuffer@~5:
+  version "5.0.1"
+  resolved "https://registry.yarnpkg.com/bytebuffer/-/bytebuffer-5.0.1.tgz#582eea4b1a873b6d020a48d58df85f0bba6cfddd"
+  dependencies:
+    long "~3"
+
+camelcase@^2.0.1:
+  version "2.1.1"
+  resolved "https://registry.yarnpkg.com/camelcase/-/camelcase-2.1.1.tgz#7c1d16d679a1bbe59ca02cacecfb011e201f5a1f"
+
+cliui@^3.0.3:
+  version "3.2.0"
+  resolved "https://registry.yarnpkg.com/cliui/-/cliui-3.2.0.tgz#120601537a916d29940f934da3b48d585a39213d"
+  dependencies:
+    string-width "^1.0.1"
+    strip-ansi "^3.0.1"
+    wrap-ansi "^2.0.0"
+
+code-point-at@^1.0.0:
+  version "1.1.0"
+  resolved "https://registry.yarnpkg.com/code-point-at/-/code-point-at-1.1.0.tgz#0d070b4d043a5bea33a2f1a40e2edb3d9a4ccf77"
+
+colour@~0.7.1:
+  version "0.7.1"
+  resolved "https://registry.yarnpkg.com/colour/-/colour-0.7.1.tgz#9cb169917ec5d12c0736d3e8685746df1cadf778"
+
+concat-map@0.0.1:
+  version "0.0.1"
+  resolved "https://registry.yarnpkg.com/concat-map/-/concat-map-0.0.1.tgz#d8a96bd77fd68df7793a73036a3ba0d5405d477b"
+
+decamelize@^1.1.1:
+  version "1.2.0"
+  resolved "https://registry.yarnpkg.com/decamelize/-/decamelize-1.2.0.tgz#f6534d15148269b20352e7bee26f501f9a191290"
+
+fs.realpath@^1.0.0:
+  version "1.0.0"
+  resolved "https://registry.yarnpkg.com/fs.realpath/-/fs.realpath-1.0.0.tgz#1504ad2523158caa40db4a2787cb01411994ea4f"
+
+glob@^7.0.5:
+  version "7.1.3"
+  resolved "https://registry.yarnpkg.com/glob/-/glob-7.1.3.tgz#3960832d3f1574108342dafd3a67b332c0969df1"
+  dependencies:
+    fs.realpath "^1.0.0"
+    inflight "^1.0.4"
+    inherits "2"
+    minimatch "^3.0.4"
+    once "^1.3.0"
+    path-is-absolute "^1.0.0"
+
+inflight@^1.0.4:
+  version "1.0.6"
+  resolved "https://registry.yarnpkg.com/inflight/-/inflight-1.0.6.tgz#49bd6331d7d02d0c09bc910a1075ba8165b56df9"
+  dependencies:
+    once "^1.3.0"
+    wrappy "1"
+
+inherits@2:
+  version "2.0.3"
+  resolved "https://registry.yarnpkg.com/inherits/-/inherits-2.0.3.tgz#633c2c83e3da42a502f52466022480f4208261de"
+
+invert-kv@^1.0.0:
+  version "1.0.0"
+  resolved "https://registry.yarnpkg.com/invert-kv/-/invert-kv-1.0.0.tgz#104a8e4aaca6d3d8cd157a8ef8bfab2d7a3ffdb6"
+
+is-fullwidth-code-point@^1.0.0:
+  version "1.0.0"
+  resolved "https://registry.yarnpkg.com/is-fullwidth-code-point/-/is-fullwidth-code-point-1.0.0.tgz#ef9e31386f031a7f0d643af82fde50c457ef00cb"
+  dependencies:
+    number-is-nan "^1.0.0"
+
+lcid@^1.0.0:
+  version "1.0.0"
+  resolved "https://registry.yarnpkg.com/lcid/-/lcid-1.0.0.tgz#308accafa0bc483a3867b4b6f2b9506251d1b835"
+  dependencies:
+    invert-kv "^1.0.0"
+
+long@~3:
+  version "3.2.0"
+  resolved "https://registry.yarnpkg.com/long/-/long-3.2.0.tgz#d821b7138ca1cb581c172990ef14db200b5c474b"
+
+minimatch@^3.0.4:
+  version "3.0.4"
+  resolved "https://registry.yarnpkg.com/minimatch/-/minimatch-3.0.4.tgz#5166e286457f03306064be5497e8dbb0c3d32083"
+  dependencies:
+    brace-expansion "^1.1.7"
+
+number-is-nan@^1.0.0:
+  version "1.0.1"
+  resolved "https://registry.yarnpkg.com/number-is-nan/-/number-is-nan-1.0.1.tgz#097b602b53422a522c1afb8790318336941a011d"
+
+once@^1.3.0:
+  version "1.4.0"
+  resolved "https://registry.yarnpkg.com/once/-/once-1.4.0.tgz#583b1aa775961d4b113ac17d9c50baef9dd76bd1"
+  dependencies:
+    wrappy "1"
+
+optjs@~3.2.2:
+  version "3.2.2"
+  resolved "https://registry.yarnpkg.com/optjs/-/optjs-3.2.2.tgz#69a6ce89c442a44403141ad2f9b370bd5bb6f4ee"
+
+os-locale@^1.4.0:
+  version "1.4.0"
+  resolved "http://registry.npmjs.org/os-locale/-/os-locale-1.4.0.tgz#20f9f17ae29ed345e8bde583b13d2009803c14d9"
+  dependencies:
+    lcid "^1.0.0"
+
+path-is-absolute@^1.0.0:
+  version "1.0.1"
+  resolved "http://registry.npmjs.org/path-is-absolute/-/path-is-absolute-1.0.1.tgz#174b9268735534ffbc7ace6bf53a5a9e1b5c5f5f"
+
+protobufjs@5.0.3:
+  version "5.0.3"
+  resolved "https://registry.yarnpkg.com/protobufjs/-/protobufjs-5.0.3.tgz#e4dfe9fb67c90b2630d15868249bcc4961467a17"
+  dependencies:
+    ascli "~1"
+    bytebuffer "~5"
+    glob "^7.0.5"
+    yargs "^3.10.0"
+
+source-map-support@0.5.9:
+  version "0.5.9"
+  resolved "https://registry.yarnpkg.com/source-map-support/-/source-map-support-0.5.9.tgz#41bc953b2534267ea2d605bccfa7bfa3111ced5f"
+  dependencies:
+    buffer-from "^1.0.0"
+    source-map "^0.6.0"
+
+source-map@^0.6.0:
+  version "0.6.1"
+  resolved "https://registry.yarnpkg.com/source-map/-/source-map-0.6.1.tgz#74722af32e9614e9c287a8d0bbde48b5e2f1a263"
+
+string-width@^1.0.1:
+  version "1.0.2"
+  resolved "https://registry.yarnpkg.com/string-width/-/string-width-1.0.2.tgz#118bdf5b8cdc51a2a7e70d211e07e2b0b9b107d3"
+  dependencies:
+    code-point-at "^1.0.0"
+    is-fullwidth-code-point "^1.0.0"
+    strip-ansi "^3.0.0"
+
+strip-ansi@^3.0.0, strip-ansi@^3.0.1:
+  version "3.0.1"
+  resolved "http://registry.npmjs.org/strip-ansi/-/strip-ansi-3.0.1.tgz#6a385fb8853d952d5ff05d0e8aaf94278dc63dcf"
+  dependencies:
+    ansi-regex "^2.0.0"
+
+tslib@^1.8.1:
+  version "1.9.3"
+  resolved "https://registry.yarnpkg.com/tslib/-/tslib-1.9.3.tgz#d7e4dd79245d85428c4d7e4822a79917954ca286"
+
+tsutils@2.27.2:
+  version "2.27.2"
+  resolved "https://registry.yarnpkg.com/tsutils/-/tsutils-2.27.2.tgz#60ba88a23d6f785ec4b89c6e8179cac9b431f1c7"
+  dependencies:
+    tslib "^1.8.1"
+
+typescript@^3.1.6:
+  version "3.1.6"
+  resolved "https://registry.yarnpkg.com/typescript/-/typescript-3.1.6.tgz#b6543a83cfc8c2befb3f4c8fba6896f5b0c9be68"
+
+window-size@^0.1.4:
+  version "0.1.4"
+  resolved "https://registry.yarnpkg.com/window-size/-/window-size-0.1.4.tgz#f8e1aa1ee5a53ec5bf151ffa09742a6ad7697876"
+
+wrap-ansi@^2.0.0:
+  version "2.1.0"
+  resolved "http://registry.npmjs.org/wrap-ansi/-/wrap-ansi-2.1.0.tgz#d8fc3d284dd05794fe84973caecdd1cf824fdd85"
+  dependencies:
+    string-width "^1.0.1"
+    strip-ansi "^3.0.1"
+
+wrappy@1:
+  version "1.0.2"
+  resolved "https://registry.yarnpkg.com/wrappy/-/wrappy-1.0.2.tgz#b5243d8f3ec1aa35f1364605bc0d1036e30ab69f"
+
+y18n@^3.2.0:
+  version "3.2.1"
+  resolved "https://registry.yarnpkg.com/y18n/-/y18n-3.2.1.tgz#6d15fba884c08679c0d77e88e7759e811e07fa41"
+
+yargs@^3.10.0:
+  version "3.32.0"
+  resolved "http://registry.npmjs.org/yargs/-/yargs-3.32.0.tgz#03088e9ebf9e756b69751611d2a5ef591482c995"
+  dependencies:
+    camelcase "^2.0.1"
+    cliui "^3.0.3"
+    decamelize "^1.1.1"
+    os-locale "^1.4.0"
+    string-width "^1.0.1"
+    window-size "^0.1.4"
+    y18n "^3.2.0"