Convert all year's robots to proper event loops

Each robot has a couple of event loops, one per thread.  Each of these
threads corresponds to the threads from before the change.  y2016 has
been tested on real hardware.

Change-Id: I99f726a8bc0498204c1a3b99f15508119eed9ad3
diff --git a/frc971/wpilib/ADIS16448.cc b/frc971/wpilib/ADIS16448.cc
index 75f082d..38d194d 100644
--- a/frc971/wpilib/ADIS16448.cc
+++ b/frc971/wpilib/ADIS16448.cc
@@ -139,6 +139,17 @@
 
   dio1_->RequestInterrupts();
   dio1_->SetUpSourceEdge(true, false);
+
+  // NI's SPI driver defaults to SCHED_OTHER.  Find it's PID with ps, and change
+  // it to a RT priority of 33.
+  PCHECK(
+      system("ps -ef | grep '\\[spi0\\]' | awk '{print $1}' | xargs chrt -f -p "
+             "33") == 0);
+
+  event_loop_->set_name("IMU");
+  event_loop_->SetRuntimeRealtimePriority(33);
+
+  event_loop_->OnRun([this]() { DoRun(); });
 }
 
 void ADIS16448::SetDummySPI(frc::SPI::Port port) {
@@ -155,7 +166,7 @@
 }
 
 void ADIS16448::InitializeUntilSuccessful() {
-  while (run_ && !Initialize()) {
+  while (event_loop_->is_running() && !Initialize()) {
     if (reset_) {
       reset_->Set(false);
       // Datasheet says this needs to be at least 10 us long, so 10 ms is
@@ -170,19 +181,9 @@
     }
   }
   LOG(INFO, "IMU initialized successfully\n");
-
-  ::aos::SetCurrentThreadRealtimePriority(33);
 }
 
-void ADIS16448::operator()() {
-  // NI's SPI driver defaults to SCHED_OTHER.  Find it's PID with ps, and change
-  // it to a RT priority of 33.
-  PCHECK(
-      system("ps -ef | grep '\\[spi0\\]' | awk '{print $1}' | xargs chrt -f -p "
-             "33") == 0);
-
-  ::aos::SetCurrentThreadName("IMU");
-
+void ADIS16448::DoRun() {
   InitializeUntilSuccessful();
 
   // Rounded to approximate the 204.8 Hz.
@@ -193,8 +194,10 @@
   zeroing::Averager<double, 6 * kImuSendRate> average_gyro_z;
 
   bool got_an_interrupt = false;
-  while (run_) {
+  while (event_loop_->is_running()) {
     {
+      // Wait for an interrupt.  (This prevents us from going to sleep in the
+      // event loop like we normally would)
       const frc::InterruptableSensorBase::WaitResult result =
           dio1_->WaitForInterrupt(0.1, !got_an_interrupt);
       if (result == frc::InterruptableSensorBase::kTimeout) {
diff --git a/frc971/wpilib/ADIS16448.h b/frc971/wpilib/ADIS16448.h
index 5af6a4f..6aeac9d 100644
--- a/frc971/wpilib/ADIS16448.h
+++ b/frc971/wpilib/ADIS16448.h
@@ -43,25 +43,21 @@
   // Sets the reset line for the IMU to use for error recovery.
   void set_reset(frc::DigitalOutput *output) { reset_ = output; }
 
-  // For ::std::thread to call.
-  //
-  // Initializes the sensor and then loops until Quit() is called taking
-  // readings.
-  void operator()();
-
   // Sets a function to be called immediately after each time this class uses
   // the SPI bus. This is a good place to do other things on the bus.
   void set_spi_idle_callback(std::function<void()> spi_idle_callback) {
     spi_idle_callback_ = std::move(spi_idle_callback);
   }
 
-  void Quit() { run_ = false; }
-
   double gyro_x_zeroed_offset() const { return gyro_x_zeroed_offset_; }
   double gyro_y_zeroed_offset() const { return gyro_y_zeroed_offset_; }
   double gyro_z_zeroed_offset() const { return gyro_z_zeroed_offset_; }
 
  private:
+  // Initializes the sensor and then loops until Quit() is called taking
+  // readings.
+  void DoRun();
+
   // Try to initialize repeatedly as long as we're supposed to be running.
   void InitializeUntilSuccessful();
 
@@ -104,7 +100,6 @@
   frc::DigitalOutput *reset_ = nullptr;
 
   std::function<void()> spi_idle_callback_ = []() {};
-  ::std::atomic<bool> run_{true};
 
   // The averaged values of the gyro over 6 seconds after power up.
   bool gyros_are_zeroed_ = false;
diff --git a/frc971/wpilib/BUILD b/frc971/wpilib/BUILD
index c6e72a4..870e655 100644
--- a/frc971/wpilib/BUILD
+++ b/frc971/wpilib/BUILD
@@ -118,6 +118,13 @@
     ],
 )
 
+queue_library(
+    name = "loop_output_handler_test_queue",
+    srcs = [
+        "loop_output_handler_test.q",
+    ],
+)
+
 cc_library(
     name = "loop_output_handler",
     srcs = [
@@ -136,6 +143,21 @@
     ],
 )
 
+cc_test(
+    name = "loop_output_handler_test",
+    srcs = [
+        "loop_output_handler_test.cc",
+    ],
+    deps = [
+        ":loop_output_handler",
+        ":loop_output_handler_test_queue",
+        "//aos/events:simulated_event_loop",
+        "//aos/logging:queue_logging",
+        "//aos/testing:googletest",
+        "//aos/testing:test_logging",
+    ],
+)
+
 cc_library(
     name = "joystick_sender",
     srcs = [
diff --git a/frc971/wpilib/drivetrain_writer.cc b/frc971/wpilib/drivetrain_writer.cc
index 8d388dc..fdbc028 100644
--- a/frc971/wpilib/drivetrain_writer.cc
+++ b/frc971/wpilib/drivetrain_writer.cc
@@ -10,27 +10,23 @@
 namespace frc971 {
 namespace wpilib {
 
-void DrivetrainWriter::Write() {
-  auto &queue = ::frc971::control_loops::drivetrain_queue.output;
-  LOG_STRUCT(DEBUG, "will output", *queue);
-  left_controller0_->SetSpeed(SafeSpeed(reversed_left0_, queue->left_voltage));
+void DrivetrainWriter::Write(
+    const ::frc971::control_loops::DrivetrainQueue::Output &output) {
+  LOG_STRUCT(DEBUG, "will output", output);
+  left_controller0_->SetSpeed(SafeSpeed(reversed_left0_, output.left_voltage));
   right_controller0_->SetSpeed(
-      SafeSpeed(reversed_right0_, queue->right_voltage));
+      SafeSpeed(reversed_right0_, output.right_voltage));
 
   if (left_controller1_) {
     left_controller1_->SetSpeed(
-        SafeSpeed(reversed_left1_, queue->left_voltage));
+        SafeSpeed(reversed_left1_, output.left_voltage));
   }
   if (right_controller1_) {
     right_controller1_->SetSpeed(
-        SafeSpeed(reversed_right1_, queue->right_voltage));
+        SafeSpeed(reversed_right1_, output.right_voltage));
   }
 }
 
-void DrivetrainWriter::Read() {
-  ::frc971::control_loops::drivetrain_queue.output.FetchAnother();
-}
-
 void DrivetrainWriter::Stop() {
   LOG(WARNING, "drivetrain output too old\n");
   left_controller0_->SetDisabled();
diff --git a/frc971/wpilib/drivetrain_writer.h b/frc971/wpilib/drivetrain_writer.h
index ea3df46..9397230 100644
--- a/frc971/wpilib/drivetrain_writer.h
+++ b/frc971/wpilib/drivetrain_writer.h
@@ -3,16 +3,20 @@
 
 #include "aos/commonmath.h"
 
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
 #include "frc971/wpilib/ahal/PWM.h"
 #include "frc971/wpilib/loop_output_handler.h"
 
 namespace frc971 {
 namespace wpilib {
 
-class DrivetrainWriter : public ::frc971::wpilib::LoopOutputHandler {
+class DrivetrainWriter : public ::frc971::wpilib::LoopOutputHandler<
+                             ::frc971::control_loops::DrivetrainQueue::Output> {
  public:
   DrivetrainWriter(::aos::EventLoop *event_loop)
-      : ::frc971::wpilib::LoopOutputHandler(event_loop) {}
+      : ::frc971::wpilib::LoopOutputHandler<
+            ::frc971::control_loops::DrivetrainQueue::Output>(
+            event_loop, ".frc971.control_loops.drivetrain_queue.output") {}
 
   void set_left_controller0(::std::unique_ptr<::frc::PWM> t, bool reversed) {
     left_controller0_ = ::std::move(t);
@@ -35,8 +39,8 @@
   }
 
  private:
-  void Write() override;
-  void Read() override;
+  void Write(
+      const ::frc971::control_loops::DrivetrainQueue::Output &output) override;
   void Stop() override;
 
   double SafeSpeed(bool reversed, double voltage) {
diff --git a/frc971/wpilib/gyro_sender.cc b/frc971/wpilib/gyro_sender.cc
index 99dc735..b1edbd2 100644
--- a/frc971/wpilib/gyro_sender.cc
+++ b/frc971/wpilib/gyro_sender.cc
@@ -13,7 +13,6 @@
 #include "aos/logging/queue_logging.h"
 #include "aos/robot_state/robot_state.q.h"
 #include "aos/time/time.h"
-#include "aos/util/phased_loop.h"
 
 #include "frc971/queues/gyro.q.h"
 #include "frc971/zeroing/averager.h"
@@ -36,124 +35,117 @@
   PCHECK(
       system("ps -ef | grep '\\[spi0\\]' | awk '{print $1}' | xargs chrt -f -p "
              "33") == 0);
+  event_loop_->set_name("Gyro");
+  event_loop_->SetRuntimeRealtimePriority(33);
+
+  // TODO(austin): This should be synchronized with SensorReader...  Pull out
+  // the sync logic and re-use it here.
+  event_loop_->AddPhasedLoop([this](int iterations) { Loop(iterations); },
+                             ::aos::time::FromRate(kReadingRate),
+                             chrono::milliseconds(4));
 }
 
-void GyroSender::operator()() {
-  ::aos::SetCurrentThreadName("Gyro");
+void GyroSender::Loop(const int iterations) {
+  switch (state_) {
+    case State::INITIALIZING: {
+      const monotonic_clock::time_point monotonic_now =
+          event_loop_->monotonic_now();
+      if (last_initialize_time_ + chrono::milliseconds(50) < monotonic_now) {
+        if (gyro_.InitializeGyro()) {
+          state_ = State::RUNNING;
+          LOG(INFO, "gyro initialized successfully\n");
 
-  // Try to initialize repeatedly as long as we're supposed to be running.
-  while (run_ && !gyro_.InitializeGyro()) {
-    ::std::this_thread::sleep_for(::std::chrono::milliseconds(50));
-  }
-  LOG(INFO, "gyro initialized successfully\n");
-
-  auto message = uid_sender_.MakeMessage();
-  message->uid = gyro_.ReadPartID();
-  LOG_STRUCT(INFO, "gyro ID", *message);
-  message.Send();
-
-  // In radians, ready to send out.
-  double angle = 0;
-
-  int startup_cycles_left = 2 * kReadingRate;
-
-  zeroing::Averager<double, 6 * kReadingRate> zeroing_data;
-  bool zeroed = false;
-  double zero_offset = 0;
-
-  ::aos::SetCurrentThreadRealtimePriority(33);
-
-  ::aos::time::PhasedLoop phased_loop(::aos::time::FromRate(kReadingRate),
-                                      event_loop_->monotonic_now(),
-                                      chrono::milliseconds(4));
-  // How many timesteps the next reading represents.
-  int number_readings = 0;
-
-  ::aos::SetCurrentThreadRealtimePriority(33);
-
-  while (run_) {
-    number_readings += phased_loop.SleepUntilNext();
-
-    const uint32_t result = gyro_.GetReading();
-    if (result == 0) {
-      LOG(WARNING, "normal gyro read failed\n");
-      continue;
-    }
-    switch (gyro_.ExtractStatus(result)) {
-      case 0:
-        LOG(WARNING, "gyro says data is bad\n");
-        continue;
-      case 1:
-        break;
-      default:
-        LOG(WARNING, "gyro gave weird status 0x%" PRIx8 "\n",
-            gyro_.ExtractStatus(result));
-        continue;
-    }
-    if (gyro_.ExtractErrors(result) != 0) {
-      const uint8_t errors = gyro_.ExtractErrors(result);
-      if (errors & (1 << 6)) {
-        LOG(WARNING, "gyro gave PLL error\n");
+          {
+            auto message = uid_sender_.MakeMessage();
+            message->uid = gyro_.ReadPartID();
+            LOG_STRUCT(INFO, "gyro ID", *message);
+            message.Send();
+          }
+        }
+        last_initialize_time_ = monotonic_now;
       }
-      if (errors & (1 << 5)) {
-        LOG(WARNING, "gyro gave quadrature error\n");
+    } break;
+    case State::RUNNING: {
+      const uint32_t result = gyro_.GetReading();
+      if (result == 0) {
+        LOG(WARNING, "normal gyro read failed\n");
+        return;
       }
-      if (errors & (1 << 4)) {
-        LOG(WARNING, "gyro gave non-volatile memory error\n");
+      switch (gyro_.ExtractStatus(result)) {
+        case 0:
+          LOG(WARNING, "gyro says data is bad\n");
+          return;
+        case 1:
+          break;
+        default:
+          LOG(WARNING, "gyro gave weird status 0x%" PRIx8 "\n",
+              gyro_.ExtractStatus(result));
+          return;
       }
-      if (errors & (1 << 3)) {
-        LOG(WARNING, "gyro gave volatile memory error\n");
+      if (gyro_.ExtractErrors(result) != 0) {
+        const uint8_t errors = gyro_.ExtractErrors(result);
+        if (errors & (1 << 6)) {
+          LOG(WARNING, "gyro gave PLL error\n");
+        }
+        if (errors & (1 << 5)) {
+          LOG(WARNING, "gyro gave quadrature error\n");
+        }
+        if (errors & (1 << 4)) {
+          LOG(WARNING, "gyro gave non-volatile memory error\n");
+        }
+        if (errors & (1 << 3)) {
+          LOG(WARNING, "gyro gave volatile memory error\n");
+        }
+        if (errors & (1 << 2)) {
+          LOG(WARNING, "gyro gave power error\n");
+        }
+        if (errors & (1 << 1)) {
+          LOG(WARNING, "gyro gave continuous self-test error\n");
+        }
+        if (errors & 1) {
+          LOG(WARNING, "gyro gave unexpected self-test mode\n");
+        }
+        return;
       }
-      if (errors & (1 << 2)) {
-        LOG(WARNING, "gyro gave power error\n");
-      }
-      if (errors & (1 << 1)) {
-        LOG(WARNING, "gyro gave continuous self-test error\n");
-      }
-      if (errors & 1) {
-        LOG(WARNING, "gyro gave unexpected self-test mode\n");
-      }
-      continue;
-    }
 
-    if (startup_cycles_left > 0) {
-      --startup_cycles_left;
-      continue;
-    }
+      if (startup_cycles_left_ > 0) {
+        --startup_cycles_left_;
+        return;
+      }
 
-    const double angle_rate = gyro_.ExtractAngle(result);
-    const double new_angle = angle_rate / static_cast<double>(kReadingRate);
-    auto message = gyro_reading_sender_.MakeMessage();
-    if (zeroed) {
-      angle += (new_angle + zero_offset) * number_readings;
-      message->angle = angle;
-      message->velocity = angle_rate + zero_offset * kReadingRate;
-      LOG_STRUCT(DEBUG, "sending", *message);
-      message.Send();
-    } else {
-      // TODO(brian): Don't break without 6 seconds of standing still before
-      // enabling. Ideas:
-      //   Don't allow driving until we have at least some data?
-      //   Some kind of indicator light?
-      {
-        message->angle = new_angle;
-        message->velocity = angle_rate;
-        LOG_STRUCT(DEBUG, "collected while zeroing", *message);
-        message->angle = 0.0;
-        message->velocity = 0.0;
+      const double angle_rate = gyro_.ExtractAngle(result);
+      const double new_angle = angle_rate / static_cast<double>(kReadingRate);
+      auto message = gyro_reading_sender_.MakeMessage();
+      if (zeroed_) {
+        angle_ += (new_angle + zero_offset_) * iterations;
+        message->angle = angle_;
+        message->velocity = angle_rate + zero_offset_ * kReadingRate;
+        LOG_STRUCT(DEBUG, "sending", *message);
         message.Send();
-      }
-      zeroing_data.AddData(new_angle);
+      } else {
+        // TODO(brian): Don't break without 6 seconds of standing still before
+        // enabling. Ideas:
+        //   Don't allow driving until we have at least some data?
+        //   Some kind of indicator light?
+        {
+          message->angle = new_angle;
+          message->velocity = angle_rate;
+          LOG_STRUCT(DEBUG, "collected while zeroing", *message);
+          message->angle = 0.0;
+          message->velocity = 0.0;
+          message.Send();
+        }
+        zeroing_data_.AddData(new_angle);
 
-      joystick_state_fetcher_.Fetch();
-      if (joystick_state_fetcher_.get() && joystick_state_fetcher_->enabled &&
-          zeroing_data.full()) {
-        zero_offset = -zeroing_data.GetAverage();
-        LOG(INFO, "total zero offset %f\n", zero_offset);
-        zeroed = true;
+        joystick_state_fetcher_.Fetch();
+        if (joystick_state_fetcher_.get() && joystick_state_fetcher_->enabled &&
+            zeroing_data_.full()) {
+          zero_offset_ = -zeroing_data_.GetAverage();
+          LOG(INFO, "total zero offset %f\n", zero_offset_);
+          zeroed_ = true;
+        }
       }
-    }
-    number_readings = 0;
+    } break;
   }
 }
 
diff --git a/frc971/wpilib/gyro_sender.h b/frc971/wpilib/gyro_sender.h
index 338ad32..3a43391 100644
--- a/frc971/wpilib/gyro_sender.h
+++ b/frc971/wpilib/gyro_sender.h
@@ -9,6 +9,7 @@
 #include "aos/robot_state/robot_state.q.h"
 #include "frc971/queues/gyro.q.h"
 #include "frc971/wpilib/gyro_interface.h"
+#include "frc971/zeroing/averager.h"
 
 namespace frc971 {
 namespace wpilib {
@@ -21,25 +22,37 @@
  public:
   GyroSender(::aos::EventLoop *event_loop);
 
-  // For ::std::thread to call.
-  //
-  // Initializes the gyro and then loops until Quit() is called taking readings.
-  void operator()();
-
-  void Quit() { run_ = false; }
+  enum class State { INITIALIZING, RUNNING };
 
  private:
+  // Initializes the gyro and then loops until Exit() is called on the event
+  // loop, taking readings.
+  void Loop(const int iterations);
+
   ::aos::EventLoop *event_loop_;
   ::aos::Fetcher<::aos::JoystickState> joystick_state_fetcher_;
   ::aos::Sender<::frc971::sensors::Uid> uid_sender_;
   ::aos::Sender<::frc971::sensors::GyroReading> gyro_reading_sender_;
 
   // Readings per second.
-  static const int kReadingRate = 200;
+  static constexpr int kReadingRate = 200;
 
   GyroInterface gyro_;
 
-  ::std::atomic<bool> run_{true};
+  State state_ = State::INITIALIZING;
+
+  // In radians, ready to send out.
+  double angle_ = 0;
+  // Calibrated offset.
+  double zero_offset_ = 0;
+
+  ::aos::monotonic_clock::time_point last_initialize_time_ =
+      ::aos::monotonic_clock::min_time;
+  int startup_cycles_left_ = 2 * kReadingRate;
+
+  zeroing::Averager<double, 6 * kReadingRate> zeroing_data_;
+
+  bool zeroed_ = false;
 };
 
 }  // namespace wpilib
diff --git a/frc971/wpilib/joystick_sender.cc b/frc971/wpilib/joystick_sender.cc
index a71ab9c..a073066 100644
--- a/frc971/wpilib/joystick_sender.cc
+++ b/frc971/wpilib/joystick_sender.cc
@@ -11,51 +11,57 @@
 namespace frc971 {
 namespace wpilib {
 
-void JoystickSender::operator()() {
-  frc::DriverStation *const ds = &frc::DriverStation::GetInstance();
-  ::aos::SetCurrentThreadName("DSReader");
-  uint16_t team_id = ::aos::network::GetTeamNumber();
+JoystickSender::JoystickSender(::aos::EventLoop *event_loop)
+    : event_loop_(event_loop),
+      joystick_state_sender_(
+          event_loop_->MakeSender<::aos::JoystickState>(".aos.joystick_state")),
+      team_id_(::aos::network::GetTeamNumber()) {
 
-  ::aos::SetCurrentThreadRealtimePriority(29);
+  event_loop_->SetRuntimeRealtimePriority(29);
 
-  // TODO(Brian): Fix the potential deadlock when stopping here (condition
-  // variable / mutex needs to get exposed all the way out or something).
-  while (run_) {
-    ds->RunIteration([&]() {
-      auto new_state = joystick_state_sender_.MakeMessage();
+  event_loop_->OnRun([this]() {
+    frc::DriverStation *const ds = &frc::DriverStation::GetInstance();
+    ::aos::SetCurrentThreadName("DSReader");
 
-      HAL_MatchInfo match_info;
-      auto status = HAL_GetMatchInfo(&match_info);
-      if (status == 0) {
-        new_state->switch_left = match_info.gameSpecificMessage[0] == 'L' ||
-                                 match_info.gameSpecificMessage[0] == 'l';
-        new_state->scale_left = match_info.gameSpecificMessage[1] == 'L' ||
-                                match_info.gameSpecificMessage[1] == 'l';
-      }
+    // TODO(Brian): Fix the potential deadlock when stopping here (condition
+    // variable / mutex needs to get exposed all the way out or something).
+    while (event_loop_->is_running()) {
+      ds->RunIteration([&]() {
+        auto new_state = joystick_state_sender_.MakeMessage();
 
-      new_state->test_mode = ds->IsTestMode();
-      new_state->fms_attached = ds->IsFmsAttached();
-      new_state->enabled = ds->IsEnabled();
-      new_state->autonomous = ds->IsAutonomous();
-      new_state->team_id = team_id;
-      new_state->fake = false;
-
-      for (uint8_t i = 0;
-           i < sizeof(new_state->joysticks) / sizeof(::aos::Joystick); ++i) {
-        new_state->joysticks[i].buttons = ds->GetStickButtons(i);
-        for (int j = 0; j < 6; ++j) {
-          new_state->joysticks[i].axis[j] = ds->GetStickAxis(i, j);
+        HAL_MatchInfo match_info;
+        auto status = HAL_GetMatchInfo(&match_info);
+        if (status == 0) {
+          new_state->switch_left = match_info.gameSpecificMessage[0] == 'L' ||
+                                   match_info.gameSpecificMessage[0] == 'l';
+          new_state->scale_left = match_info.gameSpecificMessage[1] == 'L' ||
+                                  match_info.gameSpecificMessage[1] == 'l';
         }
-        if (ds->GetStickPOVCount(i) > 0) {
-          new_state->joysticks[i].pov = ds->GetStickPOV(i, 0);
+
+        new_state->test_mode = ds->IsTestMode();
+        new_state->fms_attached = ds->IsFmsAttached();
+        new_state->enabled = ds->IsEnabled();
+        new_state->autonomous = ds->IsAutonomous();
+        new_state->team_id = team_id_;
+        new_state->fake = false;
+
+        for (uint8_t i = 0;
+             i < sizeof(new_state->joysticks) / sizeof(::aos::Joystick); ++i) {
+          new_state->joysticks[i].buttons = ds->GetStickButtons(i);
+          for (int j = 0; j < 6; ++j) {
+            new_state->joysticks[i].axis[j] = ds->GetStickAxis(i, j);
+          }
+          if (ds->GetStickPOVCount(i) > 0) {
+            new_state->joysticks[i].pov = ds->GetStickPOV(i, 0);
+          }
+          LOG_STRUCT(DEBUG, "joystick_state", *new_state);
         }
-        LOG_STRUCT(DEBUG, "joystick_state", *new_state);
-      }
-      if (!new_state.Send()) {
-        LOG(WARNING, "sending joystick_state failed\n");
-      }
-    });
-  }
+        if (!new_state.Send()) {
+          LOG(WARNING, "sending joystick_state failed\n");
+        }
+      });
+    }
+  });
 }
 
 }  // namespace wpilib
diff --git a/frc971/wpilib/joystick_sender.h b/frc971/wpilib/joystick_sender.h
index a758173..34c6bf4 100644
--- a/frc971/wpilib/joystick_sender.h
+++ b/frc971/wpilib/joystick_sender.h
@@ -11,18 +11,12 @@
 
 class JoystickSender {
  public:
-  JoystickSender(::aos::EventLoop *event_loop)
-      : event_loop_(event_loop),
-        joystick_state_sender_(event_loop_->MakeSender<::aos::JoystickState>(
-            ".aos.joystick_state")) {}
-  void operator()();
-
-  void Quit() { run_ = false; }
+  JoystickSender(::aos::EventLoop *event_loop);
 
  private:
   ::aos::EventLoop *event_loop_;
   ::aos::Sender<::aos::JoystickState> joystick_state_sender_;
-  ::std::atomic<bool> run_{true};
+  const uint16_t team_id_;
 };
 
 }  // namespace wpilib
diff --git a/frc971/wpilib/loop_output_handler.cc b/frc971/wpilib/loop_output_handler.cc
index 6be855e..5039fc3 100644
--- a/frc971/wpilib/loop_output_handler.cc
+++ b/frc971/wpilib/loop_output_handler.cc
@@ -1,85 +1 @@
 #include "frc971/wpilib/loop_output_handler.h"
-
-#include <sys/timerfd.h>
-
-#include <chrono>
-#include <functional>
-#include <thread>
-
-#include "aos/events/event-loop.h"
-#include "aos/init.h"
-#include "aos/robot_state/robot_state.q.h"
-
-namespace frc971 {
-namespace wpilib {
-
-namespace chrono = ::std::chrono;
-
-LoopOutputHandler::LoopOutputHandler(::aos::EventLoop *event_loop,
-                                     ::std::chrono::nanoseconds timeout)
-    : event_loop_(event_loop),
-      joystick_state_fetcher_(event_loop_->MakeFetcher<::aos::JoystickState>(
-          ".aos.joystick_state")),
-      watchdog_(this, timeout) {}
-
-void LoopOutputHandler::operator()() {
-  ::std::thread watchdog_thread(::std::ref(watchdog_));
-  ::aos::SetCurrentThreadName("OutputHandler");
-
-  ::aos::SetCurrentThreadRealtimePriority(30);
-  while (run_) {
-    no_joystick_state_.Print();
-    fake_joystick_state_.Print();
-    Read();
-    joystick_state_fetcher_.Fetch();
-    if (!joystick_state_fetcher_.get()) {
-      LOG_INTERVAL(no_joystick_state_);
-      continue;
-    }
-    if (joystick_state_fetcher_->fake) {
-      LOG_INTERVAL(fake_joystick_state_);
-      continue;
-    }
-
-    watchdog_.Reset();
-    Write();
-  }
-
-  Stop();
-
-  watchdog_.Quit();
-  watchdog_thread.join();
-}
-
-LoopOutputHandler::Watchdog::Watchdog(LoopOutputHandler *handler,
-                                      ::std::chrono::nanoseconds timeout)
-    : handler_(handler),
-      timeout_(timeout),
-      timerfd_(timerfd_create(CLOCK_MONOTONIC, 0)) {
-  if (timerfd_.get() == -1) {
-    PLOG(FATAL, "timerfd_create(CLOCK_MONOTONIC, 0)");
-  }
-}
-
-void LoopOutputHandler::Watchdog::operator()() {
-  ::aos::SetCurrentThreadRealtimePriority(35);
-  ::aos::SetCurrentThreadName("OutputWatchdog");
-  uint8_t buf[8];
-  while (run_) {
-    PCHECK(read(timerfd_.get(), buf, sizeof(buf)));
-    handler_->Stop();
-  }
-}
-
-void LoopOutputHandler::Watchdog::Reset() {
-  itimerspec value = itimerspec();
-  value.it_value.tv_sec = chrono::duration_cast<chrono::seconds>(timeout_).count();
-  value.it_value.tv_nsec =
-      chrono::duration_cast<chrono::nanoseconds>(
-          timeout_ - chrono::seconds(value.it_value.tv_sec))
-          .count();
-  PCHECK(timerfd_settime(timerfd_.get(), 0, &value, nullptr));
-}
-
-}  // namespace wpilib
-}  // namespace frc971
diff --git a/frc971/wpilib/loop_output_handler.h b/frc971/wpilib/loop_output_handler.h
index ff8415f..3c95408 100644
--- a/frc971/wpilib/loop_output_handler.h
+++ b/frc971/wpilib/loop_output_handler.h
@@ -21,24 +21,37 @@
 // The intended use is to have a subclass for each loop which implements the
 // pure virtual methods and is then run in a separate thread. The operator()
 // loops writing values until Quit() is called.
+template <typename T>
 class LoopOutputHandler {
  public:
   LoopOutputHandler(
-      ::aos::EventLoop *event_loop,
-      ::std::chrono::nanoseconds timeout = ::std::chrono::milliseconds(100));
+      ::aos::EventLoop *event_loop, const ::std::string &name,
+      ::std::chrono::nanoseconds timeout = ::std::chrono::milliseconds(100))
+      : event_loop_(event_loop), timeout_(timeout) {
+    event_loop_->SetRuntimeRealtimePriority(30);
+    // TODO(austin): Name thread.
+    event_loop_->MakeWatcher(name, [this](const T &t) {
+      // Push the watchdog out a bit further.
+      timer_handler_->Setup(event_loop_->monotonic_now() + timeout_);
+      Write(t);
+    });
 
-  void Quit() { run_ = false; }
+    // TODO(austin): Set name.
+    timer_handler_ = event_loop_->AddTimer([this]() { Stop(); });
 
-  void operator()();
+    event_loop_->OnRun([this, timeout]() {
+      timer_handler_->Setup(event_loop_->monotonic_now() + timeout_);
+    });
+  }
+
+  void Quit() { event_loop_->Exit(); }
+
+  // Note, all subclasses should call Stop.
+  virtual ~LoopOutputHandler() {}
 
  protected:
-  // Read a message from the appropriate queue.
-  // This must block.
-  virtual void Read() = 0;
-
   // Send the output from the appropriate queue to the hardware.
-  // Read() will always be called at least once before per invocation of this.
-  virtual void Write() = 0;
+  virtual void Write(const T &t) = 0;
 
   // Stop all outputs. This will be called in a separate thread (if at all).
   // The subclass implementation should handle any appropriate logging.
@@ -50,46 +63,9 @@
   ::aos::EventLoop *event_loop() { return event_loop_; }
 
  private:
-  // The thread that actually contains a timerfd to implement timeouts. The
-  // idea is to have a timerfd that is repeatedly set to the timeout expiration
-  // in the future so it will never actually expire unless it is not reset for
-  // too long.
-  //
-  // This class nicely encapsulates the raw fd and manipulating it. Its
-  // operator() loops until Quit() is called, calling Stop() on its associated
-  // LoopOutputHandler whenever the timerfd expires.
-  class Watchdog {
-   public:
-    Watchdog(LoopOutputHandler *handler, ::std::chrono::nanoseconds timeout);
-
-    void operator()();
-
-    void Reset();
-
-    void Quit() { run_ = false; }
-
-   private:
-    LoopOutputHandler *const handler_;
-
-    const ::std::chrono::nanoseconds timeout_;
-
-    ::aos::ScopedFD timerfd_;
-
-    ::std::atomic<bool> run_{true};
-  };
-
   ::aos::EventLoop *event_loop_;
-  ::aos::Fetcher<::aos::JoystickState> joystick_state_fetcher_;
-  Watchdog watchdog_;
-
-  ::std::atomic<bool> run_{true};
-
-  ::aos::util::SimpleLogInterval no_joystick_state_ =
-      ::aos::util::SimpleLogInterval(::std::chrono::milliseconds(500), INFO,
-                                     "no joystick state -> not outputting");
-  ::aos::util::SimpleLogInterval fake_joystick_state_ =
-      ::aos::util::SimpleLogInterval(::std::chrono::milliseconds(500), DEBUG,
-                                     "fake joystick state -> not outputting");
+  const ::std::chrono::nanoseconds timeout_;
+  ::aos::TimerHandler *timer_handler_;
 };
 
 }  // namespace wpilib
diff --git a/frc971/wpilib/loop_output_handler_test.cc b/frc971/wpilib/loop_output_handler_test.cc
new file mode 100644
index 0000000..8a7e903
--- /dev/null
+++ b/frc971/wpilib/loop_output_handler_test.cc
@@ -0,0 +1,113 @@
+#include "frc971/wpilib/loop_output_handler.h"
+
+#include <chrono>
+
+#include "gtest/gtest.h"
+
+#include "aos/events/simulated-event-loop.h"
+#include "aos/logging/logging.h"
+#include "aos/logging/queue_logging.h"
+#include "aos/testing/test_logging.h"
+#include "aos/time/time.h"
+#include "frc971/wpilib/loop_output_handler_test.q.h"
+
+namespace frc971 {
+namespace wpilib {
+namespace testing {
+namespace {
+namespace chrono = ::std::chrono;
+using ::aos::monotonic_clock;
+}  // namespace
+
+class LoopOutputHandlerTest : public ::testing::Test {
+ public:
+  LoopOutputHandlerTest()
+      : ::testing::Test(),
+        loop_output_hander_event_loop_(event_loop_factory_.MakeEventLoop()),
+        test_event_loop_(event_loop_factory_.MakeEventLoop()) {
+    ::aos::testing::EnableTestLogging();
+  }
+
+  ::aos::SimulatedEventLoopFactory event_loop_factory_;
+  ::std::unique_ptr<::aos::EventLoop> loop_output_hander_event_loop_;
+  ::std::unique_ptr<::aos::EventLoop> test_event_loop_;
+};
+
+// Test loop output handler which logs and counts.
+class TestLoopOutputHandler
+    : public LoopOutputHandler<LoopOutputHandlerTestOutput> {
+ public:
+  TestLoopOutputHandler(::aos::EventLoop *event_loop, const ::std::string &name)
+      : LoopOutputHandler(event_loop, name) {}
+
+  ~TestLoopOutputHandler() { Stop(); }
+
+  int count() const { return count_; }
+
+  ::aos::monotonic_clock::time_point last_time() const { return last_time_; }
+  ::aos::monotonic_clock::time_point stop_time() const { return stop_time_; }
+
+ protected:
+  void Write(const LoopOutputHandlerTestOutput &output) override {
+    LOG_STRUCT(DEBUG, "output", output);
+    ++count_;
+    last_time_ = event_loop()->monotonic_now();
+  }
+
+  void Stop() override {
+    stop_time_ = event_loop()->monotonic_now();
+    LOG(DEBUG, "Stopping\n");
+  }
+
+ private:
+  int count_ = 0;
+
+  ::aos::monotonic_clock::time_point last_time_ =
+      ::aos::monotonic_clock::min_time;
+  ::aos::monotonic_clock::time_point stop_time_ =
+      ::aos::monotonic_clock::min_time;
+};
+
+// Test that the watchdog calls Stop at the right time.
+TEST_F(LoopOutputHandlerTest, WatchdogTest) {
+  TestLoopOutputHandler loop_output(loop_output_hander_event_loop_.get(),
+                                    ".test");
+
+  ::aos::Sender<LoopOutputHandlerTestOutput> output_sender =
+      test_event_loop_->MakeSender<LoopOutputHandlerTestOutput>(".test");
+
+  const monotonic_clock::time_point start_time =
+      test_event_loop_->monotonic_now();
+
+  int count = 0;
+  // Send outputs for 1 second.
+  ::aos::TimerHandler *timer_handle = test_event_loop_->AddTimer(
+      [this, &start_time, &output_sender, &loop_output, &count]() {
+        EXPECT_EQ(count, loop_output.count());
+        if (test_event_loop_->monotonic_now() <
+            start_time + chrono::seconds(1)) {
+          auto output = output_sender.MakeMessage();
+          output->voltage = 5.0;
+          EXPECT_TRUE(output.Send());
+
+          ++count;
+        }
+        LOG(INFO, "Ping\n");
+      });
+
+  // Kick off the ping timer handler.
+  test_event_loop_->OnRun([this, &timer_handle]() {
+    timer_handle->Setup(test_event_loop_->monotonic_now(),
+                        chrono::milliseconds(5));
+  });
+
+  event_loop_factory_.RunFor(chrono::seconds(2));
+
+  // Confirm the watchdog
+  EXPECT_EQ(loop_output.stop_time(),
+            loop_output.last_time() + chrono::milliseconds(100));
+}
+
+}  // namespace testing
+}  // namespace wpilib
+}  // namespace frc971
diff --git a/frc971/wpilib/loop_output_handler_test.q b/frc971/wpilib/loop_output_handler_test.q
new file mode 100644
index 0000000..81336ef
--- /dev/null
+++ b/frc971/wpilib/loop_output_handler_test.q
@@ -0,0 +1,6 @@
+package frc971.wpilib;
+
+// Test output message.
+message LoopOutputHandlerTestOutput {
+  double voltage;
+};
diff --git a/frc971/wpilib/pdp_fetcher.cc b/frc971/wpilib/pdp_fetcher.cc
index 01c9613..98da761 100644
--- a/frc971/wpilib/pdp_fetcher.cc
+++ b/frc971/wpilib/pdp_fetcher.cc
@@ -5,41 +5,42 @@
 #include "aos/events/event-loop.h"
 #include "aos/init.h"
 #include "aos/logging/queue_logging.h"
-#include "aos/util/phased_loop.h"
 #include "frc971/wpilib/ahal/PowerDistributionPanel.h"
 #include "frc971/wpilib/pdp_values.q.h"
 
 namespace frc971 {
 namespace wpilib {
 
-void PDPFetcher::operator()() {
-  ::aos::SetCurrentThreadName("PDPFetcher");
-  ::std::unique_ptr<frc::PowerDistributionPanel> pdp(
-      new frc::PowerDistributionPanel());
+namespace chrono = ::std::chrono;
 
-  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
-                                      ::aos::monotonic_clock::now(),
-                                      ::std::chrono::milliseconds(4));
+PDPFetcher::PDPFetcher(::aos::EventLoop *event_loop)
+    : event_loop_(event_loop),
+      pdp_values_sender_(
+          event_loop_->MakeSender<::frc971::PDPValues>(".frc971.pdp_values")),
+      pdp_(new frc::PowerDistributionPanel()) {
+  event_loop_->set_name("PDPFetcher");
 
-  // TODO(austin): Event loop instead of while loop.
-  while (true) {
-    {
-      const int iterations = phased_loop.SleepUntilNext();
-      if (iterations != 1) {
-        LOG(DEBUG, "PDPFetcher skipped %d iterations\n", iterations - 1);
-      }
-    }
-    auto message = pdp_values_sender_.MakeMessage();
-    message->voltage = pdp->GetVoltage();
-    message->temperature = pdp->GetTemperature();
-    message->power = pdp->GetTotalPower();
-    for (int i = 0; i < 16; ++i) {
-      message->currents[i] = pdp->GetCurrent(i);
-    }
-    LOG_STRUCT(DEBUG, "got", *message);
-    if (!message.Send()) {
-      LOG(WARNING, "sending pdp values failed\n");
-    }
+  // SCHED_OTHER on purpose.
+  event_loop_->AddPhasedLoop([this](int iterations) { Loop(iterations); },
+                             chrono::milliseconds(20), chrono::milliseconds(4));
+}
+
+PDPFetcher::~PDPFetcher() {}
+
+void PDPFetcher::Loop(int iterations) {
+  if (iterations != 1) {
+    LOG(DEBUG, "PDPFetcher skipped %d iterations\n", iterations - 1);
+  }
+  auto message = pdp_values_sender_.MakeMessage();
+  message->voltage = pdp_->GetVoltage();
+  message->temperature = pdp_->GetTemperature();
+  message->power = pdp_->GetTotalPower();
+  for (int i = 0; i < 16; ++i) {
+    message->currents[i] = pdp_->GetCurrent(i);
+  }
+  LOG_STRUCT(DEBUG, "got", *message);
+  if (!message.Send()) {
+    LOG(WARNING, "sending pdp values failed\n");
   }
 }
 
diff --git a/frc971/wpilib/pdp_fetcher.h b/frc971/wpilib/pdp_fetcher.h
index db783f6..fd05d67 100644
--- a/frc971/wpilib/pdp_fetcher.h
+++ b/frc971/wpilib/pdp_fetcher.h
@@ -7,29 +7,28 @@
 #include "aos/events/event-loop.h"
 #include "frc971/wpilib/pdp_values.q.h"
 
+namespace frc {
+class PowerDistributionPanel;
+}  // namespace frc
+
 namespace frc971 {
 namespace wpilib {
 
-// Handles fetching values from the PDP. This is slow, so it has to happen in a
-// separate thread.
+// Handles fetching values from the PDP.
 class PDPFetcher {
  public:
-  PDPFetcher(::aos::EventLoop *event_loop)
-      : event_loop_(event_loop),
-        pdp_values_sender_(event_loop_->MakeSender<::frc971::PDPValues>(
-            ".frc971.pdp_values")) {}
+  PDPFetcher(::aos::EventLoop *event_loop);
 
-  void Quit() { run_ = false; }
-
-  // To be called by a ::std::thread.
-  void operator()();
+  ~PDPFetcher();
 
  private:
+  void Loop(int iterations);
+
   ::aos::EventLoop *event_loop_;
 
   ::aos::Sender<::frc971::PDPValues> pdp_values_sender_;
 
-  ::std::atomic<bool> run_{true};
+  ::std::unique_ptr<::frc::PowerDistributionPanel> pdp_;
 };
 
 }  // namespace wpilib
diff --git a/frc971/wpilib/sensor_reader.cc b/frc971/wpilib/sensor_reader.cc
index 2e0cd0a..209054b 100644
--- a/frc971/wpilib/sensor_reader.cc
+++ b/frc971/wpilib/sensor_reader.cc
@@ -19,12 +19,23 @@
 SensorReader::SensorReader(::aos::EventLoop *event_loop)
     : event_loop_(event_loop),
       robot_state_sender_(
-          event_loop_->MakeSender<::aos::RobotState>(".aos.robot_state")) {
+          event_loop_->MakeSender<::aos::RobotState>(".aos.robot_state")),
+      my_pid_(getpid()) {
   // Set some defaults.  We don't tend to exceed these, so old robots should
   // just work with them.
   UpdateFastEncoderFilterHz(500000);
   UpdateMediumEncoderFilterHz(100000);
   ds_ = &::frc::DriverStation::GetInstance();
+
+  event_loop->SetRuntimeRealtimePriority(40);
+
+  // Fill in the no pwm trigger defaults.
+  phased_loop_handler_ =
+      event_loop_->AddPhasedLoop([this](int iterations) { Loop(iterations); },
+                                 period_, chrono::milliseconds(4));
+
+  event_loop->set_name("SensorReader");
+  event_loop->OnRun([this]() { DoStart(); });
 }
 
 void SensorReader::UpdateFastEncoderFilterHz(int hz) {
@@ -82,77 +93,75 @@
   }
 }
 
-void SensorReader::operator()() {
-  ::aos::SetCurrentThreadName("SensorReader");
-
-  int32_t my_pid = getpid();
-
+void SensorReader::DoStart() {
   Start();
   if (dma_synchronizer_) {
     dma_synchronizer_->Start();
   }
 
-  const chrono::microseconds period =
+  period_ =
       pwm_trigger_ ? chrono::microseconds(5050) : chrono::microseconds(5000);
   if (pwm_trigger_) {
     LOG(INFO, "Using PWM trigger and a 5.05 ms period\n");
   } else {
     LOG(INFO, "Defaulting to open loop pwm synchronization\n");
   }
-  ::aos::time::PhasedLoop phased_loop(
-      period, ::aos::monotonic_clock::now(),
+
+  // Now that we are configured, actually fill in the defaults.
+  phased_loop_handler_->set_interval_and_offset(
+      period_,
       pwm_trigger_ ? ::std::chrono::milliseconds(3) : chrono::milliseconds(4));
 
-  ::aos::SetCurrentThreadRealtimePriority(40);
-  monotonic_clock::time_point last_monotonic_now = monotonic_clock::now();
-  while (run_) {
-    {
-      const int iterations = phased_loop.SleepUntilNext();
-      if (iterations != 1) {
-        LOG(WARNING, "SensorReader skipped %d iterations\n", iterations - 1);
-      }
-    }
-    const monotonic_clock::time_point monotonic_now = monotonic_clock::now();
+  last_monotonic_now_ = monotonic_clock::now();
+}
 
-    {
-      auto new_state = robot_state_sender_.MakeMessage();
-      ::frc971::wpilib::PopulateRobotState(new_state.get(), my_pid);
-      LOG_STRUCT(DEBUG, "robot_state", *new_state);
-      new_state.Send();
-    }
-    RunIteration();
-    if (dma_synchronizer_) {
-      dma_synchronizer_->RunIteration();
-      RunDmaIteration();
+void SensorReader::Loop(const int iterations) {
+  if (iterations != 1) {
+    LOG(WARNING, "SensorReader skipped %d iterations\n", iterations - 1);
+  }
+
+  const monotonic_clock::time_point monotonic_now =
+      event_loop_->monotonic_now();
+
+  {
+    auto new_state = robot_state_sender_.MakeMessage();
+    ::frc971::wpilib::PopulateRobotState(new_state.get(), my_pid_);
+    LOG_STRUCT(DEBUG, "robot_state", *new_state);
+    new_state.Send();
+  }
+  RunIteration();
+  if (dma_synchronizer_) {
+    dma_synchronizer_->RunIteration();
+    RunDmaIteration();
+  }
+
+  if (pwm_trigger_) {
+    LOG(DEBUG, "PWM wakeup delta: %lld\n",
+        (monotonic_now - last_monotonic_now_).count());
+    last_monotonic_now_ = monotonic_now;
+
+    monotonic_clock::time_point last_tick_timepoint = GetPWMStartTime();
+    if (last_tick_timepoint == monotonic_clock::min_time) {
+      return;
     }
 
-    if (pwm_trigger_) {
-      LOG(DEBUG, "PWM wakeup delta: %lld\n",
-          (monotonic_now - last_monotonic_now).count());
-      last_monotonic_now = monotonic_now;
-
-      monotonic_clock::time_point last_tick_timepoint = GetPWMStartTime();
-      if (last_tick_timepoint == monotonic_clock::min_time) {
-        continue;
-      }
-
-      last_tick_timepoint +=
-          (monotonic_now - last_tick_timepoint) / period * period;
-      // If it's over 1/2 of a period back in time, that's wrong.  Move it
-      // forwards to now.
-      if (last_tick_timepoint - monotonic_now < -period / 2) {
-        last_tick_timepoint += period;
-      }
-
-      // We should be sampling our sensors to kick off the control cycle 50 uS
-      // after the falling edge.  This gives us a little bit of buffer for
-      // errors in waking up.  The PWM cycle starts at the falling edge of the
-      // PWM pulse.
-      chrono::nanoseconds new_offset = phased_loop.OffsetFromIntervalAndTime(
-          period, last_tick_timepoint + chrono::microseconds(50));
-
-      phased_loop.set_interval_and_offset(period, new_offset);
+    last_tick_timepoint +=
+        ((monotonic_now - last_tick_timepoint) / period_) * period_;
+    // If it's over 1/2 of a period back in time, that's wrong.  Move it
+    // forwards to now.
+    if (last_tick_timepoint - monotonic_now < -period_ / 2) {
+      last_tick_timepoint += period_;
     }
+
+    // We should be sampling our sensors to kick off the control cycle 50 uS
+    // after the falling edge.  This gives us a little bit of buffer for
+    // errors in waking up.  The PWM cycle starts at the falling edge of the
+    // PWM pulse.
+    chrono::nanoseconds new_offset =
+        ::aos::time::PhasedLoop::OffsetFromIntervalAndTime(
+            period_, last_tick_timepoint + chrono::microseconds(50));
+
+    phased_loop_handler_->set_interval_and_offset(period_, new_offset);
   }
 }
 
diff --git a/frc971/wpilib/sensor_reader.h b/frc971/wpilib/sensor_reader.h
index d14f704..7a63444 100644
--- a/frc971/wpilib/sensor_reader.h
+++ b/frc971/wpilib/sensor_reader.h
@@ -59,8 +59,6 @@
   // sensor has been added to DMA.
   virtual void RunDmaIteration() {}
 
-  void operator()();
-
  protected:
   // Copies a DMAEncoder to a IndexPosition with the correct unit and direction
   // changes.
@@ -185,16 +183,33 @@
   // Gets called right before the DMA synchronizer is up and running.
   virtual void Start() {}
 
+  // Sets up everything during startup.
+  void DoStart();
+
+  // Runs a single iteration.
+  void Loop(int iterations);
+
   // Returns the monotonic time of the start of the first PWM cycle.
   // Returns min_time if no start time could be calculated.
   monotonic_clock::time_point GetPWMStartTime();
 
-  bool pwm_trigger_;
+  bool pwm_trigger_ = false;
 
   ::std::unique_ptr<::frc971::wpilib::DMASynchronizer> dma_synchronizer_;
 
   ::std::atomic<bool> run_{true};
   ::frc::DriverStation *ds_;
+
+  const int32_t my_pid_;
+
+  // Pointer to the phased loop handler used to modify the wakeup.
+  ::aos::PhasedLoopHandler *phased_loop_handler_;
+
+  // Last time we got called.
+  ::aos::monotonic_clock::time_point last_monotonic_now_ =
+      ::aos::monotonic_clock::min_time;
+  // The current period.
+  chrono::microseconds period_ = chrono::microseconds(5000);
 };
 
 }  // namespace wpilib
diff --git a/frc971/wpilib/wpilib_robot_base.h b/frc971/wpilib/wpilib_robot_base.h
index 3deb0e4..2cccf65 100644
--- a/frc971/wpilib/wpilib_robot_base.h
+++ b/frc971/wpilib/wpilib_robot_base.h
@@ -1,14 +1,45 @@
 #ifndef FRC971_WPILIB_NEWROBOTBASE_H_
 #define FRC971_WPILIB_NEWROBOTBASE_H_
 
+#include "aos/events/shm-event-loop.h"
+#include "aos/init.h"
 #include "frc971/wpilib/ahal/RobotBase.h"
 
 namespace frc971 {
 namespace wpilib {
 
 class WPILibRobotBase {
-public:
+ public:
   virtual void Run() = 0;
+
+  // Runs all the loops.
+  void RunLoops() {
+    // TODO(austin): SIGINT handler calling Exit on all the loops.
+    // TODO(austin): RegisterSignalHandler in ShmEventLoop for others.
+
+    ::std::vector<::std::thread> threads;
+    for (size_t i = 1; i < loops_.size(); ++i) {
+      threads.emplace_back([this, i]() { loops_[i]->Run(); });
+    }
+    // Save some memory and run the last one in the main thread.
+    loops_[0]->Run();
+
+    for (::std::thread &thread : threads) {
+      thread.join();
+    }
+
+    LOG(ERROR, "Exiting WPILibRobot\n");
+
+    ::aos::Cleanup();
+  }
+
+ protected:
+  // Adds a loop to the list of loops to run.
+  void AddLoop(::aos::ShmEventLoop *loop) { loops_.push_back(loop); }
+
+ private:
+  // List of the event loops to run in RunLoops.
+  ::std::vector<::aos::ShmEventLoop *> loops_;
 };
 
 #define AOS_ROBOT_CLASS(_ClassName_) \
@@ -17,7 +48,11 @@
 template <typename T>
 class WPILibAdapterRobot : public frc::RobotBase {
  public:
-  void StartCompetition() override { robot_.Run(); }
+  void StartCompetition() override {
+    ::aos::InitNRT();
+
+    robot_.Run();
+  }
 
  private:
   T robot_;