Convert y2017_bot3 over to use the new SensorReader class

Another step in converting to event loops.

Change-Id: I483b353a2aa991fc827cc71be5c260de09999257
diff --git a/y2017_bot3/BUILD b/y2017_bot3/BUILD
index 9841d08..b1c68ce 100644
--- a/y2017_bot3/BUILD
+++ b/y2017_bot3/BUILD
@@ -31,28 +31,20 @@
     deps = [
         "//aos:init",
         "//aos:make_unique",
-        "//aos:math",
         "//aos/controls:control_loop",
         "//aos/logging",
         "//aos/logging:queue_logging",
-        "//aos/robot_state",
-        "//aos/stl_mutex",
         "//aos/time",
         "//aos/util:log_interval",
         "//aos/util:phased_loop",
-        "//frc971/control_loops:queues",
         "//frc971/control_loops/drivetrain:drivetrain_queue",
         "//frc971/wpilib:buffered_pcm",
-        "//frc971/wpilib:dma",
-        "//frc971/wpilib:dma_edge_counting",
-        "//frc971/wpilib:encoder_and_potentiometer",
         "//frc971/wpilib:gyro_sender",
-        "//frc971/wpilib:interrupt_edge_counting",
         "//frc971/wpilib:joystick_sender",
         "//frc971/wpilib:logging_queue",
         "//frc971/wpilib:loop_output_handler",
         "//frc971/wpilib:pdp_fetcher",
-        "//frc971/wpilib:wpilib_interface",
+        "//frc971/wpilib:sensor_reader",
         "//frc971/wpilib:wpilib_robot_base",
         "//third_party:wpilib",
         "//y2017_bot3/control_loops/drivetrain:polydrivetrain_plants",
diff --git a/y2017_bot3/wpilib_interface.cc b/y2017_bot3/wpilib_interface.cc
index c3c4f37..e191e1f 100644
--- a/y2017_bot3/wpilib_interface.cc
+++ b/y2017_bot3/wpilib_interface.cc
@@ -7,7 +7,6 @@
 #include <chrono>
 #include <cmath>
 #include <functional>
-#include <mutex>
 #include <thread>
 
 #include "frc971/wpilib/ahal/AnalogInput.h"
@@ -18,35 +17,23 @@
 #include "frc971/wpilib/ahal/VictorSP.h"
 #undef ERROR
 
-#include "aos/commonmath.h"
 #include "aos/init.h"
 #include "aos/logging/logging.h"
 #include "aos/logging/queue_logging.h"
 #include "aos/make_unique.h"
-#include "aos/robot_state/robot_state.q.h"
-#include "aos/stl_mutex/stl_mutex.h"
 #include "aos/time/time.h"
-#include "aos/util/compiler_memory_barrier.h"
-#include "aos/util/log_interval.h"
 #include "aos/util/phased_loop.h"
-
-#include "frc971/control_loops/control_loops.q.h"
 #include "frc971/control_loops/drivetrain/drivetrain.q.h"
 #include "frc971/wpilib/buffered_pcm.h"
 #include "frc971/wpilib/buffered_solenoid.h"
-#include "frc971/wpilib/gyro_sender.h"
 #include "frc971/wpilib/dma.h"
-#include "frc971/wpilib/dma_edge_counting.h"
-#include "frc971/wpilib/encoder_and_potentiometer.h"
-#include "frc971/wpilib/interrupt_edge_counting.h"
+#include "frc971/wpilib/gyro_sender.h"
 #include "frc971/wpilib/joystick_sender.h"
 #include "frc971/wpilib/logging.q.h"
 #include "frc971/wpilib/loop_output_handler.h"
 #include "frc971/wpilib/pdp_fetcher.h"
-#include "frc971/wpilib/wpilib_interface.h"
+#include "frc971/wpilib/sensor_reader.h"
 #include "frc971/wpilib/wpilib_robot_base.h"
-
-#include "frc971/control_loops/drivetrain/drivetrain.q.h"
 #include "y2017_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
 #include "y2017_bot3/control_loops/superstructure/superstructure.q.h"
 
@@ -116,26 +103,12 @@
               "fast encoders are too fast");
 
 // Class to send position messages with sensor readings to our loops.
-class SensorReader {
+class SensorReader : public ::frc971::wpilib::SensorReader {
  public:
   SensorReader() {
     // Set to filter out anything shorter than 1/4 of the minimum pulse width
     // we should ever see.
-    fast_encoder_filter_.SetPeriodNanoSeconds(
-        static_cast<int>(1 / 4.0 /* built-in tolerance */ /
-                             kMaxFastEncoderPulsesPerSecond * 1e9 +
-                         0.5));
-    hall_filter_.SetPeriodNanoSeconds(100000);
-  }
-
-  void set_drivetrain_left_encoder(::std::unique_ptr<Encoder> encoder) {
-    fast_encoder_filter_.Add(encoder.get());
-    drivetrain_left_encoder_ = ::std::move(encoder);
-  }
-
-  void set_drivetrain_right_encoder(::std::unique_ptr<Encoder> encoder) {
-    fast_encoder_filter_.Add(encoder.get());
-    drivetrain_right_encoder_ = ::std::move(encoder);
+    UpdateFastEncoderFilterHz(kMaxFastEncoderPulsesPerSecond);
   }
 
   void set_drivetrain_left_hall(::std::unique_ptr<AnalogInput> analog) {
@@ -146,138 +119,7 @@
     drivetrain_right_hall_ = ::std::move(analog);
   }
 
-  void set_pwm_trigger(::std::unique_ptr<DigitalInput> pwm_trigger) {
-    medium_encoder_filter_.Add(pwm_trigger.get());
-    pwm_trigger_ = ::std::move(pwm_trigger);
-  }
-
-  // All of the DMA-related set_* calls must be made before this, and it
-  // doesn't
-  // hurt to do all of them.
-  void set_dma(::std::unique_ptr<DMA> dma) {
-    dma_synchronizer_.reset(
-        new ::frc971::wpilib::DMASynchronizer(::std::move(dma)));
-  }
-
-  void RunPWMDetecter() {
-    ::aos::SetCurrentThreadRealtimePriority(41);
-
-    pwm_trigger_->RequestInterrupts();
-    // Rising edge only.
-    pwm_trigger_->SetUpSourceEdge(true, false);
-
-    monotonic_clock::time_point last_posedge_monotonic =
-        monotonic_clock::min_time;
-
-    while (run_) {
-      auto ret = pwm_trigger_->WaitForInterrupt(1.0, true);
-      if (ret == InterruptableSensorBase::WaitResult::kRisingEdge) {
-        // Grab all the clocks.
-        const double pwm_fpga_time = pwm_trigger_->ReadRisingTimestamp();
-
-        aos_compiler_memory_barrier();
-        const double fpga_time_before = GetFPGATime() * 1e-6;
-        aos_compiler_memory_barrier();
-        const monotonic_clock::time_point monotonic_now =
-            monotonic_clock::now();
-        aos_compiler_memory_barrier();
-        const double fpga_time_after = GetFPGATime() * 1e-6;
-        aos_compiler_memory_barrier();
-
-        const double fpga_offset =
-            (fpga_time_after + fpga_time_before) / 2.0 - pwm_fpga_time;
-
-        // Compute when the edge was.
-        const monotonic_clock::time_point monotonic_edge =
-            monotonic_now - chrono::duration_cast<chrono::nanoseconds>(
-                                chrono::duration<double>(fpga_offset));
-
-        LOG(INFO, "Got PWM pulse %f spread, %f offset, %lld trigger\n",
-            fpga_time_after - fpga_time_before, fpga_offset,
-            monotonic_edge.time_since_epoch().count());
-
-        // Compute bounds on the timestep and sampling times.
-        const double fpga_sample_length = fpga_time_after - fpga_time_before;
-        const chrono::nanoseconds elapsed_time =
-            monotonic_edge - last_posedge_monotonic;
-
-        last_posedge_monotonic = monotonic_edge;
-
-        // Verify that the values are sane.
-        if (fpga_sample_length > 2e-5 || fpga_sample_length < 0) {
-          continue;
-        }
-        if (fpga_offset < 0 || fpga_offset > 0.00015) {
-          continue;
-        }
-        if (elapsed_time >
-                chrono::microseconds(5050) + chrono::microseconds(4) ||
-            elapsed_time <
-                chrono::microseconds(5050) - chrono::microseconds(4)) {
-          continue;
-        }
-        // Good edge!
-        {
-          ::std::unique_lock<::aos::stl_mutex> locker(tick_time_mutex_);
-          last_tick_time_monotonic_timepoint_ = last_posedge_monotonic;
-          last_period_ = elapsed_time;
-        }
-      } else {
-        LOG(INFO, "PWM triggered %d\n", ret);
-      }
-    }
-    pwm_trigger_->CancelInterrupts();
-  }
-
-  void operator()() {
-    ::aos::SetCurrentThreadName("SensorReader");
-
-    my_pid_ = getpid();
-
-    dma_synchronizer_->Start();
-
-    ::aos::time::PhasedLoop phased_loop(last_period_,
-                                        ::std::chrono::milliseconds(3));
-    chrono::nanoseconds filtered_period = last_period_;
-
-    ::std::thread pwm_detecter_thread(
-        ::std::bind(&SensorReader::RunPWMDetecter, this));
-
-    ::aos::SetCurrentThreadRealtimePriority(40);
-    while (run_) {
-      {
-        const int iterations = phased_loop.SleepUntilNext();
-        if (iterations != 1) {
-          LOG(WARNING, "SensorReader skipped %d iterations\n", iterations - 1);
-        }
-      }
-      RunIteration();
-
-      monotonic_clock::time_point last_tick_timepoint;
-      chrono::nanoseconds period;
-      {
-        ::std::unique_lock<::aos::stl_mutex> locker(tick_time_mutex_);
-        last_tick_timepoint = last_tick_time_monotonic_timepoint_;
-        period = last_period_;
-      }
-
-      if (last_tick_timepoint == monotonic_clock::min_time) {
-        continue;
-      }
-      chrono::nanoseconds new_offset = phased_loop.OffsetFromIntervalAndTime(
-          period, last_tick_timepoint + chrono::microseconds(2050));
-
-      // TODO(austin): If this is the first edge in a while, skip to it (plus
-      // an offset). Otherwise, slowly drift time to line up.
-
-      phased_loop.set_interval_and_offset(period, new_offset);
-    }
-    pwm_detecter_thread.join();
-  }
-
   void RunIteration() {
-    ::frc971::wpilib::SendRobotState(my_pid_);
-
     {
       auto drivetrain_message = drivetrain_queue.position.MakeMessage();
       drivetrain_message->right_encoder =
@@ -302,39 +144,10 @@
       auto superstructure_message = superstructure_queue.position.MakeMessage();
       superstructure_message.Send();
     }
-    dma_synchronizer_->RunIteration();
   }
 
-  void Quit() { run_ = false; }
-
  private:
-  double encoder_translate(int32_t value, double counts_per_revolution,
-                           double ratio) {
-    return static_cast<double>(value) / counts_per_revolution * ratio *
-           (2.0 * M_PI);
-  }
-
-  int32_t my_pid_;
-
-  // Mutex to manage access to the period and tick time variables.
-  ::aos::stl_mutex tick_time_mutex_;
-  monotonic_clock::time_point last_tick_time_monotonic_timepoint_ =
-      monotonic_clock::min_time;
-  chrono::nanoseconds last_period_ = chrono::microseconds(5050);
-
-  ::std::unique_ptr<::frc971::wpilib::DMASynchronizer> dma_synchronizer_;
-
-  ::std::unique_ptr<Encoder> drivetrain_left_encoder_,
-      drivetrain_right_encoder_;
-
   ::std::unique_ptr<AnalogInput> drivetrain_left_hall_, drivetrain_right_hall_;
-
-  ::std::unique_ptr<DigitalInput> pwm_trigger_;
-
-  ::std::atomic<bool> run_{true};
-
-  DigitalGlitchFilter fast_encoder_filter_, medium_encoder_filter_,
-      hall_filter_;
 };
 
 class SolenoidWriter {