Convert aos over to flatbuffers

Everything builds, and all the tests pass.  I suspect that some entries
are missing from the config files, but those will be found pretty
quickly on startup.

There is no logging or live introspection of queue messages.

Change-Id: I496ee01ed68f202c7851bed7e8786cee30df29f5
diff --git a/aos/BUILD b/aos/BUILD
index e918d7f..a2c7134 100644
--- a/aos/BUILD
+++ b/aos/BUILD
@@ -1,6 +1,5 @@
 load("//tools:environments.bzl", "mcu_cpus")
 load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
-load("//aos/build:queues.bzl", "queue_library")
 
 filegroup(
     name = "prime_binaries",
@@ -116,100 +115,6 @@
     visibility = ["//visibility:public"],
 )
 
-genrule(
-    name = "gen_print_field",
-    outs = ["print_field.cc"],
-    cmd = "$(location //aos/build/queues:print_field) $@",
-    tools = ["//aos/build/queues:print_field"],
-    visibility = ["//visibility:private"],
-)
-
-cc_library(
-    name = "queue_types",
-    srcs = [
-        "print_field_helpers.h",
-        "queue_types.cc",
-        ":gen_print_field",
-    ],
-    hdrs = [
-        "queue_types.h",
-    ],
-    visibility = ["//visibility:public"],
-    deps = [
-        ":generated_queue_headers",
-        "//aos:byteorder",
-        "//aos/ipc_lib:core_lib",
-        "//aos/ipc_lib:shared_mem",
-        "//aos/logging:printf_formats",
-        "//aos/mutex",
-        "//aos/time",
-    ],
-)
-
-cc_test(
-    name = "queue_types_test",
-    srcs = [
-        "queue_types_test.cc",
-    ],
-    deps = [
-        ":queue_types",
-        ":test_queue",
-        "//aos/logging",
-        "//aos/testing:googletest",
-        "//aos/testing:test_logging",
-    ],
-)
-
-cc_library(
-    name = "queues",
-    hdrs = [
-        "queue.h",
-    ],
-    visibility = ["//visibility:public"],
-    deps = [
-        "//aos:queue",
-        "//aos/ipc_lib:queue",
-        "//aos/messages",
-    ],
-)
-
-queue_library(
-    name = "test_queue",
-    srcs = [
-        "test_queue.q",
-    ],
-)
-
-genrule(
-    name = "gen_queue_primitives",
-    outs = ["queue_primitives.h"],
-    cmd = "$(location //aos/build/queues:queue_primitives) $@",
-    tools = ["//aos/build/queues:queue_primitives"],
-    visibility = ["//visibility:private"],
-)
-
-cc_library(
-    name = "generated_queue_headers",
-    hdrs = [
-        ":gen_queue_primitives",
-    ],
-    visibility = ["//aos/logging:__pkg__"],
-)
-
-cc_test(
-    name = "queue_test",
-    srcs = [
-        "queue_test.cc",
-    ],
-    deps = [
-        ":test_queue",
-        "//aos:die",
-        "//aos/testing:googletest",
-        "//aos/testing:test_shm",
-        "//aos/util:thread",
-    ],
-)
-
 cc_library(
     name = "unique_malloc_ptr",
     hdrs = [
@@ -229,8 +134,8 @@
     visibility = ["//visibility:public"],
     deps = [
         "//aos/ipc_lib:aos_sync",
-        "//aos/logging",
         "//aos/mutex",
+        "@com_github_google_glog//:glog",
     ],
 )
 
@@ -291,8 +196,8 @@
     visibility = ["//visibility:public"],
     deps = [
         "//aos/ipc_lib:aos_sync",
-        "//aos/logging",
         "//aos/time",
+        "@com_github_google_glog//:glog",
     ],
 )
 
@@ -322,14 +227,6 @@
 )
 
 cc_library(
-    name = "queue",
-    hdrs = [
-        "queue-tmpl.h",
-    ],
-    visibility = ["//aos:__pkg__"],
-)
-
-cc_library(
     name = "complex_thread_local",
     srcs = [
         "complex_thread_local.cc",
@@ -370,15 +267,31 @@
     ],
     visibility = ["//visibility:public"],
     deps = [
+        ":realtime",
         "//aos:die",
         "//aos/ipc_lib:shared_mem",
         "//aos/logging:implementations",
     ],
 )
 
+cc_library(
+    name = "realtime",
+    srcs = [
+        "realtime.cc",
+    ],
+    hdrs = [
+        "realtime.h",
+    ],
+    visibility = ["//visibility:public"],
+    deps = [
+        "@com_github_google_glog//:glog",
+    ],
+)
+
 flatbuffer_cc_library(
-    name = "configuration_flatbuffer",
+    name = "configuration_fbs",
     srcs = ["configuration.fbs"],
+    visibility = ["//visibility:public"],
 )
 
 cc_library(
@@ -391,13 +304,12 @@
     ],
     visibility = ["//visibility:public"],
     deps = [
-        ":configuration_flatbuffer",
+        ":configuration_fbs",
         ":flatbuffer_merge",
         ":flatbuffers",
         ":json_to_flatbuffer",
         "@com_google_absl//absl/base",
         "//aos:unique_malloc_ptr",
-        "//aos/logging",
         "//aos/util:file",
         "@com_github_google_glog//:glog",
         "@com_google_absl//absl/container:btree",
@@ -443,6 +355,7 @@
     srcs = ["json_tokenizer.cc"],
     hdrs = ["json_tokenizer.h"],
     deps = [
+        "@com_github_google_glog//:glog",
         "@com_google_absl//absl/strings",
     ],
 )
@@ -451,11 +364,11 @@
     name = "json_to_flatbuffer",
     srcs = ["json_to_flatbuffer.cc"],
     hdrs = ["json_to_flatbuffer.h"],
+    visibility = ["//visibility:public"],
     deps = [
         ":flatbuffer_utils",
         ":flatbuffers",
         ":json_tokenizer",
-        "//aos/logging",
         "@com_github_google_flatbuffers//:flatbuffers",
         "@com_github_google_glog//:glog",
         "@com_google_absl//absl/strings",
@@ -479,6 +392,7 @@
     srcs = ["flatbuffer_merge.cc"],
     hdrs = ["flatbuffer_merge.h"],
     copts = ["-Wno-cast-align"],
+    visibility = ["//visibility:public"],
     deps = [
         ":flatbuffer_utils",
         ":flatbuffers",
@@ -511,6 +425,7 @@
     deps = [
         "@com_github_google_flatbuffers//:flatbuffers",
         "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/strings",
     ],
 )
 
@@ -520,11 +435,14 @@
         "configuration_test.cc",
     ],
     data = [
+        "testdata/backwards.json",
         "testdata/config1.json",
         "testdata/config1_bad.json",
         "testdata/config2.json",
         "testdata/config3.json",
         "testdata/expected.json",
+        "//aos/events:config.fb.json",
+        "//aos/events:pingpong.bfbs",
     ],
     deps = [
         ":configuration",
@@ -532,3 +450,17 @@
         "//aos/testing:test_logging",
     ],
 )
+
+cc_binary(
+    name = "config_flattener",
+    srcs = [
+        "config_flattener.cc",
+    ],
+    visibility = ["//visibility:public"],
+    deps = [
+        ":configuration",
+        ":init",
+        "//aos/util:file",
+        "@com_github_google_glog//:glog",
+    ],
+)
diff --git a/aos/actions/BUILD b/aos/actions/BUILD
index 25cc6e3..fe79a4a 100644
--- a/aos/actions/BUILD
+++ b/aos/actions/BUILD
@@ -1,6 +1,6 @@
 package(default_visibility = ["//visibility:public"])
 
-load("//aos/build:queues.bzl", "queue_library")
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
 
 cc_library(
     name = "action_lib",
@@ -13,30 +13,22 @@
         "actor.h",
     ],
     deps = [
-        "//aos:queues",
+        ":actions_fbs",
         "//aos/controls:control_loop",
         "//aos/logging",
-        "//aos/logging:queue_logging",
         "//aos/time",
         "//aos/util:phased_loop",
     ],
 )
 
-queue_library(
-    name = "action_queue",
-    srcs = [
-        "actions.q",
-    ],
+flatbuffer_cc_library(
+    name = "actions_fbs",
+    srcs = ["actions.fbs"],
 )
 
-queue_library(
-    name = "test_action_queue",
-    srcs = [
-        "test_action.q",
-    ],
-    deps = [
-        ":action_queue",
-    ],
+flatbuffer_cc_library(
+    name = "test_action_fbs",
+    srcs = ["test_action.fbs"],
 )
 
 cc_test(
@@ -44,15 +36,14 @@
     srcs = [
         "action_test.cc",
     ],
+    data = ["action_test_config.json"],
     deps = [
         ":action_lib",
-        ":action_queue",
-        ":test_action_queue",
+        ":actions_fbs",
+        ":test_action_fbs",
         "//aos:event",
-        "//aos:queues",
         "//aos/events:simulated_event_loop",
         "//aos/logging",
-        "//aos/logging:queue_logging",
         "//aos/testing:googletest",
         "//aos/testing:test_shm",
         "//aos/time",
diff --git a/aos/actions/action_test.cc b/aos/actions/action_test.cc
index 178b2b0..aa0e6d2 100644
--- a/aos/actions/action_test.cc
+++ b/aos/actions/action_test.cc
@@ -7,11 +7,10 @@
 #include "gtest/gtest.h"
 
 #include "aos/actions/actions.h"
-#include "aos/actions/actions.q.h"
+#include "aos/actions/actions_generated.h"
 #include "aos/actions/actor.h"
-#include "aos/actions/test_action.q.h"
-#include "aos/events/simulated-event-loop.h"
-#include "aos/queue.h"
+#include "aos/actions/test_action_generated.h"
+#include "aos/events/simulated_event_loop.h"
 #include "aos/testing/test_logging.h"
 #include "aos/testing/test_shm.h"
 
@@ -20,24 +19,24 @@
 namespace actions {
 namespace testing {
 
-
 namespace chrono = ::std::chrono;
 
 class TestActorIndex
-    : public aos::common::actions::ActorBase<actions::TestActionQueueGroup> {
+    : public aos::common::actions::ActorBase<actions::TestActionGoal> {
  public:
-  typedef TypedActionFactory<actions::TestActionQueueGroup> Factory;
+  typedef TypedActionFactory<actions::TestActionGoal> Factory;
 
   explicit TestActorIndex(::aos::EventLoop *event_loop)
-      : aos::common::actions::ActorBase<actions::TestActionQueueGroup>(
-            event_loop, ".aos.common.actions.test_action") {}
+      : aos::common::actions::ActorBase<actions::TestActionGoal>(
+            event_loop, "/test_action") {}
 
   static Factory MakeFactory(::aos::EventLoop *event_loop) {
-    return Factory(event_loop, ".aos.common.actions.test_action");
+    return Factory(event_loop, "/test_action");
   }
 
-  bool RunAction(const uint32_t &new_index) override {
-    index = new_index;
+  bool RunAction(const UInt *new_index) override {
+    VLOG(1) << "New index " << FlatbufferToJson(new_index);
+    index = new_index->val();
     return true;
   }
 
@@ -45,35 +44,35 @@
 };
 
 class TestActorNOP
-    : public aos::common::actions::ActorBase<actions::TestActionQueueGroup> {
+    : public aos::common::actions::ActorBase<actions::TestActionGoal> {
  public:
-  typedef TypedActionFactory<actions::TestActionQueueGroup> Factory;
+  typedef TypedActionFactory<actions::TestActionGoal> Factory;
 
   explicit TestActorNOP(::aos::EventLoop *event_loop)
-      : actions::ActorBase<actions::TestActionQueueGroup>(
-            event_loop, ".aos.common.actions.test_action") {}
+      : actions::ActorBase<actions::TestActionGoal>(
+            event_loop, "/test_action") {}
 
   static Factory MakeFactory(::aos::EventLoop *event_loop) {
-    return Factory(event_loop, ".aos.common.actions.test_action");
+    return Factory(event_loop, "/test_action");
   }
 
-  bool RunAction(const uint32_t &) override { return true; }
+  bool RunAction(const UInt *) override { return true; }
 };
 
 class TestActorShouldCancel
-    : public aos::common::actions::ActorBase<actions::TestActionQueueGroup> {
+    : public aos::common::actions::ActorBase<actions::TestActionGoal> {
  public:
-  typedef TypedActionFactory<actions::TestActionQueueGroup> Factory;
+  typedef TypedActionFactory<actions::TestActionGoal> Factory;
 
   explicit TestActorShouldCancel(::aos::EventLoop *event_loop)
-      : aos::common::actions::ActorBase<actions::TestActionQueueGroup>(
-            event_loop, ".aos.common.actions.test_action") {}
+      : aos::common::actions::ActorBase<actions::TestActionGoal>(
+            event_loop, "/test_action") {}
 
   static Factory MakeFactory(::aos::EventLoop *event_loop) {
-    return Factory(event_loop, ".aos.common.actions.test_action");
+    return Factory(event_loop, "/test_action");
   }
 
-  bool RunAction(const uint32_t &) override {
+  bool RunAction(const UInt *) override {
     while (!ShouldCancel()) {
       AOS_LOG(FATAL, "NOT CANCELED!!\n");
     }
@@ -82,37 +81,41 @@
 };
 
 class TestActor2Nop
-    : public aos::common::actions::ActorBase<actions::TestAction2QueueGroup> {
+    : public aos::common::actions::ActorBase<actions::TestAction2Goal> {
  public:
-  typedef TypedActionFactory<actions::TestAction2QueueGroup> Factory;
+  typedef TypedActionFactory<actions::TestAction2Goal> Factory;
 
   explicit TestActor2Nop(::aos::EventLoop *event_loop)
-      : actions::ActorBase<actions::TestAction2QueueGroup>(
-            event_loop, ".aos.common.actions.test_action2") {}
+      : actions::ActorBase<actions::TestAction2Goal>(
+            event_loop, "/test_action2") {}
 
   static Factory MakeFactory(::aos::EventLoop *event_loop) {
-    return Factory(event_loop, ".aos.common.actions.test_action2");
+    return Factory(event_loop, "/test_action2");
   }
 
-  bool RunAction(const actions::MyParams &) { return true; }
+  bool RunAction(const actions::MyParams *) { return true; }
 };
 
 class ActionTest : public ::testing::Test {
  protected:
   ActionTest()
-      : actor1_event_loop_(event_loop_factory_.MakeEventLoop()),
+      : configuration_(
+            configuration::ReadConfig("aos/actions/action_test_config.json")),
+        event_loop_factory_(&configuration_.message()),
+        actor1_event_loop_(event_loop_factory_.MakeEventLoop()),
         actor2_event_loop_(event_loop_factory_.MakeEventLoop()),
         test_event_loop_(event_loop_factory_.MakeEventLoop()) {
     ::aos::testing::EnableTestLogging();
   }
 
+  FlatbufferDetachedBuffer<Configuration> configuration_;
+
   // Bring up and down Core.
   ::aos::SimulatedEventLoopFactory event_loop_factory_;
 
   ::std::unique_ptr<::aos::EventLoop> actor1_event_loop_;
   ::std::unique_ptr<::aos::EventLoop> actor2_event_loop_;
   ::std::unique_ptr<::aos::EventLoop> test_event_loop_;
-
 };
 
 // Tests that the the actions exist in a safe state at startup.
@@ -130,11 +133,10 @@
 TEST_F(ActionTest, StartWithOldGoal) {
   ::std::unique_ptr<::aos::EventLoop> test2_event_loop =
       event_loop_factory_.MakeEventLoop();
-  ::aos::Sender<TestActionQueueGroup::Goal> goal_sender =
-      test2_event_loop->MakeSender<TestActionQueueGroup::Goal>(
-          ".aos.common.actions.test_action.goal");
-  ::aos::Fetcher<Status> status_fetcher = test2_event_loop->MakeFetcher<Status>(
-      ".aos.common.actions.test_action.status");
+  ::aos::Sender<TestActionGoal> goal_sender =
+      test2_event_loop->MakeSender<TestActionGoal>("/test_action");
+  ::aos::Fetcher<Status> status_fetcher =
+      test2_event_loop->MakeFetcher<Status>("/test_action");
 
   TestActorIndex::Factory nop_actor_factory =
       TestActorNOP::MakeFactory(test_event_loop_.get());
@@ -142,9 +144,14 @@
   ActionQueue action_queue;
 
   {
-    auto goal_message = goal_sender.MakeMessage();
-    goal_message->run = 971;
-    ASSERT_TRUE(goal_message.Send());
+    ::aos::Sender<TestActionGoal>::Builder builder =
+        goal_sender.MakeBuilder();
+
+    TestActionGoal::Builder goal_builder =
+        builder.MakeBuilder<TestActionGoal>();
+
+    goal_builder.add_run(971);
+    ASSERT_TRUE(builder.Send(goal_builder.Finish()));
   }
 
   TestActorNOP nop_act(actor1_event_loop_.get());
@@ -154,10 +161,14 @@
   event_loop_factory_.RunFor(chrono::seconds(1));
 
   ASSERT_TRUE(status_fetcher.Fetch());
-  EXPECT_EQ(0u, status_fetcher->running);
-  EXPECT_EQ(0u, status_fetcher->last_running);
+  EXPECT_EQ(0u, status_fetcher->running());
+  EXPECT_EQ(0u, status_fetcher->last_running());
 
-  action_queue.EnqueueAction(nop_actor_factory.Make(0));
+  {
+    UIntT uint;
+    uint.val = 0;
+    action_queue.EnqueueAction(nop_actor_factory.Make(uint));
+  }
 
   // We started an action and it should be running.
   EXPECT_TRUE(action_queue.Running());
@@ -189,7 +200,11 @@
   action_queue.Tick();
   EXPECT_FALSE(action_queue.Running());
 
-  action_queue.EnqueueAction(nop_actor_factory.Make(0));
+  {
+    UIntT uint;
+    uint.val = 0;
+    action_queue.EnqueueAction(nop_actor_factory.Make(uint));
+  }
 
   // We started an action and it should be running.
   EXPECT_TRUE(action_queue.Running());
@@ -223,8 +238,12 @@
 
   // Enqueue two actions to test both cancel. We can have an action and a next
   // action so we want to test that.
-  action_queue.EnqueueAction(nop_actor_factory.Make(0));
-  action_queue.EnqueueAction(nop_actor_factory.Make(0));
+  {
+    UIntT uint;
+    uint.val = 0;
+    action_queue.EnqueueAction(nop_actor_factory.Make(uint));
+    action_queue.EnqueueAction(nop_actor_factory.Make(uint));
+  }
 
   action_queue.Tick();
 
@@ -274,7 +293,11 @@
   action_queue.Tick();
 
   // Enqueue blocking action.
-  action_queue.EnqueueAction(cancel_action_factory.Make(0));
+  {
+    UIntT uint;
+    uint.val = 0;
+    action_queue.EnqueueAction(cancel_action_factory.Make(uint));
+  }
 
   action_queue.Tick();
   EXPECT_TRUE(action_queue.Running());
@@ -306,7 +329,11 @@
   EXPECT_FALSE(action_queue.Running());
 
   // Enqueue action to be canceled.
-  action_queue.EnqueueAction(nop_actor_factory.Make(0));
+  {
+    UIntT uint;
+    uint.val = 0;
+    action_queue.EnqueueAction(nop_actor_factory.Make(uint));
+  }
   action_queue.Tick();
 
   // Should still be running as the actor could not have signalled.
@@ -325,7 +352,11 @@
   ASSERT_NE(0u, nop_actor_id);
 
   // Add the next action which should ensure the first stopped.
-  action_queue.EnqueueAction(nop_actor_factory.Make(0));
+  {
+    UIntT uint;
+    uint.val = 0;
+    action_queue.EnqueueAction(nop_actor_factory.Make(uint));
+  }
 
   // id for the second run.
   uint32_t nop_actor2_id = 0;
@@ -382,13 +413,17 @@
   EXPECT_FALSE(action_queue.Running());
 
   // Enqueue action to post index.
-  action_queue.EnqueueAction(test_actor_index_factory.Make(5));
-  ::aos::Fetcher<actions::TestActionQueueGroup::Goal> goal_fetcher_ =
-      test_event_loop_->MakeFetcher<actions::TestActionQueueGroup::Goal>(
-          ".aos.common.actions.test_action.goal");
+  {
+    UIntT uint;
+    uint.val = 5;
+    action_queue.EnqueueAction(test_actor_index_factory.Make(uint));
+  }
+  ::aos::Fetcher<actions::TestActionGoal> goal_fetcher_ =
+      test_event_loop_->MakeFetcher<actions::TestActionGoal>(
+          "/test_action");
 
   ASSERT_TRUE(goal_fetcher_.Fetch());
-  EXPECT_EQ(5u, goal_fetcher_->params);
+  EXPECT_EQ(5u, goal_fetcher_->params()->val());
   EXPECT_EQ(0u, idx_actor.index);
 
   action_queue.Tick();
@@ -400,9 +435,13 @@
   EXPECT_EQ(5u, idx_actor.index);
 
   // Enqueue action to post index.
-  action_queue.EnqueueAction(test_actor_index_factory.Make(3));
+  {
+    UIntT uint;
+    uint.val = 3;
+    action_queue.EnqueueAction(test_actor_index_factory.Make(uint));
+  }
   ASSERT_TRUE(goal_fetcher_.Fetch());
-  EXPECT_EQ(3u, goal_fetcher_->params);
+  EXPECT_EQ(3u, goal_fetcher_->params()->val());
 
   // Run the next action so it can accomplish signal completion.
   event_loop_factory_.RunFor(chrono::seconds(1));
@@ -423,7 +462,7 @@
   action_queue.Tick();
   EXPECT_FALSE(action_queue.Running());
 
-  actions::MyParams p;
+  actions::MyParamsT p;
   p.param1 = 5.0;
   p.param2 = 7;
 
diff --git a/aos/actions/action_test_config.json b/aos/actions/action_test_config.json
new file mode 100644
index 0000000..e9b6f16
--- /dev/null
+++ b/aos/actions/action_test_config.json
@@ -0,0 +1,20 @@
+{
+  "channels": [
+    {
+      "name": "/test_action",
+      "type": "aos.common.actions.TestActionGoal"
+    },
+    {
+      "name": "/test_action",
+      "type": "aos.common.actions.Status"
+    },
+    {
+      "name": "/test_action2",
+      "type": "aos.common.actions.TestAction2Goal"
+    },
+    {
+      "name": "/test_action2",
+      "type": "aos.common.actions.Status"
+    }
+  ]
+}
diff --git a/aos/actions/actions.fbs b/aos/actions/actions.fbs
new file mode 100644
index 0000000..0ce41fc
--- /dev/null
+++ b/aos/actions/actions.fbs
@@ -0,0 +1,24 @@
+namespace aos.common.actions;
+
+table Status {
+  // The run value of the instance we're currently running or 0.
+  running:uint;
+  // A run value we were previously running or 0.
+  last_running:uint;
+  // If false the action failed to complete and may be in a bad state,
+  // this is a critical problem not a cancellation.
+  success:bool;
+}
+
+table DoubleParam {
+  val:double;
+}
+
+table Goal {
+  // The unique value to put into status.running while running this instance or
+  // 0 to cancel.
+  run:uint;
+  // Default parameter.  The more useful thing to do would be to define your own
+  // goal type to change param to a useful structure.
+  params:DoubleParam;
+}
diff --git a/aos/actions/actions.h b/aos/actions/actions.h
index e2b9ca8..d01b3f5 100644
--- a/aos/actions/actions.h
+++ b/aos/actions/actions.h
@@ -9,10 +9,10 @@
 #include <atomic>
 #include <memory>
 
-#include "aos/events/event-loop.h"
+#include "aos/actions/actions_generated.h"
+#include "aos/events/event_loop.h"
+#include "aos/json_to_flatbuffer.h"
 #include "aos/logging/logging.h"
-#include "aos/logging/queue_logging.h"
-#include "aos/queue.h"
 
 namespace aos {
 namespace common {
@@ -105,31 +105,28 @@
 class TypedAction : public Action {
  public:
   // A convenient way to refer to the type of our goals.
+  typedef T GoalType;
   typedef typename std::remove_reference<decltype(
-      *(static_cast<T*>(nullptr)->goal.MakeMessage().get()))>::type GoalType;
-  typedef typename std::remove_reference<decltype(
-      *(static_cast<T*>(nullptr)->status.MakeMessage().get()))>::type StatusType;
-  typedef typename std::remove_reference<
-      decltype(static_cast<GoalType*>(nullptr)->params)>::type ParamType;
+      *static_cast<GoalType *>(nullptr)->params())>::type ParamType;
 
-  TypedAction(typename ::aos::Fetcher<StatusType> *status_fetcher,
+  TypedAction(typename ::aos::Fetcher<Status> *status_fetcher,
               typename ::aos::Sender<GoalType> *goal_sender,
-              const ParamType &params)
+              const typename ParamType::NativeTableType &params)
       : status_fetcher_(status_fetcher),
         goal_sender_(goal_sender),
-        goal_(goal_sender_->MakeMessage()),
         // This adds 1 to the counter (atomically because it's potentially
         // shared across threads) and then bitwise-ORs the bottom of the PID to
         // differentiate it from other processes's values (ie a unique id).
         run_value_(run_counter_.fetch_add(1, ::std::memory_order_relaxed) |
                    ((getpid() & 0xFFFF) << 16)),
         params_(params) {
-    AOS_LOG(DEBUG, "Action %" PRIx32 " created on queue %s\n", run_value_,
-            goal_sender_->name());
+    AOS_LOG(DEBUG, "Action %" PRIx32 " created on queue %.*s\n", run_value_,
+            static_cast<int>(goal_sender_->name().size()),
+            goal_sender_->name().data());
     // Clear out any old status messages from before now.
     status_fetcher_->Fetch();
     if (status_fetcher_->get()) {
-      AOS_LOG_STRUCT(DEBUG, "have status", *status_fetcher_->get());
+      VLOG(1) << "have status" << FlatbufferToJson(status_fetcher_->get());
     }
   }
 
@@ -164,9 +161,8 @@
     if (old_run_value != nullptr) *old_run_value = old_run_value_;
   }
 
-  typename ::aos::Fetcher<StatusType> *status_fetcher_;
+  typename ::aos::Fetcher<Status> *status_fetcher_;
   typename ::aos::Sender<GoalType> *goal_sender_;
-  typename ::aos::Sender<GoalType>::Message goal_;
 
   // Track if we have seen a response to the start message.
   bool has_started_ = false;
@@ -182,7 +178,7 @@
   const uint32_t run_value_;
 
   // flag passed to action in order to have differing types
-  const ParamType params_;
+  const typename ParamType::NativeTableType params_;
 
   // The old value for running that we may have seen. If we see any value other
   // than this or run_value_, somebody else got in the way and we're done. 0 if
@@ -196,20 +192,18 @@
 template <typename T>
 class TypedActionFactory {
  public:
+  typedef T GoalType;
   typedef typename std::remove_reference<decltype(
-      *(static_cast<T*>(nullptr)->goal.MakeMessage().get()))>::type GoalType;
-  typedef typename std::remove_reference<decltype(
-      *(static_cast<T*>(nullptr)->status.MakeMessage().get()))>::type StatusType;
-  typedef typename std::remove_reference<decltype(
-      static_cast<GoalType *>(nullptr)->params)>::type ParamType;
+      *static_cast<GoalType *>(nullptr)->params())>::type ParamType;
 
   explicit TypedActionFactory(::aos::EventLoop *event_loop,
                               const ::std::string &name)
       : name_(name),
-        status_fetcher_(event_loop->MakeFetcher<StatusType>(name + ".status")),
-        goal_sender_(event_loop->MakeSender<GoalType>(name + ".goal")) {}
+        status_fetcher_(event_loop->MakeFetcher<Status>(name)),
+        goal_sender_(event_loop->MakeSender<GoalType>(name)) {}
 
-  ::std::unique_ptr<TypedAction<T>> Make(const ParamType &param) {
+  ::std::unique_ptr<TypedAction<T>> Make(
+      const typename ParamType::NativeTableType &param) {
     return ::std::unique_ptr<TypedAction<T>>(
         new TypedAction<T>(&status_fetcher_, &goal_sender_, param));
   }
@@ -221,7 +215,7 @@
 
  private:
   const ::std::string name_;
-  typename ::aos::Fetcher<StatusType> status_fetcher_;
+  typename ::aos::Fetcher<Status> status_fetcher_;
   typename ::aos::Sender<GoalType> goal_sender_;
 };
 
@@ -231,25 +225,31 @@
 template <typename T>
 void TypedAction<T>::DoCancel() {
   if (!sent_started_) {
-    AOS_LOG(INFO, "Action %" PRIx32 " on queue %s was never started\n",
-            run_value_, goal_sender_->name());
+    AOS_LOG(INFO, "Action %" PRIx32 " on queue %.*s was never started\n",
+            run_value_, static_cast<int>(goal_sender_->name().size()),
+            goal_sender_->name().data());
   } else {
     if (interrupted_) {
       AOS_LOG(INFO,
               "Action %" PRIx32
-              " on queue %s was interrupted -> not cancelling\n",
-              run_value_, goal_sender_->name());
+              " on queue %.*s was interrupted -> not cancelling\n",
+              run_value_, static_cast<int>(goal_sender_->name().size()),
+              goal_sender_->name().data());
     } else {
       if (sent_cancel_) {
-        AOS_LOG(DEBUG, "Action %" PRIx32 " on queue %s already cancelled\n",
-                run_value_, goal_sender_->name());
+        AOS_LOG(DEBUG, "Action %" PRIx32 " on queue %.*s already cancelled\n",
+                run_value_, static_cast<int>(goal_sender_->name().size()),
+                goal_sender_->name().data());
       } else {
-        AOS_LOG(DEBUG, "Canceling action %" PRIx32 " on queue %s\n", run_value_,
-                goal_sender_->name());
+        AOS_LOG(DEBUG, "Canceling action %" PRIx32 " on queue %.*s\n",
+                run_value_, static_cast<int>(goal_sender_->name().size()),
+                goal_sender_->name().data());
         {
-          auto goal_message = goal_sender_->MakeMessage();
-          goal_message->run = 0;
-          goal_message.Send();
+          auto builder = goal_sender_->MakeBuilder();
+          typename GoalType::Builder goal_builder =
+              builder.template MakeBuilder<GoalType>();
+          goal_builder.add_run(0);
+          builder.Send(goal_builder.Finish());
         }
         sent_cancel_ = true;
       }
@@ -268,7 +268,7 @@
     CheckInterrupted();
   } else {
     while (status_fetcher_->FetchNext()) {
-      AOS_LOG_STRUCT(DEBUG, "got status", *status_fetcher_->get());
+      VLOG(1) << "got status" << FlatbufferToJson(status_fetcher_->get());
       CheckStarted();
       if (has_started_) CheckInterrupted();
     }
@@ -278,7 +278,7 @@
   // yet.
   if (!has_started_) return true;
   return status_fetcher_->get() &&
-         status_fetcher_->get()->running == run_value_;
+         status_fetcher_->get()->running() == run_value_;
 }
 
 template <typename T>
@@ -289,11 +289,11 @@
   if (!status_fetcher_->FetchNext()) {
     return false;
   }
-  AOS_LOG_STRUCT(DEBUG, "got status", *status_fetcher_->get());
+  VLOG(1) << "got status" << FlatbufferToJson(status_fetcher_->get());
   CheckStarted();
   CheckInterrupted();
   if (has_started_ && (status_fetcher_->get() &&
-                       status_fetcher_->get()->running != run_value_)) {
+                       status_fetcher_->get()->running() != run_value_)) {
     return true;
   }
   return false;
@@ -303,23 +303,24 @@
 void TypedAction<T>::CheckStarted() {
   if (has_started_) return;
   if (status_fetcher_->get()) {
-    if (status_fetcher_->get()->running == run_value_ ||
-        (status_fetcher_->get()->running == 0 &&
-         status_fetcher_->get()->last_running == run_value_)) {
+    if (status_fetcher_->get()->running() == run_value_ ||
+        (status_fetcher_->get()->running() == 0 &&
+         status_fetcher_->get()->last_running() == run_value_)) {
       // It's currently running our instance.
       has_started_ = true;
-      AOS_LOG(DEBUG, "Action %" PRIx32 " on queue %s has been started\n",
-              run_value_, goal_sender_->name());
+      AOS_LOG(DEBUG, "Action %" PRIx32 " on queue %.*s has been started\n",
+              run_value_, static_cast<int>(goal_sender_->name().size()),
+              goal_sender_->name().data());
     } else if (old_run_value_ != 0 &&
-               status_fetcher_->get()->running == old_run_value_) {
+               status_fetcher_->get()->running() == old_run_value_) {
       AOS_LOG(DEBUG, "still running old instance %" PRIx32 "\n",
               old_run_value_);
     } else {
       AOS_LOG(WARNING,
-              "Action %" PRIx32 " on queue %s interrupted by %" PRIx32
+              "Action %" PRIx32 " on queue %.*s interrupted by %" PRIx32
               " before starting\n",
-              run_value_, goal_sender_->name(),
-              status_fetcher_->get()->running);
+              run_value_, static_cast<int>(goal_sender_->name().size()),
+              goal_sender_->name().data(), status_fetcher_->get()->running());
       has_started_ = true;
       interrupted_ = true;
     }
@@ -331,13 +332,13 @@
 template <typename T>
 void TypedAction<T>::CheckInterrupted() {
   if (!interrupted_ && has_started_ && status_fetcher_->get()) {
-    if (status_fetcher_->get()->running != 0 &&
-        status_fetcher_->get()->running != run_value_) {
+    if (status_fetcher_->get()->running() != 0 &&
+        status_fetcher_->get()->running() != run_value_) {
       AOS_LOG(WARNING,
-              "Action %" PRIx32 " on queue %s interrupted by %" PRIx32
+              "Action %" PRIx32 " on queue %.*s interrupted by %" PRIx32
               " after starting\n",
-              run_value_, goal_sender_->name(),
-              status_fetcher_->get()->running);
+              run_value_, static_cast<int>(goal_sender_->name().size()),
+              goal_sender_->name().data(), status_fetcher_->get()->running());
     }
   }
 }
@@ -346,29 +347,38 @@
 void TypedAction<T>::DoStart() {
   if (!sent_started_) {
     AOS_LOG(DEBUG, "Starting action %" PRIx32 "\n", run_value_);
-    goal_->run = run_value_;
-    goal_->params = params_;
+    auto builder = goal_sender_->MakeBuilder();
+    auto params_offset = ParamType::Pack(*builder.fbb(), &params_);
+
+    auto goal_builder = builder.template MakeBuilder<GoalType>();
+    goal_builder.add_params(params_offset);
+    goal_builder.add_run(run_value_);
+
     sent_started_ = true;
-    if (!goal_.Send()) {
-      AOS_LOG(ERROR, "sending goal for action %" PRIx32 " on queue %s failed\n",
-              run_value_, goal_sender_->name());
+    if (!builder.Send(goal_builder.Finish())) {
+      AOS_LOG(ERROR,
+              "sending goal for action %" PRIx32 " on queue %.*s failed\n",
+              run_value_, static_cast<int>(goal_sender_->name().size()),
+              goal_sender_->name().data());
       // Don't wait to see a message with it.
       has_started_ = true;
     }
     status_fetcher_->FetchNext();
     if (status_fetcher_->get()) {
-      AOS_LOG_STRUCT(DEBUG, "got status", *status_fetcher_->get());
+      VLOG(1) << "got status" << FlatbufferToJson(status_fetcher_->get());
     }
-    if (status_fetcher_->get() && status_fetcher_->get()->running != 0) {
-      old_run_value_ = status_fetcher_->get()->running;
-      AOS_LOG(INFO, "Action %" PRIx32 " on queue %s already running\n",
-              old_run_value_, goal_sender_->name());
+    if (status_fetcher_->get() && status_fetcher_->get()->running() != 0) {
+      old_run_value_ = status_fetcher_->get()->running();
+      AOS_LOG(INFO, "Action %" PRIx32 " on queue %.*s already running\n",
+              old_run_value_, static_cast<int>(goal_sender_->name().size()),
+              goal_sender_->name().data());
     } else {
       old_run_value_ = 0;
     }
   } else {
-    AOS_LOG(WARNING, "Action %" PRIx32 " on queue %s already started\n",
-            run_value_, goal_sender_->name());
+    AOS_LOG(WARNING, "Action %" PRIx32 " on queue %.*s already started\n",
+            run_value_, static_cast<int>(goal_sender_->name().size()),
+            goal_sender_->name().data());
   }
 }
 
diff --git a/aos/actions/actions.q b/aos/actions/actions.q
deleted file mode 100644
index e3046c9..0000000
--- a/aos/actions/actions.q
+++ /dev/null
@@ -1,35 +0,0 @@
-package aos.common.actions;
-
-interface StatusInterface {
-  // 0 if the action isn't running or the value from goal.run.
-  uint32_t running;
-};
-
-interface GoalInterface {
-  // 0 to stop or an arbitrary value to put in status.running.
-  uint32_t run;
-};
-
-message Status {
-  // The run value of the instance we're currently running or 0.
-  uint32_t running;
-  // A run value we were previously running or 0.
-  uint32_t last_running;
-  // If false the action failed to complete and may be in a bad state,
-  // this is a critical problem not a cancellation.
-  bool success;
-};
-
-message Goal {
-  // The unique value to put into status.running while running this instance or
-  // 0 to cancel.
-  uint32_t run;
-  // Default parameter.  The more useful thing to do would be to define your own
-  // goal type to change param to a useful structure.
-  double params;
-};
-
-interface ActionQueueGroup {
-  queue Status status;
-  queue Goal goal;
-};
diff --git a/aos/actions/actor.h b/aos/actions/actor.h
index a9b75e6..f5629a6 100644
--- a/aos/actions/actor.h
+++ b/aos/actions/actor.h
@@ -7,9 +7,9 @@
 #include <chrono>
 #include <functional>
 
+#include "aos/actions/actions_generated.h"
 #include "aos/controls/control_loop.h"
 #include "aos/logging/logging.h"
-#include "aos/logging/queue_logging.h"
 #include "aos/time/time.h"
 #include "aos/util/phased_loop.h"
 
@@ -20,29 +20,27 @@
 template <class T>
 class ActorBase {
  public:
+  typedef T GoalType;
   typedef typename std::remove_reference<decltype(
-      *(static_cast<T *>(nullptr)->goal.MakeMessage().get()))>::type GoalType;
-  typedef typename std::remove_reference<decltype(*(
-      static_cast<T *>(nullptr)->status.MakeMessage().get()))>::type StatusType;
-  typedef typename std::remove_reference<decltype(
-      static_cast<GoalType *>(nullptr)->params)>::type ParamType;
+      *static_cast<GoalType *>(nullptr)->params())>::type ParamType;
 
   ActorBase(::aos::EventLoop *event_loop, const ::std::string &name)
       : event_loop_(event_loop),
-        status_sender_(event_loop->MakeSender<StatusType>(name + ".status")),
-        goal_fetcher_(event_loop->MakeFetcher<GoalType>(name + ".goal")) {
+        status_sender_(event_loop->MakeSender<Status>(name)),
+        goal_fetcher_(event_loop->MakeFetcher<GoalType>(name)) {
     AOS_LOG(INFO, "Constructing action %s\n", name.c_str());
-    event_loop->MakeWatcher(name + ".goal",
+    event_loop->MakeWatcher(name,
                             [this](const GoalType &goal) { HandleGoal(goal); });
 
     // Send out an inital status saying we aren't running to wake up any users
     // who might be waiting forever for the previous action.
     event_loop->OnRun([this]() {
-      auto status_message = status_sender_.MakeMessage();
-      status_message->running = 0;
-      status_message->last_running = 0;
-      status_message->success = !abort_;
-      if (!status_message.Send()) {
+      auto builder = status_sender_.MakeBuilder();
+      Status::Builder status_builder = builder.template MakeBuilder<Status>();
+      status_builder.add_running(0);
+      status_builder.add_last_running(0);
+      status_builder.add_success(!abort_);
+      if (!builder.Send(status_builder.Finish())) {
         AOS_LOG(ERROR, "Failed to send the status.\n");
       }
     });
@@ -99,7 +97,7 @@
   // Will return true if finished or asked to cancel.
   // Will return false if it failed accomplish its goal
   // due to a problem with the system.
-  virtual bool RunAction(const ParamType& params) = 0;
+  virtual bool RunAction(const ParamType *params) = 0;
 
   void HandleGoal(const GoalType &goal);
 
@@ -110,7 +108,7 @@
 
   uint32_t current_id_ = 0;
 
-  ::aos::Sender<StatusType> status_sender_;
+  ::aos::Sender<Status> status_sender_;
   ::aos::Fetcher<GoalType> goal_fetcher_;
 
   State state_ = State::WAITING_FOR_ACTION;
@@ -118,48 +116,51 @@
 
 template <class T>
 void ActorBase<T>::HandleGoal(const GoalType &goal) {
-  AOS_LOG_STRUCT(DEBUG, "action goal", goal);
+  VLOG(1) << "action goal " << FlatbufferToJson(&goal);
   switch (state_) {
     case State::WAITING_FOR_ACTION:
-      if (goal.run) {
+      if (goal.run()) {
         state_ = State::RUNNING_ACTION;
       } else {
-        auto status_message = status_sender_.MakeMessage();
-        status_message->running = 0;
-        status_message->last_running = 0;
-        status_message->success = !abort_;
-        if (!status_message.Send()) {
+        auto builder = status_sender_.MakeBuilder();
+        Status::Builder status_builder = builder.template MakeBuilder<Status>();
+        status_builder.add_running(0);
+        status_builder.add_last_running(0);
+        status_builder.add_success(!abort_);
+        if (!builder.Send(status_builder.Finish())) {
           AOS_LOG(ERROR, "Failed to send the status.\n");
         }
         break;
       }
     case State::RUNNING_ACTION: {
       ++running_count_;
-      const uint32_t running_id = goal.run;
+      const uint32_t running_id = goal.run();
       current_id_ = running_id;
       AOS_LOG(INFO, "Starting action %" PRIx32 "\n", running_id);
       {
-        auto status_message = status_sender_.MakeMessage();
-        status_message->running = running_id;
-        status_message->last_running = 0;
-        status_message->success = !abort_;
-        if (!status_message.Send()) {
+        auto builder = status_sender_.MakeBuilder();
+        Status::Builder status_builder = builder.template MakeBuilder<Status>();
+        status_builder.add_running(running_id);
+        status_builder.add_last_running(0);
+        status_builder.add_success(!abort_);
+        if (!builder.Send(status_builder.Finish())) {
           AOS_LOG(ERROR, "Failed to send the status.\n");
         }
       }
 
-      AOS_LOG_STRUCT(INFO, "goal", goal);
-      abort_ = !RunAction(goal.params);
+      VLOG(1) << "goal " << FlatbufferToJson(&goal);
+      abort_ = !RunAction(goal.params());
       AOS_LOG(INFO, "Done with action %" PRIx32 "\n", running_id);
       current_id_ = 0u;
 
       {
-        auto status_message = status_sender_.MakeMessage();
-        status_message->running = 0;
-        status_message->last_running = running_id;
-        status_message->success = !abort_;
+        auto builder = status_sender_.MakeBuilder();
+        Status::Builder status_builder = builder.template MakeBuilder<Status>();
+        status_builder.add_running(0);
+        status_builder.add_last_running(running_id);
+        status_builder.add_success(!abort_);
 
-        if (!status_message.Send()) {
+        if (!builder.Send(status_builder.Finish())) {
           AOS_LOG(ERROR, "Failed to send the status.\n");
         } else {
           AOS_LOG(INFO, "Sending Done status %" PRIx32 "\n", running_id);
@@ -171,7 +172,7 @@
               running_id);
     } break;
     case State::WAITING_FOR_STOPPED:
-      if (goal.run == 0) {
+      if (goal.run() == 0) {
         AOS_LOG(INFO, "Action stopped.\n");
         state_ = State::WAITING_FOR_ACTION;
       }
@@ -211,9 +212,9 @@
 template <class T>
 bool ActorBase<T>::ShouldCancel() {
   if (goal_fetcher_.Fetch()) {
-    AOS_LOG_STRUCT(DEBUG, "goal queue", *goal_fetcher_);
+    VLOG(1) << "goal queue " << FlatbufferToJson(goal_fetcher_.get());
   }
-  bool ans = !goal_fetcher_->run || goal_fetcher_->run != current_id_;
+  bool ans = !goal_fetcher_->run() || goal_fetcher_->run() != current_id_;
   if (ans) {
     AOS_LOG(INFO, "Time to stop action\n");
   }
diff --git a/aos/actions/test_action.fbs b/aos/actions/test_action.fbs
new file mode 100644
index 0000000..f7f8052
--- /dev/null
+++ b/aos/actions/test_action.fbs
@@ -0,0 +1,20 @@
+namespace aos.common.actions;
+
+table UInt {
+  val:uint;
+}
+
+table TestActionGoal {
+  run:uint;
+  params:UInt;
+}
+
+table MyParams {
+  param1:double;
+  param2:int;
+}
+
+table TestAction2Goal {
+  run:uint;
+  params:MyParams;
+}
diff --git a/aos/actions/test_action.q b/aos/actions/test_action.q
deleted file mode 100644
index f2d268d..0000000
--- a/aos/actions/test_action.q
+++ /dev/null
@@ -1,32 +0,0 @@
-package aos.common.actions;
-
-import "aos/actions/actions.q";
-
-queue_group TestActionQueueGroup {
-  implements aos.common.actions.ActionQueueGroup;
-
-  message Goal {
-    uint32_t run;
-    uint32_t params;
-  };
-
-  queue Goal goal;
-  queue aos.common.actions.Status status;
-};
-
-struct MyParams {
-  double param1;
-  int32_t param2;
-};
-
-queue_group TestAction2QueueGroup {
-  implements aos.common.actions.ActionQueueGroup;
-
-  message Goal {
-    uint32_t run;
-    MyParams params;
-  };
-
-  queue Goal goal;
-  queue aos.common.actions.Status status;
-};
diff --git a/aos/build/BUILD b/aos/build/BUILD
deleted file mode 100644
index e69de29..0000000
--- a/aos/build/BUILD
+++ /dev/null
diff --git a/aos/build/queues.bzl b/aos/build/queues.bzl
deleted file mode 100644
index 07a91e4..0000000
--- a/aos/build/queues.bzl
+++ /dev/null
@@ -1,117 +0,0 @@
-def _single_queue_file_impl(ctx):
-  args = [
-    '-h_file_path', ctx.outputs.header.path,
-    '-cc_file_path', ctx.outputs.cc.path,
-    '-src_filename', ctx.file.src.short_path,
-    '-I', '.',
-    ctx.file.src.path,
-  ]
-  ctx.action(
-    outputs = [
-      ctx.outputs.header,
-      ctx.outputs.cc,
-    ],
-    inputs = [ ctx.file.src ] + ctx.attr.q_deps.transitive_q_files,
-    executable = ctx.executable._queue_compiler,
-    arguments = args,
-    mnemonic = 'QGen',
-    progress_message = 'Generating C++ code for %s' % ctx.file.src.short_path,
-  )
-
-def _single_queue_file_outputs(src):
-  return {
-    'header': src.name + '.h',
-    'cc': src.name + '.cc',
-  }
-
-_single_queue_file = rule(
-    attrs = {
-        "src": attr.label(
-            mandatory = True,
-            single_file = True,
-            allow_files = [".q"],
-        ),
-        "q_deps": attr.label(
-            providers = ["transitive_q_files"],
-            mandatory = True,
-        ),
-        "package_name": attr.string(
-            mandatory = True,
-        ),
-        "_queue_compiler": attr.label(
-            executable = True,
-            default = Label("//aos/build/queues:compiler"),
-            cfg = "host",
-        ),
-    },
-    output_to_genfiles = True,
-    outputs = _single_queue_file_outputs,
-    implementation = _single_queue_file_impl,
-)
-
-def _q_deps_impl(ctx):
-  transitive_q_files = ctx.files.srcs
-  for dep in ctx.attr.deps:
-    transitive_q_files = transitive_q_files + dep.transitive_q_files
-  return struct(transitive_q_files = transitive_q_files)
-
-_q_deps = rule(
-    attrs = {
-        "srcs": attr.label_list(
-            mandatory = True,
-            non_empty = True,
-            allow_files = [".q"],
-        ),
-        "deps": attr.label_list(
-            mandatory = True,
-            non_empty = False,
-            providers = ["transitive_q_files"],
-        ),
-    },
-    implementation = _q_deps_impl,
-)
-
-"""Creates a C++ library from a set of .q files.
-
-Attrs:
-  srcs: A list of .q files.
-  deps: Other queue_library rules this one depends on.
-"""
-
-def queue_library(name, srcs, deps = [],
-                  compatible_with = None, restricted_to = None,
-                  visibility = None):
-  q_deps = _q_deps(
-    name = name + '__q_deps',
-    srcs = srcs,
-    deps = [dep + '__q_deps' for dep in deps],
-    visibility = visibility,
-    compatible_with = compatible_with,
-    restricted_to = restricted_to,
-  )
-
-  for src in srcs:
-    _single_queue_file(
-      name = name + '_' + src,
-      src = src,
-      q_deps = ':%s__q_deps' % name,
-      package_name = native.package_name(),
-      visibility = ['//visibility:private'],
-      compatible_with = compatible_with,
-      restricted_to = restricted_to,
-    )
-
-  native.cc_library(
-    name = name,
-    srcs = [src + '.cc' for src in srcs],
-    hdrs = [src + '.h' for src in srcs],
-    deps = deps + [
-      '//aos:once',
-      '//aos:queues',
-      '//aos:queue_types',
-      '//aos/logging:printf_formats',
-    ],
-    visibility = visibility,
-    compatible_with = compatible_with,
-    restricted_to = restricted_to,
-  )
diff --git a/aos/build/queues/BUILD b/aos/build/queues/BUILD
deleted file mode 100644
index 0ff6a87..0000000
--- a/aos/build/queues/BUILD
+++ /dev/null
@@ -1,45 +0,0 @@
-load("//tools/build_rules:ruby.bzl", "ruby_library", "ruby_binary")
-
-ruby_library(
-    name = "lib",
-    srcs = [
-        "load.rb",
-        "write_iff_changed.rb",
-    ] + glob(["*/*.rb"]),
-)
-
-ruby_binary(
-    name = "compiler",
-    srcs = [
-        "compiler.rb",
-    ],
-    data = [
-        "@clang_3p6_repo//:clang-format",
-    ],
-    visibility = ["//visibility:public"],
-    deps = [
-        ":lib",
-    ],
-)
-
-ruby_binary(
-    name = "queue_primitives",
-    srcs = [
-        "queue_primitives.rb",
-    ],
-    visibility = ["//visibility:public"],
-    deps = [
-        ":lib",
-    ],
-)
-
-ruby_binary(
-    name = "print_field",
-    srcs = [
-        "print_field.rb",
-    ],
-    visibility = ["//visibility:public"],
-    deps = [
-        ":lib",
-    ],
-)
diff --git a/aos/build/queues/compiler.rb b/aos/build/queues/compiler.rb
deleted file mode 100644
index 6ca141d..0000000
--- a/aos/build/queues/compiler.rb
+++ /dev/null
@@ -1,152 +0,0 @@
-require_relative "load.rb"
-
-def parse_args(globals,args)
-  i = 0
-  while(i < args.length)
-    if(args[i] == "-I")
-      args.delete_at(i)
-      if(!args[i])
-        $stderr.puts "hey! -I is followed by nothing."
-        $stderr.puts "\tnot a supported usage..."
-        $stderr.puts "\tWot. Wot."
-        exit!(-1)
-      end
-      path = args.delete_at(i)
-      globals.add_path(path)
-    elsif(args[i] == "-cpp_out")
-      args.delete_at(i)
-      path = args.delete_at(i)
-      if(path =~ /\./)
-        $stderr.puts "hey! path #{path} has a \".\" char which is "
-        $stderr.puts "\tnot a supported usage..."
-        $stderr.puts "\tWot. Wot."
-        exit!(-1)
-      elsif(!path)
-        $stderr.puts "hey! No cpp_out path provided."
-        $stderr.puts "\tumm, you could try -cpp_out \"\""
-        $stderr.puts "\tThat might do the trick"
-        $stderr.puts "\tWot. Wot."
-        exit!(-1)
-      end
-      $cpp_out = path.split(/\\|\//)
-    elsif(args[i] == "-cpp_base")
-      args.delete_at(i)
-      path = args.delete_at(i)
-      $cpp_base = File.expand_path(path)
-      if(!File.exists?($cpp_base))
-        $stderr.puts "output directory #{$cpp_base.inspect} does not exist."
-        $stderr.puts "\tI'm not going to make that! sheesh, who do you think I am?"
-        $stderr.puts "\tWot. Wot."
-        exit!(-1)
-      end
-    elsif(args[i] == "-src_filename")
-      args.delete_at(i)
-      $src_filename = args.delete_at(i)
-    elsif(args[i] == "-h_file_path")
-      args.delete_at(i)
-      path = args.delete_at(i)
-      $h_file_path = File.expand_path(path)
-      if(!File.exists?(File.dirname($h_file_path)))
-        $stderr.puts "directory of output #{$h_file_path.inspect} does not exist."
-        $stderr.puts "\tI'm not going to make that! sheesh, who do you think I am?"
-        $stderr.puts "\tWot. Wot."
-        exit!(-1)
-      end
-    elsif(args[i] == "-cc_file_path")
-      args.delete_at(i)
-      path = args.delete_at(i)
-      $cc_file_path = File.expand_path(path)
-      if(!File.exists?(File.dirname($cc_file_path)))
-        $stderr.puts "directory of output #{$cc_file_path.inspect} does not exist."
-        $stderr.puts "\tI'm not going to make that! sheesh, who do you think I am?"
-        $stderr.puts "\tWot. Wot."
-        exit!(-1)
-      end
-    elsif(args[i] =~ /^-/)
-      $stderr.puts "hey! unknown argument #{args[i]}."
-      $stderr.puts "\tWot. Wot."
-      exit!(-1)
-    else
-      i += 1
-    end
-  end
-  if ($cpp_base && $cpp_out) == ($src_filename && $h_file_path && $cc_file_path)
-    $stderr.puts "hey! I'm not sure where to write the output files!"
-    exit!(-1)
-  end
-end
-def format_pipeline(output)
-  read_in, write_in = IO.pipe()
-  # TODO(phil): Is there a better way to use the sandboxed clang-format here?
-  child = Process.spawn({'LD_LIBRARY_PATH' => './bazel-out/host/bin/aos/build/queues/compiler.runfiles/org_frc971/external/clang_3p6_repo/usr/lib/x86_64-linux-gnu'},
-                        './bazel-out/host/bin/aos/build/queues/compiler.runfiles/org_frc971/external/clang_3p6_repo/usr/bin/clang-format-3.6 --style=google',
-                        {:in=>read_in, write_in=>:close,
-                         :out=>output.fileno})
-  read_in.close
-  [child, write_in]
-end
-def build(filename,globals_template)
-  globals = Globals.new()
-  globals_template.paths.each do |path|
-    globals.add_path(path)
-  end
-  filename = File.expand_path(filename)
-  q_file = QFile.parse(filename)
-  output_file = q_file.q_eval(globals)
-  q_filename = File.basename(filename)
-
-  if $cpp_base && $cpp_out
-    $src_filename = ($cpp_out + [q_filename]).join("/")
-    $h_file_path = $cpp_base + "/" + $src_filename + ".h"
-    $cc_file_path = $cpp_base + "/" + $src_filename + ".cc"
-    FileUtils.mkdir_p(Pathname.new($cpp_base) + $cpp_out.join("/"))
-  end
-
-  cpp_tree = output_file.make_cpp_tree($src_filename)
-
-  cpp_tree.add_cc_include(($src_filename + ".h").inspect)
-  cpp_tree.add_cc_include("aos/byteorder.h".inspect)
-  cpp_tree.add_cc_include("<inttypes.h>")
-  cpp_tree.add_cc_include("aos/queue_types.h".inspect)
-  cpp_tree.add_cc_include("aos/once.h".inspect)
-  cpp_tree.add_cc_include("aos/logging/printf_formats.h".inspect)
-  cpp_tree.add_cc_using("::aos::to_network")
-  cpp_tree.add_cc_using("::aos::to_host")
-
-  header_file = WriteIffChanged.new($h_file_path)
-  cc_file = WriteIffChanged.new($cc_file_path)
-  header_child, header_output = format_pipeline(header_file)
-  cc_child, cc_output = format_pipeline(cc_file)
-  cpp_tree.write_header_file($cpp_base,header_output)
-  cpp_tree.write_cc_file($cpp_base,cc_output)
-  header_output.close()
-  cc_output.close()
-  if !Process.wait2(cc_child)[1].success?
-    $stderr.puts "Formatting cc file failed."
-    exit 1
-  end
-  if !Process.wait2(header_child)[1].success?
-    $stderr.puts "Formatting header file failed."
-    exit 1
-  end
-  header_file.close()
-  cc_file.close()
-end
-begin
-  args = ARGV.dup
-  globals = Globals.new()
-  parse_args(globals,args)
-  if(args.length == 0)
-    $stderr.puts "hey! you want me to do something,"
-    $stderr.puts "\tbut you gave me no q files to build!"
-    $stderr.puts "\tWot. Wot."
-    exit!(-1)
-  end
-  args.each do |filename|
-    build(filename,globals)
-  end
-  exit(0)
-rescue QError => e
-  $stderr.print(e.to_s)
-  exit!(-1)
-end
diff --git a/aos/build/queues/cpp_pretty_print/auto_gen.rb b/aos/build/queues/cpp_pretty_print/auto_gen.rb
deleted file mode 100644
index d3fb480..0000000
--- a/aos/build/queues/cpp_pretty_print/auto_gen.rb
+++ /dev/null
@@ -1,306 +0,0 @@
-module CPP
-end
-class CPP::Comment
-	def initialize(text)
-		@text = text
-	end
-	def pp(state)
-		state.needs_semi = false
-		if(@text.include?("\n"))
-			state.print("/* #{@text} */")
-		else
-			state.print("// #{@text}")
-		end
-	end
-end
-class CPP::TODO < CPP::Comment
-	def initialize(owner,text)
-		@text = "TODO(#{owner}): #{text}"
-	end
-end
-class CPP::StaticVar
-	class ForwardDec
-		def initialize(func) ; @func = func ; end
-		def pp(state) ; @func.pp_forward_dec(state) ; end
-	end
-	attr_accessor :args, :static
-	def initialize(type_class, val_type, name, args = CPP::Args.new())
-		@type_class = type_class
-		@val_type = val_type
-		@name = name
-		@args = args
-		@static = true
-	end
-	def forward_dec() ; ForwardDec.new(self) ; end
-	def pp_forward_dec(state)
-    if (@static)
-      state.print("static ")
-		end
-		state.print("#{@val_type} #{@name}")
-	end
-	def pp(state)
-		state.print("#{@val_type} #{@type_class.chop_method_prefix}#{@name}(")
-		state.pp(@args)
-		state.print(")")
-	end
-	alias_method :pp_header_file, :pp_forward_dec
-	alias_method :pp_cc_file, :pp
-end
-class CPP::MemberFunc
-	class ForwardDec
-		def initialize(func) ; @func = func ; end
-		def pp(state) ; @func.pp_forward_dec(state) ; end
-	end
-	attr_accessor :args,:suite,:return_type,:name,:pre_func_types,:const,:static,:virtual
-	def initialize(type_class,return_type,name)
-		@type_class = type_class
-		@return_type = return_type
-		@name = name
-		@const = false
-		@static = false
-		@virtual = false
-		@args = CPP::Args.new()
-		@suite = CPP::Suite.new()
-	end
-	attr_accessor :inline
-	def forward_dec() ; ForwardDec.new(self) ; end
-	def pp_forward_dec(state)
-		return self.pp_inline(state) if(@inline)
-        if (@static)
-          state.print("static ")
-				elsif (@virtual)
-          state.print("virtual ")
-        end
-		state.print("#{@return_type} #{@pre_func_types}#{@name}(")
-		state.pp(@args)
-		state.print(")")
-        if (@const)
-          state.print(" const")
-        end
-	end
-	def pp_inline(state)
-        if (@static)
-          state.print("static ")
-				elsif (@virtual)
-          state.print("virtual ")
-        end
-		state.print("#{@return_type} #{@pre_func_types}#{@name}(")
-		state.pp(@args)
-		state.print(") ")
-        if (@const)
-          state.print(" const")
-        end
-		@suite.pp_one_line(state)
-	end
-	def pp(state)
-		return if(@inline)
-		state.print("#{@return_type} #{@pre_func_types}#{@type_class.chop_method_prefix}#{@name}(")
-		state.pp(@args)
-		state.print(") ")
-		if (@const)
-			state.print("const ")
-		end
-		state.pp(@suite)
-		state.v_pad(2)
-	end
-	alias_method :pp_header_file, :pp_forward_dec
-	alias_method :pp_cc_file, :pp
-	
-end
-class CPP::Constructor
-	class ForwardDec
-		def initialize(func) ; @func = func ; end
-		def pp(state) ; @func.pp_forward_dec(state) ; end
-	end
-	attr_accessor :args,:suite,:return_type,:name
-	def initialize(type_class)
-		@type_class = type_class
-		@args = CPP::Args.new()
-		@suite = CPP::Suite.new()
-		@var_cons = CPP::Args.new()
-	end
-	def forward_dec() ; ForwardDec.new(self) ; end
-	def add_cons(*args)
-		@var_cons.push(CPP::FuncCall.build(*args))
-	end
-	def pp_forward_dec(state)
-		state.print("#{@type_class.name}(")
-		state.pp(@args)
-		state.print(")")
-	end
-	def pp_inline(state)
-		pp(state,false)
-	end
-	def pp(state,prefix = true)
-		state.needs_semi = false
-		state.print(@type_class.chop_method_prefix) if(prefix)
-		state.print("#{@type_class.name}(")
-		state.pp(@args)
-		if(@var_cons.length >= 1)
-			state.print(")")
-			state.endline()
-			state.indent += 4
-			state.print(": ")
-			state.pp(@var_cons)
-			state.indent -= 4
-			state.print(" ")
-		else
-			state.print(") ")
-		end
-		state.pp(@suite)
-		state.v_pad(2)
-	end
-	alias_method :pp_header_file, :pp_forward_dec
-	alias_method :pp_cc_file, :pp
-end
-class CPP::Destructor
-	class ForwardDec
-		def initialize(func) ; @func = func ; end
-		def pp(state) ; @func.pp_forward_dec(state) ; end
-	end
-	attr_accessor :args,:suite,:return_type,:name
-	def initialize(type_class)
-		@type_class = type_class
-		@args = CPP::Args.new()
-		@suite = CPP::Suite.new()
-	end
-	def forward_dec() ; ForwardDec.new(self) ; end
-	def pp_forward_dec(state)
-		state.print("~#{@type_class.name}(")
-		state.pp(@args)
-		state.print(")")
-	end
-	def pp(state)
-		state.print("#{@type_class.chop_method_prefix}~#{@type_class.name}(")
-		state.pp(@args)
-		state.print(") ")
-		state.pp(@suite)
-		state.v_pad(2)
-	end
-	alias_method :pp_header_file, :pp_forward_dec
-	alias_method :pp_cc_file, :pp
-end
-class CPP::Include
-	attr_accessor :filename
-	def initialize(filename)
-		@filename = filename
-	end
-	def pp(state)
-		state.needs_semi = false
-		state.suppress_indent()
-		state.print("#include #{@filename}")
-		state.endline()
-	end
-end
-class CPP::IncludeGuard
-	attr_accessor :name,:suite
-	def initialize(suite = CPP::Suite.new())
-		@suite = suite
-	end
-	def self.rand_name(len = 40)
-		str = ""
-		len.times { str += ((rand(26) + ?A).chr)}
-		return str
-	end
-	def pp(state)
-		@name ||= IncludeGuard.rand_name
-		state.needs_semi = false
-		state.suppress_indent()
-		state.print("#ifndef #{@name}")
-		state.endline()
-		state.suppress_indent()
-		state.print("#define #{@name}")
-		state.endline()
-		if(@suite.respond_to?(:pp_no_braces))
-			@suite.pp_no_braces(state)
-		else
-			state.pp(@suite)
-		end
-		state.endline()
-		state.needs_semi = false
-		state.suppress_indent()
-		state.print("#endif  // #{@name}")
-		state.endline()
-	end
-end
-class CPP::IfnDef
-	attr_accessor :name,:suite
-	def initialize(suite = CPP::Suite.new())
-		@suite = suite
-	end
-	def pp(state)
-		state.needs_semi = false
-		state.suppress_indent()
-		state.print("#ifndef #{@name}")
-		state.endline()
-		if(@suite.respond_to?(:pp_no_braces))
-			@suite.pp_no_braces(state)
-		else
-			state.pp(@suite)
-		end
-		state.endline()
-		state.needs_semi = false
-		state.suppress_indent()
-		state.print("#endif  // #{@name}")
-		state.endline()
-	end
-end
-class CPP::PreprocessorIf
-	attr_accessor :name,:suite
-	def initialize(ifsuite, elsesuite)
-		@ifsuite = ifsuite
-		@elsesuite = elsesuite
-	end
-	def write_if(state)
-		state.needs_semi = false
-		state.suppress_indent()
-		state.print("#if #{@name}")
-		state.endline()
-	end
-	def write_else(state)
-		state.needs_semi = false
-		state.suppress_indent()
-		state.print("#else  // #{@name}")
-		state.endline()
-	end
-	def write_endif(state)
-		state.needs_semi = false
-		state.suppress_indent()
-		state.print("#endif  // #{@name}")
-		state.endline()
-	end
-	def pp_inline(state)
-		self.write_if(state)
-		@ifsuite.pp_inline(state)
-		if(@elsesuite != nil)
-			self.write_else(state)
-			@elsesuite.pp_inline(state)
-		end
-		self.write_endif(state)
-	end
-	def pp(state)
-		self.write_if(state)
-		if(@ifsuite.respond_to?(:pp_no_braces))
-			@ifsuite.pp_no_braces(state)
-		else
-			state.pp(@ifsuite)
-		end
-		if(@elsesuite != nil)
-			self.write_else(state)
-			if(@elsesuite.respond_to?(:pp_no_braces))
-				@elsesuite.pp_no_braces(state)
-			else
-				state.pp(@elsesuite)
-			end
-		end
-		self.write_endif(state)
-	end
-end
-class CPP::Using
-	def initialize(using)
-		@using = using
-	end
-	def pp(state)
-		state.print("using #{@using}")
-	end
-end
diff --git a/aos/build/queues/cpp_pretty_print/dep_file_pair.rb b/aos/build/queues/cpp_pretty_print/dep_file_pair.rb
deleted file mode 100644
index 02233d4..0000000
--- a/aos/build/queues/cpp_pretty_print/dep_file_pair.rb
+++ /dev/null
@@ -1,470 +0,0 @@
-class GroupElement
-	def add_group_dep(group_dep)
-		@group_dep = group_dep
-	end
-	def adjust_group(state,old_group)
-		if(@group_dep != old_group)
-			@group_dep.adjust_from(state,old_group)
-		end
-		return @group_dep
-	end
-end
-class DepMask < GroupElement
-	def initialize(elem)
-		@elem = elem
-		@deps = []
-	end
-	def add_dep(dep)
-		@deps << dep
-		self
-	end
-	def method_missing(method,*args,&blk)
-		@elem.send(method,*args,&blk)
-	end
-	alias_method :old_respond_to, :respond_to?
-	def respond_to?(method)
-		old_respond_to(method) || @elem.respond_to?(method)
-	end
-end
-
-class MemberElementHeader < GroupElement
-	def initialize(elem)
-		@elem = elem
-	end
-	def pp(state)
-		if(@elem.respond_to?(:pp_header_file))
-			@elem.pp_header_file(state)
-		else
-			state.pp(@elem)
-		end
-	end
-	def self.check(plan,elem)
-		plan.push(self.new(elem))
-	end
-end
-class MemberElementInline < GroupElement
-	def initialize(elem)
-		@elem = elem
-	end
-	def pp(state)
-		if(@elem.respond_to?(:pp_inline))
-			@elem.pp_inline(state)
-		else
-			state.pp(@elem)
-		end
-	end
-end
-class MemberElementCC < GroupElement
-	attr_accessor :pp_override
-	def initialize(elem)
-		@elem = elem
-	end
-	def pp(state)
-		return state.pp(@elem) if(@pp_override)
-		@elem.pp_cc_file(state)
-	end
-	def self.check(plan,elem)
-		plan.push(self.new(elem)) if(elem.respond_to?(:pp_cc_file))
-	end
-end
-class ImplicitName
-	attr_accessor :parent
-	def initialize(name,parent)
-		@name = name
-		@parent = parent
-	end
-	def close(state)
-		state.endline()
-		state.needs_semi = false
-		state.print("}  // namespace #{@name}\n")
-	end
-	def name()
-		if(@parent)
-			return @parent.name + "." + @name
-		else
-			return "." + @name
-		end
-	end
-	def open(state)
-		state.endline()
-		state.needs_semi = false
-		state.print("namespace #{@name} {\n")
-	end
-	def adjust_from(state,old_group)
-		close_grps = []
-		grp = old_group
-		while(grp)
-			close_grps << grp
-			grp = grp.parent
-		end
-		open_grps = []
-		grp = self
-		while(grp)
-			open_grps << grp
-			grp = grp.parent
-		end
-		while(open_grps[-1] == close_grps[-1] && close_grps[-1])
-			close_grps.pop()
-			open_grps.pop()
-		end
-		close_grps.each do |grp|
-			grp.close(state)
-		end
-		open_grps.reverse.each do |grp|
-			grp.open(state)
-		end
-	end
-	def adjust_to(state,new_group)
-		grp = self
-		while(grp)
-			grp.close(state)
-			grp = grp.parent
-		end
-	end
-end
-class GroupPlan < GroupElement
-	attr_accessor :implicit
-	def initialize(group_elem,members = [])
-		@group_elem = group_elem
-		@members = CPP::Suite.new(members)
-	end
-	def push(mem)
-		mem.add_group_dep(@implicit) if(@implicit)
-		@members << mem
-	end
-	def pp(state)
-		if(@group_elem)
-			@group_elem.open(state)
-		end
-		group = nil
-		@members.each do |member|
-			group = member.adjust_group(state,group)
-			#puts "at:#{group.name}" if(group.respond_to?(:name))
-			state.endline()
-			state.needs_semi = true
-			state.pp(member)
-			state.endline()
-		end
-		group.adjust_to(state,nil) if(group)
-		if(@group_elem)
-			@group_elem.close(state)
-		end
-	end
-end
-class CC_Mask
-	def initialize(elem)
-		@elem = elem
-	end
-	def plan_cc(plan)
-		elem = MemberElementCC.new(@elem)
-		elem.pp_override = true
-		plan.push(elem)
-	end
-	def plan_header(plan);
-	end
-end
-module Types
-	class TypeDef
-		def initialize(type,name)
-			@type = type
-			@name = name
-		end
-		def pp(state)
-			state.pp("typedef #{@type.name} #{@name}")
-		end
-	end
-	class Type
-		attr_accessor :name,:static,:dec,:space
-		def initialize(namespace,name)
-			@space = namespace
-			@name = name
-			@members = []
-			@protections = {}
-			@deps = []
-		end
-    def parent_class
-      @parent.split(' ')[1] if @parent
-    end
-		class ProtectionGroup
-			def initialize(name)
-				@name = name
-			end
-			def adjust_from(state,other)
-				state.indent -= 1
-				state.pp("#@name:")
-				state.endline
-				state.indent += 1
-			end
-			def adjust_to(state,other)
-				other.adjust_from(state,self) if other
-			end
-		end
-		ProtectionGroups = { :public => ProtectionGroup.new(:public),
-			:protected => ProtectionGroup.new(:protected),
-		 	:private => ProtectionGroup.new(:private)}
-		def set_parent(parent)
-			@parent = parent
-		end
-		def chop_method_prefix()
-			@space.chop_method_prefix + "#@name::"
-		end
-		def def_func(*args)
-			func = CPP::MemberFunc.new(self,*args)
-			@protections[func] = @protection
-			@members << func
-			return func
-		end
-		def add_cc_comment(*args)
-			args.each do |arg|
-				@members.push(CC_Mask.new(CPP::Comment.new(arg)))
-			end
-		end
-		def plan_cc(plan)
-			@members.each do |member|
-				if(member.respond_to?(:plan_cc))
-					member.plan_cc(plan)
-				elsif(member.respond_to?(:pp_cc_file))
-					plan.push(MemberElementCC.new(member))
-				end
-			end
-		end
-		def plan_header(plan)
-			group_plan = GroupPlan.new(self)
-			plan.push(group_plan)
-			@members.each do |member|
-				group_plan.implicit = ProtectionGroups[@protections[member]]
-				if(member.respond_to?(:plan_header))
-					member.plan_header(group_plan)
-				else
-					group_plan.push(MemberElementHeader.new(member))
-				end
-				#member.plan_cc(plan)
-			end
-		end
-		def open(state)
-			state.needs_semi = false
-			state.v_pad(2)
-			if(@static)
-				state.print("static ")
-			end
-			self.template_header(state) if(self.respond_to?(:template_header))
-			state.print("#{self.class.type_name} #{@name}")
-			self.template_spec_args(state) if(self.respond_to?(:template_spec_args))
-			if(@parent)
-				state.print(" : #{@parent} {\n")
-			else
-				state.print(" {\n")
-			end
-			state.indent += 2
-		end
-		def close(state)
-			state.indent -= 2
-			state.needs_semi = true
-			if(@dec)
-				state.print("\n} #{@dec}")
-			else
-				state.print("\n}")
-			end
-			state.v_pad(2)
-		end
-		def add_dep(other)
-			@deps << other
-			self
-		end
-	end
-	class Class < Type
-		def add_member(protection,member)
-			@protection = protection
-			@members.push(member)
-			@protections[member] = protection
-			return member
-		end
-		def add_struct(*args)
-			add_member(:public, Types::Struct.new(self,*args))
-		end
-		def public() ; @protection = :public ; end 
-		def protected() ; @protection = :protected ; end 
-		def private() ; @protection = :private ; end 
-		def self.type_name() ; "class" ; end
-	end
-	class PreprocessorIf < Type
-		def initialize(*args)
-			super(*args)
-		end
-		def add_member(member)
-			@members.push(member)
-			return member
-		end
-		def self.type_name() ; "#if" ; end
-		def open(state)
-			state.needs_semi = false
-			state.print("\n#if #{@name}")
-		end
-		def close(state)
-			state.needs_semi = false
-			state.print("\n#endif  // #{@name}")
-		end
-	end
-	class Struct < Type
-		attr_accessor :members
-		def add_member(member)
-			@members.push(member)
-			return member
-		end
-		def self.type_name() ; "struct" ; end
-	end
-	class TemplateClass < Class
-		def initialize(*args)
-			super(*args)
-			@t_args = CPP::Args.new()
-		end
-		def spec_args()
-			return @spec_args ||= CPP::Args.new()
-		end
-		def template_header(state)
-			if(@t_args.length > 0)
-				state.pp("template < ")
-				state.pp(@t_args)
-			else
-				state.pp("template < ")
-			end
-			state.pp(">\n")
-		end
-		def plan_cc(plan)
-
-		end
-		def plan_header(plan)
-			group_plan = GroupPlan.new(self)
-			plan.push(group_plan)
-			@members.each do |member|
-				group_plan.implicit = ProtectionGroups[@protections[member]]
-				if(member.respond_to?(:plan_header))
-					member.plan_header(group_plan)
-				else
-					group_plan.push(MemberElementInline.new(member))
-				end
-			end
-		end
-		def template_spec_args(state)
-			if(@spec_args)
-				state.pp("< ")
-				state.pp(@spec_args)
-				state.pp(">")
-			end
-		end
-	end
-end
-class DepFilePair
-	class NameSpace
-		def initialize(name,parent)
-			@name,@parent = name,parent
-			@members = []
-		end
-		def add_struct(*args)
-			add Types::Struct.new(self,*args)
-		end
-		def add_template(*args)
-			add Types::TemplateClass.new(self,*args)
-		end
-		def add_class(*args)
-			add Types::Class.new(self,*args)
-		end
-		def add_cc(arg)
-			@members.push(CC_Mask.new(arg))
-		end
-		def chop_method_prefix()
-			""
-		end
-		def class_comment(*args)
-			add CPP::Comment.new(*args)
-		end
-		def var_dec_comment(*args)
-			add CPP::Comment.new(*args)
-		end
-		def add_var_dec(arg)
-			add DepMask.new(arg)
-		end
-		def plan_cc(plan)
-			plan.implicit = ImplicitName.new(@name,plan.implicit)
-			@members.each do |member|
-				if(member.respond_to?(:plan_cc))
-					member.plan_cc(plan)
-				else
-					MemberElementCC.check(plan,member)
-				end
-			end
-			plan.implicit = plan.implicit.parent
-		end
-		def plan_header(plan)
-			plan.implicit = ImplicitName.new(@name,plan.implicit)
-			@members.each do |member|
-				if(member.respond_to?(:plan_header))
-					member.plan_header(plan)
-				else
-					MemberElementHeader.check(plan,member)
-				end
-			end
-			plan.implicit = plan.implicit.parent
-		end
-		def add val
-			@members << val
-			val
-		end
-	end
-	def initialize(rel_path)
-		@rel_path = rel_path
-		@cc_includes = []
-		@header_includes = []
-		@spaces = []
-		@cc_usings = []
-		@cache = {}
-	end
-	def add_cc_include(inc_path)
-		@cc_includes << CPP::Include.new(inc_path)
-	end
-	def add_cc_using(using)
-		@cc_usings << CPP::Using.new(using)
-	end
-	def add_header_include(inc_path)
-		@header_includes << CPP::Include.new(inc_path)
-	end
-	def add_namespace(name,parent)
-		space = NameSpace.new(name,parent)
-		if(parent != self)
-			parent.add(space)
-		else
-			@spaces.push(space)
-		end
-		return space
-	end
-	def set(type,cached)
-		@cache[type] = cached
-	end
-	def get(type)
-		cached = @cache[type]
-		return cached if cached
-		cached = type.create(self)
-		cached_check = @cache[type]
-		return cached_check if cached_check
-		set(type,cached)
-		return cached
-	end
-	def write_cc_file(cpp_base,cc_file)
-		plan_cc = GroupPlan.new(nil,elems_cc = [])
-		@spaces.each do |space|
-			space.plan_cc(plan_cc)
-		end
-		suite = CPP::Suite.new(@cc_includes + @cc_usings + [plan_cc])
-		CPP.pretty_print(suite,cc_file)
-	end
-	def write_header_file(cpp_base,header_file)
-		plan_header = GroupPlan.new(nil,elems_cc = [])
-		@spaces.each do |space|
-			space.plan_header(plan_header)
-		end
-		suite = CPP::Suite.new(@header_includes + [plan_header])
-		include_guard = CPP::IncludeGuard.new(suite)
-		include_guard.name = @rel_path.upcase.gsub(/[\.\/\\]/,"_") + "_H_"
-		CPP.pretty_print(include_guard,header_file)
-	end
-end
diff --git a/aos/build/queues/cpp_pretty_print/file_pair_types.rb b/aos/build/queues/cpp_pretty_print/file_pair_types.rb
deleted file mode 100644
index 25ce4fe..0000000
--- a/aos/build/queues/cpp_pretty_print/file_pair_types.rb
+++ /dev/null
@@ -1,204 +0,0 @@
-module CPP
-end
-class CPP::TypePair
-	attr_accessor :name,:static,:dec
-	def initialize(namespace,name)
-		@space,@name = namespace,name
-		@members = []
-		@protections = {}
-		@dont_sort = {}
-	end
-	ProtectionTable = { :public => 0,:protected => 1,:private => 2 }
-	def comp(m1,m2)
-		if(!(@dont_sort[m1] || @dont_sort[m2]))
-			if(@protections[m1] && @protections[m2])
-				comp = ProtectionTable[@protections[m1]] <=> ProtectionTable[@protections[m2]]
-				return comp if(comp != 0)
-			end
-			comp = TypeTable[m1.class] <=> TypeTable[m2.class]
-			return comp if(comp != 0)
-		end
-		return @stable[m1] <=> @stable[m2]
-	end
-	def set_parent(parent)
-		@parent = parent
-	end
-	def add_class(name)
-		return add_member(:public,CPP::ClassPair.new(self,name))
-	end
-	def add_struct(name)
-		return add_member(:public,CPP::StructPair.new(self,name))
-	end
-	def add_cc_comment(*strs)
-		strs.each do |str|
-			@members << comment = CPP::CCMemberWrapper.new(CPP::Comment.new(str))
-			@protections[comment] = @protection
-		end
-		#@dont_sort[comment] = true
-	end
-	def method_prefix()
-		@space.method_prefix + "#@name::"
-	end
-	def chop_method_prefix()
-		@space.chop_method_prefix + "#@name::"
-	end
-	def pp(state)
-		@stable = {}
-		@members.each_with_index { |mem,i| @stable[mem] = i }
-		members = @members.sort { |m1,m2| comp(m1,m2) }
-
-		state.needs_semi = false
-		state.v_pad(2)
-		if(@static)
-			state.print("static ")
-		end
-		if(@parent)
-			state.print("#{self.class.type_name} #{@name} : #{@parent} {\n")
-		else
-			state.print("#{self.class.type_name} #{@name} {\n")
-		end 
-		state.indent += 2
-		protection = nil 
-		members.each do |member|
-			if(protection != @protections[member])
-				state.indent -= 1
-				state.needs_semi = false
-				state.v_pad(2) if(protection)
-				protection = @protections[member]
-				state.print("#{protection}:\n")
-				state.indent += 1
-				state.endline()
-			end
-			state.endline()
-			state.needs_semi = true
-			if(member.respond_to?(:pp_header_file))
-				member.pp_header_file(state)
-			else
-				state.pp(member)
-			end
-			state.endline()
-		end 
-		state.indent -= 2
-		state.needs_semi = true
-		if(@dec)
-		state.print("\n} #{@dec}")
-		else
-		state.print("\n}")
-		end
-		state.v_pad(2)
-	end
-	def pp_header_file(state)
-		pp(state)
-	end
-	def pp_cc_file(state)
-		@members.each do |member|
-			state.needs_semi = true
-			member.pp_cc_file(state) if(member.respond_to?(:pp_cc_file))
-			state.endline()
-		end
-	end
-	def def_func(*args)
-		func = CPP::MemberFunc.new(self,*args)
-		@protections[func] = @protection
-		@members << func
-		return func
-	end
-end
-class CPP::CCMemberWrapper
-	def initialize(member)
-		@member = member
-	end
-	def pp_header_file(state) ; end
-	def pp_cc_file(state)
-		state.pp(@member)
-	end
-end
-class CPP::ClassPair < CPP::TypePair
-	attr_accessor :name
-	def initialize(namespace,name)
-		super(namespace,name)
-		@protection = :public #default to public
-	end
-	def add_member(protection,member)
-		@protection = protection
-		@members << member
-		@protections[member] = protection
-		return member
-	end
-	def public() ; @protection = :public ; end
-	def protected() ; @protection = :protected ; end
-	def private() ; @protection = :private ; end
-	def self.type_name() ; "class" ; end
-end
-class CPP::StructPair < CPP::TypePair
-	def self.type_name() ; "struct" ; end
-	def add_member(member)
-		@members << member
-		return member
-	end
-end
-CPP::TypePair::TypeTable = { CPP::StructPair => 0, CPP::ClassPair => 1,CPP::Constructor => 2 }
-CPP::TypePair::TypeTable.default = 3
-class CPP::TemplateClass < CPP::ClassPair
-	def initialize(namespace,name)
-		super(namespace,name)
-		@t_args = CPP::Args.new()
-	end
-	def spec_args()
-		return @spec_args ||= CPP::Args.new()
-	end
-	def pp(state)
-		@stable = {}
-		@members.each_with_index { |mem,i| @stable[mem] = i }
-		members = @members.sort { |m1,m2| comp(m1,m2) }
-		state.needs_semi = false
-		state.v_pad(2)
-		if(@t_args.length > 0)
-			state.pp("template < ")
-			state.pp(@t_args)
-		else
-			state.pp("template < ")
-		end
-		state.pp(">\n")
-		state.pp("class #@name")
-		if(@spec_args)
-			state.pp("< ")
-			state.pp(@spec_args)
-			state.pp("> {")
-		else
-			state.pp(" {")
-		end
-		state.endline()
-		state.indent += 2
-		protection = nil 
-		members.each do |member|
-			if(protection != @protections[member])
-				state.indent -= 1
-				state.needs_semi = false
-				state.v_pad(2) if(protection)
-				protection = @protections[member]
-				state.print("#{protection}:\n")
-				state.indent += 1
-				state.endline()
-			end
-			state.endline()
-			state.needs_semi = true
-			if(member.respond_to?(:pp_inline))
-				member.pp_inline(state)
-			else
-				state.pp(member)
-			end
-			state.endline()
-		end 
-		state.indent -= 2
-		state.needs_semi = true
-		if(@dec)
-			state.print("\n} #{@dec}")
-		else
-			state.print("\n}")
-		end
-		state.v_pad(2)
-	end
-	def pp_cc_file(state); end
-end
-
diff --git a/aos/build/queues/cpp_pretty_print/standard_types.rb b/aos/build/queues/cpp_pretty_print/standard_types.rb
deleted file mode 100644
index 997059a..0000000
--- a/aos/build/queues/cpp_pretty_print/standard_types.rb
+++ /dev/null
@@ -1,365 +0,0 @@
-module CPP
-	class Class
-
-	end
-	class Funct
-		attr_accessor :retval,:name,:args,:suite
-		def initialize(retval = nil,name = nil,args = Args.new(),suite = Suite.new())
-			@retval,@name,@args,@suite = retval,name,args,suite
-		end
-		def pp(state)
-			state.pp(@retval)
-			state.print(" ")
-			state.pp(@name)
-			state.print("(")
-			state.pp(@args)
-			state.print(")")
-			state.pp(@suite)
-		end
-	end
-	class If
-		attr_accessor :cond,:suite,:else_suite
-		def initialize(cond = nil,suite = Suite.new(),else_suite = nil)
-			@cond,@suite,@else_suite = cond,suite,else_suite
-		end
-		def pp(state)
-			state.print("if (")
-			state.pp(@cond)
-			state.print(") ")
-			state.needs_semi = false
-			state.pp(@suite)
-			if(@else_suite)
-				state.print(" else ")
-				state.pp(@else_suite)
-			end
-		end
-		def else_suite()
-			return(@else_suite ||= Suite.new())
-		end
-	end
-	class For
-		attr_accessor :init,:cond,:update,:suite
-		def initialize(init = nil,cond = nil,update = nil,suite = Suite.new())
-			@init,@cond,@update,@suite = init,cond,update,suite
-		end
-		def pp(state)
-			state.print("for (")
-			Args.new([@init,@cond,@update]).pp(state,";")
-			state.print(") ")
-			state.needs_semi = false
-			state.pp(@suite)
-		end
-	end
-	class Args < Array
-		attr_accessor :dont_wrap
-		def pp(state,sep = ",")
-			pos = start = state.col
-			self.each_with_index do |arg,i|
-				#puts "#{state.col - start} , #{start}"
-				state.print(sep) if(i != 0)
-				if(pos > 80)
-					state.wrap(state.indent + 4)
-					pos = start = state.col
-				elsif(state.col * 2 - pos > 80 && !@dont_wrap)
-					state.wrap(start)
-					start = pos
-				else
-					state.print(" ") if(i != 0)
-					pos = state.col
-				end
-				state.pp(arg)
-			end
-		end
-	end
-	class Suite < Array
-		def pp(state)
-			state.print("{")
-			state.>>
-			state.needs_semi = false
-			self.pp_no_braces(state)
-			state.<<
-			state.print("}")
-		end
-		def pp_no_braces(state)
-			self.each do |arg,i|
-				state.endline()
-				state.needs_semi = true
-				state.pp(arg)
-				state.endline()
-			end
-		end
-		def pp_one_line(state)
-			if(self.length == 1)
-				state.needs_semi = true
-				state.print("{ ")
-				state.pp(self[0])
-				state.print(";") if(state.needs_semi)
-				state.needs_semi = false
-				state.print(" }")
-			else
-				self.pp(state)
-			end
-		end
-	end
-	class FuncCall
-		attr_accessor :name,:args
-		def initialize(name = nil,args = Args.new())
-			@name,@args = name,args
-		end
-		def self.build(name,*args)
-			self.new(name,Args.new(args))
-		end
-		def pp(state)
-			state.pp(@name)
-			state.print("(")
-			state.pp(@args)
-			state.print(")")
-		end
-	end
-	class BIT_OR
-		attr_accessor :val1,:val2
-		def initialize(val1,val2)
-			@val1,@val2 = val1,val2
-		end
-		def pp(state)
-			state.pp(@val1)
-			state.print(" | ")
-			state.pp(@val2)
-		end
-	end
-	class LT
-		attr_accessor :val1,:val2
-		def initialize(val1,val2)
-			@val1,@val2 = val1,val2
-		end
-		def pp(state)
-			state.pp(@val1)
-			state.print(" < ")
-			state.pp(@val2)
-		end
-	end
-	class Div
-		attr_accessor :val1,:val2
-		def initialize(val1,val2)
-			@val1,@val2 = val1,val2
-		end
-		def pp(state)
-			state.pp(@val1)
-			state.print(" / ")
-			state.pp(@val2)
-		end
-	end
-	class Add
-		attr_accessor :val1,:val2
-		def initialize(val1,val2)
-			@val1,@val2 = val1,val2
-		end
-		def pp(state)
-			state.pp(@val1)
-			state.print(" + ")
-			state.pp(@val2)
-		end
-	end
-	class Member
-		attr_accessor :obj,:name
-		def initialize(obj,name)
-			@obj,@name = obj,name
-		end
-		def pp(state)
-			state.pp(@obj)
-			state.print(".")
-			state.pp(@name)
-		end
-	end
-	class PointerMember
-		attr_accessor :obj,:name
-		def initialize(obj,name)
-			@obj,@name = obj,name
-		end
-		def pp(state)
-			state.pp(@obj)
-			state.print("->")
-			state.pp(@name)
-		end
-	end
-	class Minus
-		attr_accessor :val
-		def initialize(val)
-			@val = val
-		end
-		def pp(state)
-			state.print("-")
-			state.pp(@val)
-		end
-	end
-	class Not
-		attr_accessor :val
-		def initialize(val)
-			@val = val
-		end
-		def pp(state)
-			state.print("!")
-			state.pp(@val)
-		end
-	end
-	class Address
-		attr_accessor :val
-		def initialize(val)
-			@val = val
-		end
-		def pp(state)
-			state.print("&")
-			state.pp(@val)
-		end
-	end
-	class Paran
-		attr_accessor :val
-		def initialize(val)
-			@val = val
-		end
-		def pp(state)
-			state.print("(")
-			state.pp(@val)
-			state.print(")")
-		end
-	end
-	class Assign
-		attr_accessor :lval,:rval
-		def initialize(lval = nil,rval = Args.new())
-			@lval,@rval = lval,rval
-		end
-		def pp(state)
-			state.pp(@lval)
-			state.print(" = ")
-			state.pp(@rval)
-		end
-	end
-	class PointerDeref
-		attr_accessor :val
-		def initialize(val)
-			@val = val
-		end
-		def pp(state)
-			state.print("*")
-			state.pp(@val)
-		end
-	end
-	class Cast
-		attr_accessor :to,:val
-		def initialize(to,val)
-			@to,@val = to,val
-		end
-		def pp(state)
-			state.print("(")
-			state.pp(@to)
-			state.print(")")
-			state.pp(@val)
-		end
-	end
-	class VarDec
-		attr_accessor :type,:name
-		def initialize(type = nil,name = nil)
-			@type,@name = type,name
-		end
-		def pp(state)
-			state.pp(@type)
-			state.print(" ")
-			state.pp(@name)
-		end
-	end
-	class Return
-		attr_accessor :val
-		def initialize(val = nil)
-			@val = val
-		end
-		def pp(state)
-			state.print("return ")
-			state.pp(@val)
-		end
-	end
-	class TraversalState
-		attr_accessor :needs_semi,:indent,:col
-		def initialize(file)
-			@file = file
-			@indent = 0
-			@not_indented = true
-			@just_endlined = true
-			@hold_points = []
-			@col = 0
-		end
-		def set_hold_point()
-			@hold_points.push(@col)
-		end
-		def wrap(col)
-			@file.print("\n")
-			@file.print(" " * col)
-			@col = col
-		end
-		def suppress_indent()
-			@not_indented = false
-		end
-		def <<()
-			@indent -= 2
-		end
-		def >>()
-			@indent += 2
-		end
-		def pp(ast)
-			return ast.pp(self) if(ast.respond_to?(:pp) &&
-			                       ast.class != String &&
-			                       ast.class != Integer)
-			self.print(ast)
-		end
-		def print(chars)
-			return print_no_split(chars) if(!chars.respond_to?(:split))
-			chars.split(/\n/,-1).each_with_index do |line,i|
-				endline() if(i != 0)
-				print_no_split(line) if(line && line.length > 0)
-			end
-		end
-		def print_no_split(chars)
-			if(@not_indented)
-				@file.print(" "*@indent)
-				@col += @indent
-				@not_indented = false
-			end
-			if(chars)
-				chars = chars.to_s
-				if(chars.length > 0)
-					@col += chars.length
-					@file.print(chars)
-					@just_endlined = false
-					@v_pad = 0
-				end
-			end
-		end
-		def endline()
-			return if(@just_endlined)
-			@file.print(";") if(@needs_semi)
-			@needs_semi = false
-			@file.print("\n")
-			@not_indented = true
-			@just_endlined = true
-			@hold_points.clear()
-			@v_pad += 1
-			@col = 0
-		end
-		def v_pad(n)
-			while(@v_pad < n)
-				force_endline()
-			end
-		end
-		def force_endline()
-			@just_endlined = false
-			endline()
-		end
-	end
-	def self.pretty_print(ast,file)
-		state = TraversalState.new(file)
-		if(ast.respond_to?(:pp_no_braces))
-			ast.pp_no_braces(state) 
-		else
-			state.pp(ast)
-		end
-	end
-end
diff --git a/aos/build/queues/load.rb b/aos/build/queues/load.rb
deleted file mode 100644
index 50d59f8..0000000
--- a/aos/build/queues/load.rb
+++ /dev/null
@@ -1,17 +0,0 @@
-$LOAD_PATH.unshift(".")
-
-["tokenizer.rb","q_file.rb","queue_group.rb","queue.rb","namespaces.rb",
- "interface.rb","errors.rb", "q_struct.rb"].each do |name|
-  require_relative "objects/" + name
-end
-["standard_types.rb","auto_gen.rb","file_pair_types.rb",
-  "dep_file_pair.rb"].each do |name|
-	require_relative "cpp_pretty_print/" + name
-end
-["q_file.rb","message_dec.rb","queue_dec.rb", "q_struct.rb"].each do |name|
-	require_relative "output/" + name
-end
-require_relative "write_iff_changed.rb"
-
-require "fileutils"
-require "pathname"
diff --git a/aos/build/queues/objects/errors.rb b/aos/build/queues/objects/errors.rb
deleted file mode 100644
index d776a22..0000000
--- a/aos/build/queues/objects/errors.rb
+++ /dev/null
@@ -1,43 +0,0 @@
-class QError < Exception
-	def initialize(msg)
-		super()
-		@msg = msg
-		@qstacktrace = []
-	end
-	def self.set_name(name)
-		@pretty_name = name
-	end
-	def self.pretty_name()
-		@pretty_name
-	end
-	def to_s
-		msg = "Error:(#{self.class.pretty_name})\n\t"
-		msg += @msg
-		msg += "\n" if(msg[-1] != "\n")
-		@qstacktrace.each do |part|
-			part = part.q_stack_name if(part.respond_to?(:q_stack_name))
-			msg += "\tfrom: #{part}\n"
-		end
-		return msg
-	end
-	set_name("Base Level Exception.")
-	attr_accessor :qstacktrace
-end
-class QSyntaxError < QError
-	def initialize(msg)
-		super(msg)
-	end
-	set_name("Syntax Error")
-end
-class QNamespaceCollision < QError
-	def initialize(msg)
-		super(msg)
-	end
-	set_name("Namespace Collision")
-end
-class QImportNotFoundError < QError
-	def initialize(msg)
-		super(msg)
-	end
-	set_name("Couldn't Find Target of Import Statement")
-end
diff --git a/aos/build/queues/objects/interface.rb b/aos/build/queues/objects/interface.rb
deleted file mode 100644
index 52332b6..0000000
--- a/aos/build/queues/objects/interface.rb
+++ /dev/null
@@ -1,69 +0,0 @@
-class MessageElementReq
-	def initialize(type,name)
-		@type = type
-		@name = name
-	end
-	def self.parse(tokens)
-		type = tokens.expect(:tWord).data
-		name = tokens.expect(:tWord).data
-		tokens.expect(:tSemi)
-		return self.new(type,name)
-	end 
-end 
-class QueueReq
-	def initialize(name,type = nil)
-		@name = name
-		@type = type
-	end
-	def self.parse(tokens)
-		type_or_name = tokens.expect(:tWord).data
-		if(tokens.peak == :tSemi)
-			tokens.expect(:tSemi)
-			return self.new(type_or_name)
-		else
-			name = tokens.expect(:tWord).data
-			tokens.expect(:tSemi)
-			return self.new(name,type_or_name)
-		end
-	end
-end
-class InterfaceStmt < QStmt
-	def initialize(name,elements)
-		@name = name
-		@elements = elements
-	end
-	def q_eval(locals)
-
-	end
-	def self.check_type(tokens,new_type,old_type)
-		return new_type if(old_type == nil)
-		if(new_type != old_type)
-			tokens.qError(<<ERROR_MSG)
-error: intermixing queue definitions (a queue_group feature)
-	and type definitions (a message_group feature)
-	this results in an undefined type value.
-	Wot. Wot.
-ERROR_MSG
-		end
-		return old_type
-	end
-	def self.parse(tokens)
-		name = tokens.expect(:tWord).data
-		values = []
-		type = nil
-		tokens.expect(:tOpenB)
-		while(tokens.peak != :tCloseB)
-			if(tokens.peak.data == "queue")
-				tokens.expect(:tWord)
-				values << QueueReq.parse(tokens)
-				type = check_type(tokens,:queue_group,type)
-			else
-				values << MessageElementReq.parse(tokens)
-				type = check_type(tokens,:message_group,type)
-			end
-		end 
-		tokens.expect(:tCloseB)
-		tokens.expect(:tSemi)
-		self.new(name,values)
-	end
-end
diff --git a/aos/build/queues/objects/namespaces.rb b/aos/build/queues/objects/namespaces.rb
deleted file mode 100644
index ea3aa80..0000000
--- a/aos/build/queues/objects/namespaces.rb
+++ /dev/null
@@ -1,211 +0,0 @@
-class LocalSituation
-	attr_accessor :globals,:local
-	def initialize(globals)
-		@globals = globals
-		@local = nil
-	end
-	def package=(qualified)
-		if(@local)
-			raise QSyntaxError.new(<<ERROR_MSG)
-You are redefining the package path.
- Stuff might break if you do that.
- Other options include: using another header file, and just using the same namespace.
- If you are confident that you need this you can remove this check at
- 	#{__FILE__}:#{__LINE__}.
- Or file a feature request.
- But that would be weird...
- Wot. Wot.
-ERROR_MSG
-		end
-		@local = @globals.space
-		qualified.names.each do |name|
-			@local = @local.get_make(name)
-		end
-	end
-	def register(value)
-		if(!@local)
-			raise QError.new(<<ERROR_MSG)
-There is no package path defined, This is a big problem because
- we are kindof expecting you to have a package path...
- use a :
-    package my_super.cool.project;
- statement to remedy this situation. (or file a feature request)
- Wot. Wot.
-ERROR_MSG
-		end
-		@local[value.name] = value
-		value.parent = @local if(value.respond_to?(:parent=))
-		value.loc = @local
-	end
-	def bind(bind_to)
-		return BoundSituation.new(self,bind_to)
-	end
-end
-class BoundSituation < LocalSituation
-	def initialize(locals,bind_to)
-		@globals = locals.globals
-		@local = bind_to
-	end
-end
-class NameSpace
-	attr_accessor :parent,:name
-	def initialize(name = nil,parent = nil)
-		@name = name
-		@parent = parent
-		@spaces = {}
-	end
-	def []=(key,val)
-		if(old_val = @spaces[key])
-			old_val = old_val.created_by if(old_val.respond_to?(:created_by) && old_val.created_by)
-			if(old_val.respond_to?(:q_stack_name))
-				old_val = old_val.q_stack_name
-			else
-				old_val = "eh, it is a #{old_val.class} thats all I know..."
-			end
-			raise QNamespaceCollision.new(<<ERROR_MSG)
-Woah! The name #{queue_name(key).inspect} is already taken by some chap at #{old_val}.
-\tFind somewhere else to peddle your wares.
-\tWot. Wot.
-ERROR_MSG
-		end
-		@spaces[key] = val
-	end
-	def to_cpp_id(name)
-		txt = @name + "::" + name
-		return @parent.to_cpp_id(txt) if(@parent && parent.name)
-		return "::" + txt
-	end
-	def queue_name(queue)
-		get_name() + "." + queue
-	end
-	def [](key)
-		#puts "getting #{get_name}.#{key}"
-		@spaces[key]
-	end
-	def get_make(name)
-		@spaces[name] ||= self.class.new(name,self)
-	end
-	def get_name()
-		if(@parent)
-			return "#{@parent.get_name}.#{@name}"
-		else
-			return "#{@name}"
-		end
-	end
-	def create(cpp_tree)
-		if(@parent && @parent.name)
-			parent = cpp_tree.get(@parent)
-		else
-			parent = cpp_tree
-		end
-		return cpp_tree.add_namespace(@name,parent)
-	end
-	def to_s()
-		"<NameSpace: #{get_name()}>"
-	end
-	def inspect()
-		"<NameSpace: #{get_name()}>"
-	end
-	def root()
-		return self if(@parent == nil)
-		return @parent.root
-	end
-end
-class Globals
-	attr_accessor :space
-	def initialize()
-		@space = NameSpace.new()
-		@space.get_make("aos")
-		@include_paths = []
-	end
-	def paths()
-		@include_paths
-	end
-	def add_path(path)
-		@include_paths << path
-	end
-	def find_file(filename)
-		@include_paths.each do |path_name|
-			new_path = File.expand_path(path_name) + "/" + filename
-			if(File.exists?(new_path))
-				return new_path 
-			end
-		end
-		raise QImportNotFoundError.new(<<ERROR_MSG)
-Problem Loading:#{filename.inspect} I looked in:
-\t#{(@include_paths.collect {|name| name.inspect}).join("\n\t")}
-\tbut alas, it was nowhere to be found.
-\tIt is popular to include the top of the repository as the include path start, 
-\tand then reference off of that. 
-\tI would suggest doing that and then trying to build again.
-\tWot. Wot.
-ERROR_MSG
-	end
-end
-class QualifiedName
-	attr_accessor :names,:off_root
-	def initialize(names,off_root = false)
-		@names = names
-		@off_root = off_root
-	end
-	def test_lookup(namespace)
-		@names.each do |name|
-			return nil if(!namespace.respond_to?(:[]))
-			namespace = namespace[name]
-			return nil if(!namespace)
-		end
-		return namespace
-	end
-	def is_simple?()
-		return !@off_root && @names.length == 1
-	end
-	def to_simple()
-		return @names[-1]
-	end
-	def to_s()
-		if(@off_root)
-			return ".#{@names.join(".")}"
-		else
-			return @names.join(".")
-		end
-	end
-	def lookup(locals)
-		if(@off_root)
-			local = locals.globals.space
-		else
-			local = locals.local
-		end
-		target = nil
-		while(!target && local)
-			target = test_lookup(local)
-			local = local.parent
-		end
-		return target if(target)
-		if(@off_root)
-			raise QError.new(<<ERROR_MSG)
-I was looking for .#{@names.join(".")}, but alas, it was not under
-\tthe root namespace.
-\tI'm really sorry old chap.
-\tWot. Wot.
-ERROR_MSG
-		else
-			raise QError.new(<<ERROR_MSG)
-I was looking for #{@names.join(".")}, but alas, I could not find
-\tit in #{locals.local.get_name} or any parent namespaces.
-\tI'm really sorry old chap.
-\tWot. Wot.
-ERROR_MSG
-		end
-	end
-	def self.parse(tokens)
-		names = []
-		off_root = (tokens.peak == :tDot)
-		tokens.next if(off_root)
-		names << tokens.expect(:tWord).data
-		while(tokens.peak == :tDot)
-			tokens.next
-			names << tokens.expect(:tWord).data
-		end
-		return self.new(names,off_root)
-	end
-end
diff --git a/aos/build/queues/objects/q_file.rb b/aos/build/queues/objects/q_file.rb
deleted file mode 100644
index f73b638..0000000
--- a/aos/build/queues/objects/q_file.rb
+++ /dev/null
@@ -1,150 +0,0 @@
-class QStmt
-	def set_line(val)
-		@file_line = val
-		return self
-	end
-	def q_stack_name()
-		@file_line
-	end
-	def self.method_added(name)
-		@wrapped ||= {}
-		return if(name != :q_eval && name != :q_eval_extern)
-		return if(@wrapped[name])
-		@wrapped[name] = true
-		method = self.instance_method(name)
-		define_method(name) do |*args,&blk|
-			begin 
-				method.bind(self).call(*args,&blk)
-			rescue QError => e
-				e.qstacktrace << self
-				raise e
-			end 
-		end 
-	end 
-
-end
-class ImportStmt < QStmt
-	def initialize(filename)
-		@filename = filename
-	end
-	def q_eval(locals)
-		filename = locals.globals.find_file(@filename)
-		#puts "importing #{filename.inspect}"
-		q_file = QFile.parse(filename)
-		q_output = q_file.q_eval_extern(locals.globals)
-		q_output.extern = true
-		return Target::QInclude.new(@filename + ".h")
-	end
-	def self.parse(tokens)
-		line = tokens.pos
-		to_import = (tokens.expect(:tString) do |token|
-			<<ERROR_MSG
-I found a #{token.humanize} at #{token.pos}.
-\tI was really looking for a "filename" for this import statement.
-\tSomething like: import "super_cool_file";
-\tWot.Wot
-ERROR_MSG
-		end).data
-		tokens.expect(:tSemi) do |token|
-			<<ERROR_MSG
-I found a #{token.humanize} at #{token.pos}.
-\tI was really looking for a ";" to finish off this import statement
-\tat line #{line};
-\tSomething like: import #{to_import.inspect};
-\tWot.Wot                #{" "*to_import.inspect.length}^
-ERROR_MSG
-		end
-		return self.new(to_import).set_line(line)
-	end
-end
-class PackageStmt < QStmt
-	def initialize(name)
-		@name = name
-	end
-	def q_eval(locals)
-		locals.package = @name
-		return nil
-	end
-	def self.parse(tokens)
-		line = tokens.pos
-		qualified_name = QualifiedName.parse(tokens)
-		tokens.expect(:tSemi)
-		return self.new(qualified_name).set_line(line)
-	end
-end
-class QFile
-	attr_accessor :namespace
-	def initialize(filename,suite)
-		@filename,@suite = filename,suite
-	end
-	def q_eval(globals = Globals.new())
-		local_pos = LocalSituation.new(globals)
-		q_file = Target::QFile.new()
-		@suite.each do |name|
-			val = name.q_eval(local_pos)
-			if(val)
-				if(val.respond_to?(:create))
-					q_file.add_type(val)
-				end
-			end
-		end
-		@namespace = local_pos.local
-		return q_file
-	end
-	def q_eval_extern(globals)
-		local_pos = LocalSituation.new(globals)
-		q_file = Target::QFile.new()
-		@suite.each do |name|
-			if(name.respond_to?(:q_eval_extern))
-				val = name.q_eval_extern(local_pos)
-			else
-				val = name.q_eval(local_pos)
-			end
-			if(val)
-				if(val.respond_to?(:create))
-					q_file.add_type(val)
-				end
-			end
-		end
-		return q_file
-	end
-	def self.parse(filename)
-		tokens = Tokenizer.new(filename)
-		suite = []
-		while(tokens.peak != :tEnd)
-			token = tokens.expect(:tWord) do |token| #symbol
-			<<ERROR_MSG
-I found a #{token.humanize} at #{token.pos}.
-\tI was really looking for a "package", "import", "queue_group",
-\t"message", or "queue" statement to get things moving.
-\tSomething like: import "super_cool_file";
-\tWot.Wot
-ERROR_MSG
-			end
-			case token.data
-			when "package"
-				suite << PackageStmt.parse(tokens)
-			when "import"
-				suite << ImportStmt.parse(tokens)
-			when "queue_group"
-				suite << QueueGroupStmt.parse(tokens)
-			when "message"
-				suite << MessageStmt.parse(tokens)
-			when "queue"
-				suite << QueueStmt.parse(tokens)
-			when "interface"
-				suite << InterfaceStmt.parse(tokens)
-			when "struct"
-				suite << StructStmt.parse(tokens)
-			else
-				tokens.qError(<<ERROR_MSG)
-expected a "package","import","queue","struct","queue_group", or "message" statement rather
-	than a #{token.data.inspect}, (whatever that is?)
-	oh! no! a feature request!?
-	Wot. Wot.
-ERROR_MSG
-			end
-		end
-		return self.new(filename,suite)
-	end
-end
diff --git a/aos/build/queues/objects/q_struct.rb b/aos/build/queues/objects/q_struct.rb
deleted file mode 100644
index cd47fe6..0000000
--- a/aos/build/queues/objects/q_struct.rb
+++ /dev/null
@@ -1,37 +0,0 @@
-
-class StructStmt 
-	def initialize(name,suite)
-		@name = name
-		@suite = suite
-	end
-	def q_eval(locals)
-		group = Target::StructDec.new(@name)
-		locals.register(group)
-		@suite.each do |stmt|
-			stmt.q_eval(locals.bind(group))
-		end 
-		return group
-	end
-	def self.parse(tokens)
-		name = tokens.expect(:tWord).data
-		values = []
-		tokens.expect(:tOpenB)
-		while(tokens.peak != :tCloseB)
-			values << MessageElementStmt.parse(tokens)
-		end
-		names = {}
-		values.each do |val|
-			if(names[val.name])
-				raise QSyntaxError.new(<<ERROR_MSG)
-Hey! duplicate name #{val.name.inspect} in your message declaration statement (message #{name}).
-\tI found them at: #{names[val.name].q_stack_name()} and #{val.q_stack_name()}.
-\tWot. Wot.
-ERROR_MSG
-			end
-			names[val.name] = val
-		end
-		tokens.expect(:tCloseB)
-		tokens.expect(:tSemi)
-		self.new(name,values)
-	end
-end
diff --git a/aos/build/queues/objects/queue.rb b/aos/build/queues/objects/queue.rb
deleted file mode 100644
index 7841411..0000000
--- a/aos/build/queues/objects/queue.rb
+++ /dev/null
@@ -1,173 +0,0 @@
-class MessageElementStmt < QStmt
-	attr_accessor :name
-	def initialize(type_name,name,length = nil) #lengths are for arrays
-		@type_name = type_name
-		@type = type_name.to_s
-    @type = '::aos::monotonic_clock::time_point' if @type == 'Time'
-		@name = name
-		@length = length
-	end
-	CommonMistakes = {"short" => "int16_t","int" => "int32_t","long" => "int64_t","time" => "Time"}
-	def check_type_error(locals)
-		if(!(Sizes[@type] || (@length != nil && @type == "char")) )
-			if(correction = CommonMistakes[@type])
-				raise QError.new(<<ERROR_MSG)
-Hey! you have a \"#{@type}\" in your message statement.
-\tplease use #{correction} instead. Your type is not supported because we
-\twant to guarantee that the sizes of the messages stay the same across platforms.
-\tWot. Wot.
-ERROR_MSG
-			elsif(@type == "char")
-				raise QError.new(<<ERROR_MSG)
-Hey! you have a \"#{@type}\" in your message statement.
-\tyou need your declaration to be a char array like: char[10].
-\tor, please use int8_t or uint8_t.
-\tWot. Wot.
-ERROR_MSG
-			else
-				@is_struct_type = true
-				return if(lookup_type(locals))
-				raise QError.new(<<ERROR_MSG)
-Hey! you have a \"#{@type}\" in your message statement.
-\tThat is not in the list of supported types.
-\there is the list of supported types:
-\tint{8,16,32,64}_t,uint{8,16,32,64}_t,bool,float,double
-\tWot. Wot.
-ERROR_MSG
-			end
-		end
-	end
-
-	PrintFormat = {"bool" => "%c",
-                       "float" => "%f",
-                       "char" => "%c",
-                       "double" => "%f",
-                       "uint8_t" => "%\" PRIu8 \"",
-                       "uint16_t" => "%\" PRIu16 \"",
-                       "uint32_t" => "%\" PRIu32 \"",
-                       "uint64_t" => "%\" PRIu64 \"",
-                       "int8_t" => "%\" PRId8 \"",
-                       "int16_t" => "%\" PRId16 \"",
-                       "int32_t" => "%\" PRId32 \"",
-                       "int64_t" => "%\" PRId64 \"",
-                       "::aos::monotonic_clock::time_point" => "\" AOS_TIME_FORMAT \""}
-        def toPrintFormat()
-		if(format = PrintFormat[@type])
-			return format;
-		end
-		raise QError.new(<<ERROR_MSG)
-Somehow this slipped past me, but
-\tI couldn't find the print format of #{@type}. Really, my bad.
-\tWot. Wot.
-ERROR_MSG
-	end
-
-	Sizes = {"bool" => 1, "float" => 4,"double" => 8,"::aos::monotonic_clock::time_point" => 8}
-	[8,16,32,64].each do |len|
-		Sizes["int#{len}_t"] = len / 8
-		Sizes["uint#{len}_t"] = len / 8
-	end
-	Zero = {"float" => "0.0f","double" => "0.0","bool" => "false","::aos::monotonic_clock::time_point" => "::aos::monotonic_clock::epoch()"}
-	def size()
-		if(size = Sizes[@type]); return size; end
-		return 1 if(@type == "char")
-		raise QError.new(<<ERROR_MSG)
-Somehow this slipped past me, but
-\tI couldn't find the size of #{@type}. Really, my bad.
-\tWot. Wot.
-ERROR_MSG
-	end
-	def lookup_type(locals)
-		return @type_name.lookup(locals)
-	end
-	def q_eval(locals)
-		check_type_error(locals)
-		if(@is_struct_type)
-			tval = lookup_type(locals)
-			member = Target::MessageStructElement.new(tval, @name)
-      if (@length != nil)
-        inner_member = member
-        member = Target::MessageArrayElement.new(inner_member, @length)
-      end
-		else
-			member = Target::MessageElement.new(@type,@name)
-			member.size = size()
-			member.zero = Zero[@type] || "0";
-			member.printformat = toPrintFormat()
-
-			if(@length != nil)
-        inner_member = member
-				member = Target::MessageArrayElement.new(inner_member,@length)
-			end
-		end
-		locals.local.add_member(member)
-	end
-	def self.parse(tokens)
-		line = tokens.pos
-		#type = tokens.expect(:tWord).data
-		type_name = QualifiedName.parse(tokens)
-		len = nil
-		if(tokens.peak == :tOpenB)
-			tokens.expect(:tOpenB)
-			len = tokens.expect(:tNumber).data
-			tokens.expect(:tCloseB)
-		end
-		name = tokens.expect(:tWord).data
-		tokens.expect(:tSemi)
-		return self.new(type_name,name,len).set_line(line)
-	end
-end
-class MessageStmt < QStmt
-	def initialize(name,suite)
-		@name = name
-		@suite = suite
-	end
-	def q_eval(locals)
-		group = Target::MessageDec.new(@name)
-		locals.register(group)
-		@suite.each do |stmt|
-			stmt.q_eval(locals.bind(group))
-		end 
-		return group
-	end
-	def self.parse(tokens)
-		name = tokens.expect(:tWord).data
-		values = []
-		tokens.expect(:tOpenB)
-		while(tokens.peak != :tCloseB)
-			values << MessageElementStmt.parse(tokens)
-		end
-		names = {}
-		values.each do |val|
-			if(names[val.name])
-				raise QSyntaxError.new(<<ERROR_MSG)
-Hey! duplicate name #{val.name.inspect} in your message declaration statement (message #{name}).
-\tI found them at: #{names[val.name].q_stack_name()} and #{val.q_stack_name()}.
-\tWot. Wot.
-ERROR_MSG
-			end
-			names[val.name] = val
-		end
-		tokens.expect(:tCloseB)
-		tokens.expect(:tSemi)
-		self.new(name,values)
-	end
-end
-class QueueStmt < QStmt
-	def initialize(type,name)
-		@type,@name = type,name
-	end
-	def q_eval(locals)
-		queue = Target::QueueDec.new(@type.lookup(locals),@name)
-		locals.register(queue)
-		locals.local.add_queue(queue) if(locals.local.respond_to?(:add_queue))
-		return queue
-	end
-	def self.parse(tokens)
-		line = tokens.pos
-		type_name = QualifiedName.parse(tokens)
-		name = tokens.expect(:tWord).data
-		tokens.expect(:tSemi)
-		return self.new(type_name,name).set_line(line)
-	end
-end
diff --git a/aos/build/queues/objects/queue_group.rb b/aos/build/queues/objects/queue_group.rb
deleted file mode 100644
index 136834f..0000000
--- a/aos/build/queues/objects/queue_group.rb
+++ /dev/null
@@ -1,115 +0,0 @@
-class QueueGroupTypeStmt < QStmt
-	def initialize(name,suite)
-		@name,@suite = name,suite
-	end
-	def q_eval(locals)
-		group = Target::QueueGroupDec.new(@name)
-		group.created_by = self
-		locals.register(group)
-		@suite.each do |stmt|
-			stmt.q_eval(locals.bind(group))
-		end
-		return group
-	end
-end
-class ImplementsStmt < QStmt
-	def initialize(name)
-		@name = name
-	end
-	def q_eval(locals)
-
-	end
-	def self.parse(tokens)
-		name = QualifiedName.parse(tokens)
-		tokens.expect(:tSemi)
-		return self.new(name)
-	end
-end
-class QueueGroupStmt < QStmt
-	def initialize(type,name)
-		@type,@name = type,name
-	end
-	def q_eval(locals)
-		group = Target::QueueGroup.new(@type.lookup(locals),@name)
-		group.created_by = self
-		locals.register(group)
-		return group
-	end
-	def self.parse(tokens)
-		line = tokens.pos
-		type_name = QualifiedName.parse(tokens)
-		if(type_name.names.include?("queue_group"))
-			tokens.qError(<<ERROR_MSG)
-I was looking at the identifier you gave 
-\tfor the queue group type between line #{line} and #{tokens.pos}
-\tThere shouldn't be a queue_group type called queue_group
-\tor including queue_group in it's path, it is a reserved keyword.
-\tWot. Wot.
-ERROR_MSG
-		end
-		if(tokens.peak == :tOpenB)
-			if(type_name.is_simple?())
-				type_name = type_name.to_simple
-			else
-				tokens.qError(<<ERROR_MSG)
-You gave the name: "#{type_name.to_s}" but you're only allowed to 
-\thave simple names like "#{type_name.names[-1]}" in queue_group definitions
-\ttry something like:
-\tqueue_group ControlLoop { }
-\tWot. Wot.
-ERROR_MSG
-			end
-			tokens.expect(:tOpenB)
-			suite = []
-			while(tokens.peak != :tCloseB)
-				token = tokens.expect(:tWord) do |token|
-					<<ERROR_MSG
-I'm a little confused, I found a #{token.humanize} at #{token.pos}
-\tbut what I really wanted was an identifier signifying a nested 
-\tmessage declaration, or queue definition, or an impliments statement.
-\tWot.Wot
-ERROR_MSG
-				end
-				case token.data
-				when "message"
-					suite << MessageStmt.parse(tokens)
-				when "queue"
-					suite << QueueStmt.parse(tokens)
-				when "implements"
-					suite << ImplementsStmt.parse(tokens)
-				else
-					tokens.qError(<<ERROR_MSG)
-expected a "queue","implements" or "message" statement rather
-\tthan a #{token.data.inspect}.
-\tWot. Wot.
-ERROR_MSG
-				end 
-			end
-			tokens.expect(:tCloseB)
-			obj = QueueGroupTypeStmt.new(type_name,suite).set_line(line)
-		else
-			name = (tokens.expect(:tWord) do |token|
-				<<ERROR_MSG
-I found a #{token.humanize} at #{token.pos}
-\tbut I was in the middle of parsing a queue_group statement, and
-\twhat I really wanted was an identifier to store the queue group.
-\tSomething like: queue_group control_loops.Drivetrain my_cool_group;
-\tWot.Wot
-ERROR_MSG
-			end).data
-			obj = QueueGroupStmt.new(type_name,name).set_line(line)
-			if(tokens.peak == :tDot)
-				tokens.qError(<<ERROR_MSG)
-Hey! It looks like you're trying to use a complex identifier at: #{tokens.pos}
-\tThats not going to work. Queue Group definitions have to be of the form:
-\tqueue_group ComplexID SimpleID
-\tWot. Wot.
-ERROR_MSG
-			end	
-		end
-		tokens.expect(:tSemi) do |token|
-			token.pos
-		end
-		return obj
-	end
-end
diff --git a/aos/build/queues/objects/tokenizer.rb b/aos/build/queues/objects/tokenizer.rb
deleted file mode 100644
index 2a33b90..0000000
--- a/aos/build/queues/objects/tokenizer.rb
+++ /dev/null
@@ -1,213 +0,0 @@
-class BufferedReader
-	def initialize(file)
-		@file = file
-		@line = 1
-		@chars = []
-		@col_nums = []
-		@col = 0
-	end
-	def filename
-		return File.basename(@file.path)
-	end
-	def pos()
-		"#{filename()}:#{lineno()},#{@col}"
-	end
-	def clear_comment()
-		@file.gets
-		@line += 1
-	end
-	def lineno()
-		return @line
-		return @file.lineno + 1
-	end
-	def pop_char()
-		val = @chars.pop() || @file.read(1)
-		@col_nums[@line] = @col += 1
-		if(val == "\n")
-			@line += 1
-			@col = 0
-		end
-
-		return val
-	end
-	def unpop_char(char)
-		if(char == "\n")
-			@line -= 1
-			@col = @col_nums[@line]
-		end
-		@col -= 1
-		@chars.push(char)
-	end
-end
-class Tokenizer
-	TOKEN_TYPES = {"{" => :tOpenB,"}"=> :tCloseB,";" => :tSemi,"," => :tComma,
-		"(" => :tOpenParan,")" => :tCloseParan,"=" => :tAssign,"." => :tDot,
-		"<<"=> :tLShift,"*" => :tMult,"+" => :tAdd,"[" => :tOpenB,
-		"]" => :tCloseB}
-	Humanize = TOKEN_TYPES.invert
-	class Token
-		attr_accessor :type,:data,:pos
-		def to_s
-			if(@type == :tString)
-				val = @data.inspect.to_s
-			elsif(@type == :tWord)
-				val = @data.to_s
-			else
-				val = @data.to_s
-			end
-			return "#{val.ljust(50)}:#{@type}"
-		end
-		def humanize()
-			if(@type == :tString)
-				return "#{@data.inspect.to_s} string"
-			elsif(@type == :tWord)
-				return "#{@data.inspect} identifier"
-			end
-			return Humanize[@type].inspect
-		end
-		def inspect()
-			data = ""
-			data = " #{@data.inspect}" if(@data)
-			"<Token :#{@type}#{data} at #{@pos}>"
-		end
-		def ==(other)
-			if(other.class == Symbol)
-				return @type == other
-			elsif(other.class == self.class)
-				return @type == other.type && @data == other.data
-			else
-				return nil
-			end
-		end
-	end
-	def initialize(file)
-		file = File.open(file,"r") if(file.class == String)
-		@read = BufferedReader.new(file)
-	end
-	def qError(error)
-		syntax_error(error)
-	end
-	def syntax_error(msg)
-		err = QSyntaxError.new(msg)
-		err.qstacktrace << "#{@read.lineno} of #{@read.filename}"
-		raise err
-	end
-	def peak_token()
-		@peak_token = next_token()
-	end
-	def peak()
-		peak_token()
-	end
-	def next()
-		next_token()
-	end
-	def pos()
-		@read.pos
-	end
-	def tokenize(string_token)
-		token = Token.new()
-		token.type = TOKEN_TYPES[string_token]
-		return token
-	end
-	def next_token()
-		if(token = @peak_token)
-			@peak_token = nil
-			return token
-		end
-		token = next_token_cache()
-		pos = self.pos()
-		token.pos = pos
-		return token
-	end
-	def next_token_cache()
-		token = Token.new()
-		token.data = ""
-		while (char = @read.pop_char())
-			#puts "#{char.inspect}:#{token.inspect}"
-			if(char == "/")
-				if(@read.pop_char == "/")
-					@read.clear_comment()
-				else
-					syntax_error("unexpected #{char.inspect}")
-				end
-			elsif(char == "#")
-				@read.clear_comment()
-			elsif(char =~ /[\s\r\n]/)
-				if(token.type)
-					return token
-				end
-			elsif(char =~ /\"/)
-				token.type = :tString
-				token.data = ""
-				while((char = @read.pop_char) != "\"")
-					token.data += char
-				end
-				return token
-			elsif(char =~ /[1-9]/)
-				token.type = :tNumber
-				token.data = char.to_i
-				while(char != ".")
-					char = @read.pop_char
-					if(char =~ /[0-9]/)
-						token.data = char.to_i + token.data * 10
-					elsif(char == ".")
-					else
-						@read.unpop_char(char)
-						return token
-					end
-				end
-				second_char = 0
-				man = 0
-				while(true)
-					char = @read.pop_char
-					if(char =~ /[0-9]/)
-						second_char = char.to_i + second_char * 10
-						man = man * 10
-					else
-						@read.unpop_char(char)
-						token.data += second_char / man.to_f
-						return token
-					end
-				end
-			elsif(char == ":")
-				if(@read.pop_char == "=")
-					return tokenize(":=")
-				end
-				syntax_error("unexpected \":\"")
-			elsif(char =~ /[;\{\}=()\",\*\+\.\[\]]/)
-				return(tokenize(char))
-			elsif(char =~ /[a-zA-Z_]/)
-				token.type = :tWord
-				token.data = char
-				while(true)
-					char = @read.pop_char()
-					if(char && char =~ /\w/)
-						token.data += char
-					else
-						@read.unpop_char(char)
-						return token
-					end
-				end
-			elsif(char == "<")
-				if((char = @read.pop_char()) == "<")
-					return tokenize("<<")
-				else
-					@read.unpop_char(char)
-					return tokenize("<")
-				end
-			else
-				syntax_error("unexpected #{char.inspect}")
-			end
-		end
-		token.type = :tEnd
-		return token
-	end
-	def expect(type,&blk)
-		token = self.next
-		if(token != type)
-			syntax_error(blk.call(token)) if(blk)
-			syntax_error("unexpected: #{token.type}")
-		end
-		return token
-	end
-end
diff --git a/aos/build/queues/output/message_dec.rb b/aos/build/queues/output/message_dec.rb
deleted file mode 100644
index 0f5694a..0000000
--- a/aos/build/queues/output/message_dec.rb
+++ /dev/null
@@ -1,434 +0,0 @@
-begin
-  require "sha1"
-rescue LoadError
-  require "digest/sha1"
-end
-
-class Target::StructBase < Target::Node
-  def create_DoGetType(type_class, cpp_tree)
-    member_func = CPP::MemberFunc.new(type_class,"const ::aos::MessageType*","DoGetType")
-    member_func.static = true
-    fields = []
-    register_members = []
-    @members.each do |member|
-      tId = member.getTypeID()
-      fieldName = member.name.inspect
-      if(member.respond_to?(:add_TypeRegister))
-        register_members.push(member)
-      end
-      fields << "new ::aos::MessageType::Field{#{tId}, #{member.respond_to?(:length) ? member.length : 0}, #{fieldName}}"
-    end
-    register_members.uniq do |member|
-      member.type
-    end.each do |member|
-      member.add_TypeRegister(cpp_tree, type_class, member_func)
-    end
-    id = getTypeID()
-    member_func.suite << ("static const ::aos::MessageType kMsgMessageType(#{type_class.parent_class ? type_class.parent_class + '::Size()' : 0}, #{id}, #{(@loc.respond_to?(:queue_name) ? @loc.queue_name(@name) : "#{@loc.get_name()}.#{@name}").inspect}, {" +
-                          "#{fields.join(", ")}})");
-                          type_class.add_member(member_func)
-                          member_func.suite << "::aos::type_cache::Add(kMsgMessageType)"
-                          member_func.suite << CPP::Return.new("&kMsgMessageType")
-  end
-  def create_InOrderConstructor(type_class, cpp_tree)
-    if @members.empty?
-      return
-    end
-    cons = CPP::Constructor.new(type_class)
-    type_class.add_member(cons)
-    @members.each do |member|
-      if member.respond_to?(:type_name)
-        type_name = "#{member.type_name(cpp_tree)} #{member.name}_in"
-      else
-        type_name = member.create_usage(cpp_tree, "#{member.name}_in")
-      end
-
-      cons.args << type_name
-      cons.add_cons(member.name, member.name + '_in')
-    end
-  end
-  def create_DefaultConstructor(type_class, cpp_tree)
-    cons = CPP::Constructor.new(type_class)
-    type_class.add_member(cons)
-    cons.add_cons(type_class.parent_class) if type_class.parent_class
-    cons.suite << CPP::FuncCall.build('Zero')
-  end
-  def create_Zero(type_class,cpp_tree)
-    member_func = CPP::MemberFunc.new(type_class,"void","Zero")
-    type_class.add_member(member_func)
-    @members.each do |elem|
-      elem.zeroCall(member_func.suite)
-    end
-    member_func.suite << CPP::FuncCall.new(type_class.parent_class + '::Zero') if type_class.parent_class
-  end
-  def create_Size(type_class,cpp_tree)
-    member_func = CPP::MemberFunc.new(type_class,"size_t","Size")
-    member_func.inline = true
-    member_func.static = true
-    type_class.add_member(member_func.forward_dec)
-    size = 0
-    @members.each do |elem|
-      size += elem.size
-    end
-    if type_class.parent_class
-      member_func.suite << CPP::Return.new(CPP::Add.new(size,
-                                                        "#{type_class.parent_class}::Size()"))
-    else
-      member_func.suite << CPP::Return.new(size)
-    end
-  end
-  def create_Serialize(type_class,cpp_tree)
-    member_func = CPP::MemberFunc.new(type_class,"size_t","Serialize")
-    type_class.add_member(member_func)
-    member_func.args << "char *buffer"
-    member_func.suite << "#{type_class.parent_class}::Serialize(buffer)" if type_class.parent_class
-    member_func.const = true
-    offset = type_class.parent_class ? type_class.parent_class + '::Size()' : '0'
-    @members.each do |elem|
-      elem.toNetwork(offset,member_func.suite)
-      offset += " + #{elem.size}";
-    end
-    member_func.suite << CPP::Return.new(CPP::FuncCall.new('Size'))
-  end
-  def create_Deserialize(type_class,cpp_tree)
-    member_func = CPP::MemberFunc.new(type_class,"size_t","Deserialize")
-    type_class.add_member(member_func)
-    member_func.args << "const char *buffer"
-    member_func.suite << "#{type_class.parent_class}::Deserialize(buffer)" if type_class.parent_class
-    offset = type_class.parent_class ? type_class.parent_class + '::Size()' : '0'
-    @members.each do |elem|
-      elem.toHost(offset,member_func.suite)
-      offset += " + #{elem.size}";
-    end
-    member_func.suite << CPP::Return.new(CPP::FuncCall.new('Size'))
-  end
-  def create_EqualsNoTime(type_class,cpp_tree)
-    member_func = CPP::MemberFunc.new(type_class,"bool","EqualsNoTime")
-    member_func.const = true
-    type_class.add_member(member_func)
-    member_func.args << "const #{type_class.name} &other"
-    member_func.suite << "if (!#{type_class.parent_class}::EqualsNoTime(other)) return false;" if type_class.parent_class
-    @members.each do |elem|
-      if elem.respond_to? :create_EqualsNoTime
-        member_func.suite << "if (!other.#{elem.name}.EqualsNoTime(#{elem.name})) return false;"
-      elsif elem.respond_to?(:length) && elem.member_type.respond_to?(:create_EqualsNoTime)
-        0.upto(elem.length - 1) do |i|
-          member_func.suite << "if (!other.#{elem.name}[#{i}].EqualsNoTime(#{elem.name}[#{i}])) return false;"
-        end
-      else
-        member_func.suite << "if (other.#{elem.name} != #{elem.name}) return false;"
-      end
-    end
-    member_func.suite << CPP::Return.new('true')
-  end
-  def simpleStr()
-    return "{\n" + @members.collect() { |elem| elem.simpleStr() + "\n"}.join("") + "}"
-  end
-  def getTypeID()
-    return "0x" + (((Digest::SHA1.hexdigest(simpleStr())[0..3].to_i(16)) << 16) | size).to_s(16)
-  end
-  def add_member(member)
-    @members << member
-  end
-  def size()
-    return @size if(@size)
-    @size = 0
-    @members.each do |elem|
-      @size += elem.size
-    end
-    return @size
-  end
-end
-
-class Target::MessageDec < Target::StructBase
-  attr_accessor :name,:loc,:parent,:msg_hash
-  def initialize(name)
-    @name = name
-    @members = []
-  end
-  def extern=(value)
-    @extern=value
-  end
-  def get_name()
-    if(@parent)
-      return "#{@parent.get_name}.#{@name}"
-    else
-      return "#{@name}"
-    end
-  end
-  def create_Print(type_class,cpp_tree)
-    member_func = CPP::MemberFunc.new(type_class,"size_t","Print")
-    type_class.add_member(member_func)
-    member_func.args << "char *buffer"
-    member_func.args << "size_t length"
-    member_func.const = true
-    format = "\""
-    args = []
-    @members.each do |elem|
-      format += ", "
-      format += elem.toPrintFormat()
-      elem.fetchPrintArgs(args)
-    end
-    format += "\""
-    member_func.suite << "size_t super_size = ::aos::Message::Print(buffer, length)"
-    member_func.suite << "buffer += super_size"
-    member_func.suite << "length -= super_size"
-    if !args.empty?
-      member_func.suite << "return super_size + snprintf(buffer, length, " + ([format] + args).join(", ") + ")";
-    else
-      # snprintf will return zero.
-      member_func.suite << "return super_size"
-    end
-  end
-  def create_GetType(type_class, cpp_tree)
-    member_func = CPP::MemberFunc.new(type_class,"const ::aos::MessageType*","GetType")
-    type_class.add_member(member_func)
-    member_func.static = true
-    member_func.suite << "static ::aos::Once<const ::aos::MessageType> getter(#{type_class.name}::DoGetType)"
-    member_func.suite << CPP::Return.new("getter.Get()")
-  end
-  def self.builder_loc(loc)
-    return @builder_loc if(@builder_loc)
-    return @builder_loc = loc.root.get_make("aos")
-  end
-  def type_name(builder_loc,name)
-    if(builder_loc == @loc) #use relative name
-      return name
-    else #use full name
-      return @loc.to_cpp_id(name)
-    end
-  end
-  def create(cpp_tree)
-    return self if(@extern)
-    orig_namespace = namespace = cpp_tree.get(@loc)
-    name = ""
-    if(namespace.class < Types::Type) #is nested
-      name = namespace.name + "_" + name
-      namespace = namespace.space
-    end
-    type_class = namespace.add_struct(name + @name)
-    if(name.length > 0)
-      orig_namespace.add_member(:public, Types::TypeDef.new(type_class,@name))
-    end
-    cpp_tree.set(self,type_class)
-    type_class.set_parent("public ::aos::Message")
-    ts = self.simpleStr()
-    self.msg_hash = "0x#{Digest::SHA1.hexdigest(ts)[-8..-1]}"
-    type_class.add_member("enum {kQueueLength = 100, kHash = #{self.msg_hash}}")
-    @members.each do |elem|
-      type_class.add_member(elem.create_usage(cpp_tree))
-    end
-
-    create_Serialize(type_class,cpp_tree)
-    create_Deserialize(type_class,cpp_tree)
-    create_Zero(type_class,cpp_tree)
-    create_Size(type_class,cpp_tree)
-    create_Print(type_class,cpp_tree)
-    create_GetType(type_class, cpp_tree)
-    create_DoGetType(type_class, cpp_tree)
-    create_DefaultConstructor(type_class, cpp_tree)
-    create_InOrderConstructor(type_class, cpp_tree)
-    create_EqualsNoTime(type_class, cpp_tree)
-
-    b_namespace = cpp_tree.get(b_loc = self.class.builder_loc(@loc))
-
-    template = b_namespace.add_template("MessageBuilder")
-    template.spec_args << t = @loc.to_cpp_id(@name)
-    msg_ptr_t = "ScopedMessagePtr< #{t}>"
-    msg_bld_t = "MessageBuilder< #{t}>"
-    template.add_member(:private,"#{msg_ptr_t} msg_ptr_")
-    template.add_member(:private,"#{msg_bld_t}(const #{msg_bld_t}&)")
-    template.add_member(:private,"void operator=(const #{msg_bld_t}&)")
-    template.add_member(:private,"friend class ::aos::Queue< #{t}>")
-
-    cons = CPP::Constructor.new(template)
-    template.add_member(:private,cons)
-    cons.args << "RawQueue *queue"
-    cons.args << "#{t} *msg"
-    cons.add_cons("msg_ptr_","queue","msg")
-    template.public
-    DefineMembers(cpp_tree, template, msg_bld_t)
-  end
-  def DefineMembers(cpp_tree, template, msg_bld_t) 
-    send = template.def_func("bool","Send")
-    send.suite << CPP::Return.new("msg_ptr_.Send()")
-    @members.each do |elem|
-=begin
-      MessageBuilder<frc971::control_loops::Drivetrain::Goal> &steering(
-              double steering) {
-            msg_ptr_->steering = steering;
-              return *this;
-              }
-=end
-      setter = template.def_func(msg_bld_t,"&#{elem.name}")
-        setter.args << elem.create_usage(cpp_tree)
-      elem.set_message_builder(setter.suite)
-      setter.suite << CPP::Return.new("*this")
-
-    end
-  end
-end
-class Target::MessageElement < Target::Node
-  attr_accessor :name,:loc,:size,:zero,:type,:printformat
-  def initialize(type,name)
-    @type,@name = type,name
-  end
-  def type()
-    return @type
-  end
-  def type_name(cpp_tree)
-    return type()
-  end
-  def toPrintFormat()
-    return printformat
-  end
-  def create_usage(cpp_tree, this_name=nil)
-    if (this_name == nil)
-      this_name = @name
-    end
-    "#{@type} #{this_name}"
-  end
-  def toNetwork(offset,suite, parent = "", this_name=nil)
-    if (this_name == nil)
-      this_name = @name
-    end
-    suite << f_call = CPP::FuncCall.build("to_network",
-                                          "&#{parent}#{this_name}",
-                                          "&buffer[#{offset}]")
-    f_call.args.dont_wrap = true
-  end
-  def toHost(offset,suite, parent = "", this_name=nil)
-    if (this_name == nil)
-      this_name = @name
-    end
-    suite << f_call = CPP::FuncCall.build("to_host",
-                                          "&buffer[#{offset}]",
-                                          "&#{parent}#{this_name}")
-                                            f_call.args.dont_wrap = true
-  end
-  def getTypeID()
-    '0x' + ((Digest::SHA1.hexdigest(@type)[0..3].to_i(16) << 16) |
-            0x2000 | # marks it as primitive
-            size).to_s(16)
-  end
-  def simpleStr()
-    "#{@type} #{@name}"
-  end
-  def set_message_builder(suite, this_name=nil)
-    this_name ||= @name
-    suite << "msg_ptr_->#{this_name} = #{this_name}"
-  end
-
-  def zeroCall(suite, parent = "", this_name=nil)
-    if (this_name == nil)
-      this_name = @name
-    end
-    suite << CPP::Assign.new(parent + this_name,@zero)
-  end
-  def fetchPrintArgs(args, parent = "", this_name=nil)
-    if (this_name == nil)
-      this_name = @name
-    end
-    if (@type == 'bool')
-      args.push("#{parent}#{this_name} ? 'T' : 'f'")
-    elsif (@type == '::aos::monotonic_clock::time_point')
-      args.push(["AOS_TIME_ARGS(static_cast<int32_t>(",
-                 "::std::chrono::duration_cast<::std::chrono::seconds>(",
-                 "#{parent}#{this_name}.time_since_epoch()).count()), ",
-                 "static_cast<uint32_t>(::std::chrono::duration_cast<::std::chrono::nanoseconds>(",
-                 "#{parent}#{this_name}.time_since_epoch() - ",
-                 "::std::chrono::duration_cast<::std::chrono::seconds>(",
-                 "#{parent}#{this_name}.time_since_epoch())).count()))"].join(''))
-    else
-      args.push("#{parent}#{this_name}")
-    end
-  end
-end
-class Target::MessageArrayElement < Target::Node
-  attr_accessor :loc, :length
-  def initialize(type,length)
-    @type,@length = type,length
-  end
-  def zero()
-    return @type.zero()
-  end
-  def name()
-    return @type.name()
-  end
-
-  def add_TypeRegister(*args)
-    if @type.respond_to?(:add_TypeRegister)
-      @type.add_TypeRegister(*args)
-    end
-  end
-
-  def toPrintFormat()
-    return ([@type.toPrintFormat] * @length).join(", ")
-  end
-  def create_usage(cpp_tree, this_name=nil)
-    if (this_name == nil)
-      this_name = name
-    end
-    return "::std::array< #{@type.type_name(cpp_tree)}, #{@length}> #{this_name}"
-  end
-  def type()
-    return "::std::array< #{@type.type()}, #{@length}>"
-  end
-  def member_type()
-    return @type
-  end
-  def simpleStr()
-    return "#{@type.type} #{@name}[#{@length}]"
-  end
-  def getTypeID()
-    return @type.getTypeID()
-  end
-  def size()
-    return @type.size * @length
-  end
-  def toNetwork(offset, suite, parent="", this_name=nil)
-    if (this_name == nil)
-      this_name = name
-    end
-    offset = (offset == 0) ? "" : "#{offset} + "
-    for_loop_var = getForLoopVar()
-    suite << for_stmt = CPP::For.new("int #{for_loop_var} = 0","#{for_loop_var} < #{@length}","#{for_loop_var}++")
-    @type.toNetwork("#{offset} (#{for_loop_var} * #{@type.size})", for_stmt.suite, parent, "#{this_name}[#{for_loop_var}]")
-  end
-  def toHost(offset, suite, parent="", this_name=nil)
-    if (this_name == nil)
-      this_name = name
-    end
-    offset = (offset == 0) ? "" : "#{offset} + "
-    for_loop_var = getForLoopVar()
-    suite << for_stmt = CPP::For.new("int #{for_loop_var} = 0","#{for_loop_var} < #{@length}","#{for_loop_var}++")
-    @type.toHost("#{offset} (#{for_loop_var} * #{@type.size})", for_stmt.suite, parent, "#{this_name}[#{for_loop_var}]")
-  end
-  def set_message_builder(suite, this_name=nil)
-    if (this_name == nil)
-      this_name = name
-    end
-
-    for_loop_var = getForLoopVar()
-    suite << for_stmt = CPP::For.new("int #{for_loop_var} = 0","#{for_loop_var} < #{@length}","#{for_loop_var}++")
-    @type.set_message_builder(for_stmt.suite, "#{this_name}[#{for_loop_var}]")
-  end
-  def zeroCall(suite, parent="", this_name=nil)
-    if (this_name == nil)
-      this_name = name
-    end
-
-    offset = (offset == 0) ? "" : "#{offset} + "
-    for_loop_var = getForLoopVar()
-    suite << for_stmt = CPP::For.new("int #{for_loop_var} = 0","#{for_loop_var} < #{@length}","#{for_loop_var}++")
-    @type.zeroCall(for_stmt.suite, parent, "#{this_name}[#{for_loop_var}]")
-  end
-  def fetchPrintArgs(args, parent = "", this_name=nil)
-    if (this_name == nil)
-      this_name = name
-    end
-    for i in 0..(@length-1)
-      @type.fetchPrintArgs(args, parent, "#{this_name}[#{i}]")
-    end
-  end
-end
diff --git a/aos/build/queues/output/q_file.rb b/aos/build/queues/output/q_file.rb
deleted file mode 100644
index 3bbdaed..0000000
--- a/aos/build/queues/output/q_file.rb
+++ /dev/null
@@ -1,200 +0,0 @@
-begin
-  require "sha1"
-rescue LoadError
-  require "digest/sha1"
-end
-
-$i = 0
-def getForLoopVar()
-  $i = $i + 1
-  return "_autogen_index_#{$i}"
-end
-
-module Target
-end
-class Target::Node
-	attr_accessor :created_by
-	def get_name()
-		if(@parent)
-			return "#{@parent.get_name}.#{@name}"
-		else
-			return "#{@name}"
-		end 
-	end
-end
-class Target::QFile < Target::Node
-	def initialize() #needs to know repo_path, 
-		@class_types = []
-	end
-	def add_type(type)
-		@class_types << type
-	end
-	def extern=(value)
-		@class_types.each do |type|
-			type.extern=value
-		end
-	end
-	def make_cpp_tree(rel_path)
-		cpp_tree = DepFilePair.new(rel_path)
-		cpp_tree.add_header_include("<array>")
-		cpp_tree.add_header_include("\"aos/macros.h\"")
-		cpp_tree.add_header_include("\"aos/queue.h\"")
-		@class_types.each do |type|
-			cpp_tree.get(type)
-		end
-		return cpp_tree
-	end
-end
-class Target::QInclude < Target::Node
-	def initialize(path)
-		@path = path
-	end
-	def extern=(value)
-		@extern=value
-	end
-	def create(cpp_tree)
-		return if (@extern)
-#		inc = cpp_tree.header.add_include("\"#{@path}\"")
-		inc = cpp_tree.add_header_include("\"#{@path}\"")
-		cpp_tree.set(self,inc)
-	end
-end
-class Target::QueueGroupDec < Target::Node
-	attr_accessor :name,:loc,:parent,:queues
-	def initialize(name)
-		@name = name
-		@queues = []
-		@subs = {}
-	end
-	def root()
-		@parent.root()
-	end
-	def []=(key,val)
-		#puts "#{key}= #{val}"
-		@subs[key] = val
-	end
-	def extern=(value)
-		@extern=value
-	end
-	def get_name()
-		if(@parent)
-			return "#{@parent.get_name}.#{@name}"
-		else
-			return "#{@name}"
-		end 
-	end
-	def to_cpp_id(id)
-		name = "#{@name}::#{id}"
-		return @parent.to_cpp_id(name) if(@parent)
-		return name
-	end
-	def [](key)
-		#puts "#{key}"
-		@subs[key]
-	end
-	def add_queue(queue)
-		@queues.push(queue)
-	end
-	def hash_with_name(name)
-		ts = (@queues.collect { |queue|
-			queue.msg_hash()
-		}).join("") + name
-		return "0x#{Digest::SHA1.hexdigest(ts)[-8..-1]}"
-	end
-	def create(cpp_tree)
-		return if(@extern)
-		namespace = cpp_tree.get(@loc)
-		type_class = Types::Class.new(namespace,@name)
-		cpp_tree.set(self,type_class)  #breaks infinite recursion
-		type_class.set_parent("public ::aos::QueueGroup")
-		@queues.each do |queue|
-			type_class.add_member(:public,queue.create_usage(cpp_tree))
-		end
-		create_Constructor(type_class,cpp_tree)
-		namespace.add(type_class)
-	end
-	def create_Constructor(type_class,cpp_tree)
-		member_func = CPP::Constructor.new(type_class)
-		type_class.add_member(:public,member_func)
-		#cpp_tree.cc_file.add_funct(member_func)
-		member_func.args << "const char *name";
-		member_func.add_cons("::aos::QueueGroup","name")
-		@queues.each do |queue|
-			member_func.args << "const char *#{queue.name}_name";
-			member_func.add_cons(queue.name,"#{queue.name}_name")
-		end
-	end
-end
-class Target::QueueGroup < Target::Node
-	attr_accessor :name,:loc
-	def initialize(type,name)
-		@type,@name = type,name
-	end
-	def type_name()
-		if(@type.loc == @loc) #use relative name
-			return @type.name
-		else #use full name
-			return @type.loc.to_cpp_id(@type.name)
-		end 
-	end
-	def create(cpp_tree)
-		namespace = cpp_tree.get(@loc)
-		type = cpp_tree.get(@type)
-		cpp_tree.set(self,self)
-		namespace.add_cc("static #{type_name} *#{@name}_ptr")
-		counter = "#{@name}_counter"
-		namespace.add_cc("static int #{counter}")
-
-		str = <<COMMENT_END
-Schwarz counter to construct and destruct the #{@name} object.
-Must be constructed before &#{@name} is constructed so that #{@name}_ptr
-is valid so we can store a reference to the object.
-COMMENT_END
-		str.split(/\n/).each do |str_sec|
-			namespace.class_comment(str_sec)
-		end
-		init_class = namespace.add_class("InitializerFor_" + @name).add_dep(type)
-		
-
-		init_class.add_cc_comment(
-        "The counter is initialized at load-time, i.e., before any of the static",
-		"objects are initialized.")
-
-
-		cons = CPP::Constructor.new(init_class)
-		init_class.add_member(:public,cons)
-		cons.suite << if_stmt = CPP::If.new("0 == #{counter}++")
-
-		cons_call = CPP::FuncCall.new("new #{type_name}")
-		cons_call.args.push(@loc.queue_name(@name).inspect)
-
-		@type.queues.collect do |queue|
-			cons_call.args.push(@loc.queue_name(@name + "." + queue.name).inspect)
-		end
-		if_stmt.suite << CPP::Assign.new("#{@name}_ptr",cons_call)
-
-
-		destruct = CPP::Destructor.new(init_class)
-		destruct.suite << if_stmt = CPP::If.new("0 == --#{counter}")
-		if_stmt.suite << "delete #{@name}_ptr"
-		if_stmt.suite << CPP::Assign.new("#{@name}_ptr","NULL")
-
-		init_class.add_member(:public,destruct)
-		init_class.static = true
-		init_class.dec = @name + "_initializer";
-
-		str = <<COMMENT_END
-Create a reference to the new object in the pointer.  Since we have already
-created the initializer
-COMMENT_END
-		str.split(/\n/).map{|str_sec| CPP::Comment.new(str_sec)}.each do |comment|
-      namespace.add(comment)
-    end
-		namespace.add("static UNUSED_VARIABLE #{type_name} &#{@name}" +
-                  " = #{@name}_initializer.get()")
-
-		get = init_class.def_func(type_name,"get") #.add_dep(type)
-		get.pre_func_types = "&"
-		get.suite << CPP::Return.new("*#{@name}_ptr")
-	end
-end
diff --git a/aos/build/queues/output/q_struct.rb b/aos/build/queues/output/q_struct.rb
deleted file mode 100644
index f538bb3..0000000
--- a/aos/build/queues/output/q_struct.rb
+++ /dev/null
@@ -1,156 +0,0 @@
-class Target::StructDec < Target::StructBase
-  attr_accessor :name,:loc,:parent, :extern
-  def initialize(name)
-    @name = name
-    @members = []
-  end
-  def add_member(member)
-    @members << member
-  end
-  def create_GetType(type_class, cpp_tree)
-    member_func = CPP::MemberFunc.new(type_class,"const ::aos::MessageType*","GetType")
-    type_class.add_member(member_func)
-    member_func.static = true
-    member_func.suite << "static ::aos::Once<const ::aos::MessageType> getter(#{type_class.name}::DoGetType)"
-    member_func.suite << CPP::Return.new("getter.Get()")
-  end
-  def create(cpp_tree)
-    return self if(@extern)
-    orig_namespace = namespace = cpp_tree.get(@loc)
-    name = ""
-    if(namespace.class < Types::Type) #is nested
-      name = namespace.name + "_" + name
-      namespace = namespace.space
-    end
-    type_class = namespace.add_struct(name + @name)
-
-    @members.each do |elem|
-      type_class.add_member(elem.create_usage(cpp_tree))
-    end
-    create_DoGetType(type_class, cpp_tree)
-    create_GetType(type_class, cpp_tree)
-    create_DefaultConstructor(type_class, cpp_tree)
-    create_InOrderConstructor(type_class, cpp_tree)
-    create_Zero(type_class, cpp_tree)
-    create_Size(type_class, cpp_tree)
-    create_Serialize(type_class, cpp_tree)
-    create_Deserialize(type_class, cpp_tree)
-    create_EqualsNoTime(type_class, cpp_tree)
-    return type_class
-  end
-  def getPrintFormat()
-    return "{" + @members.collect { |elem| elem.toPrintFormat() }.join(", ") + "}"
-  end
-  def fetchPrintArgs(args, parent = "")
-    @members.each do |elem|
-      elem.fetchPrintArgs(args, parent)
-    end
-  end
-  def toHost(offset, suite, parent)
-    @members.each do |elem|
-      elem.toHost(offset, suite, parent)
-      offset += " + #{elem.size()}"
-    end
-  end
-  def toNetwork(offset, suite, parent)
-    @members.each do |elem|
-      elem.toNetwork(offset, suite, parent)
-      offset += " + #{elem.size()}"
-    end
-  end
-  def zeroCall(suite, parent)
-    @members.each do |elem|
-      elem.zeroCall(suite, parent)
-    end
-  end
-end
-class Target::MessageStructElement < Target::Node
-  attr_accessor :name,:loc
-  def initialize(type,name)
-    @type, @name = type, name
-  end
-  def type()
-    return @type.get_name
-  end
-  def create_EqualsNoTime(type_class,cpp_tree)
-    member_func = CPP::MemberFunc.new(type_class,"bool","EqualsNoTime")
-    member_func.const = true
-    type_class.add_member(member_func)
-    member_func.args << "const #{type_class.name} &other"
-    member_func.suite << "if (!#{type_class.parent_class}::EqualsNoTime(other)) return false;" if type_class.parent_class
-    @members.each do |elem|
-      if elem.respond_to? :create_EqualsNoTime
-        member_func.suite << "if (!other.#{elem.name}.EqualsNoTime(#{elem.name})) return false;"
-      elsif elem.respond_to?(:length) && elem.member_type.respond_to?(:create_EqualsNoTime)
-        0.upto(elem.length - 1) do |i|
-          member_func.suite << "if (!other.#{elem.name}[#{i}].EqualsNoTime(#{elem.name}[#{i}])) return false;"
-        end
-      else
-        member_func.suite << "if (other.#{elem.name} != #{elem.name}) return false;"
-      end
-    end
-    member_func.suite << CPP::Return.new('true')
-  end
-  def type_name(cpp_tree)
-    type = cpp_tree.get(@type)
-    if(@type.loc == @loc) #use relative name
-      return type.name
-    else #use full name
-      return @type.loc.to_cpp_id(type.name)
-    end 
-  end
-  def size()
-    return @type.size()
-  end
-  def toPrintFormat()
-    @type.getPrintFormat()
-  end
-  def create_usage(cpp_tree, this_name=nil)
-    if (this_name == nil)
-      this_name = @name
-    end
-    return "#{type_name(cpp_tree)} #{this_name}"
-  end
-  def add_TypeRegister(cpp_tree, o_type, member_func)
-    type = cpp_tree.get(@type)
-    tName = @type.loc.to_cpp_id(type.name)
-    member_func.suite << "#{tName}::GetType()"
-  end
-  def fetchPrintArgs(args, parent = "", this_name=nil)
-    if (this_name == nil)
-      this_name = @name
-    end
-    @type.fetchPrintArgs(args, parent + "#{this_name}.")
-  end
-  def toNetwork(offset,suite, parent = "", this_name=nil)
-    if (this_name == nil)
-      this_name = @name
-    end
-    @type.toNetwork(offset, suite, parent + "#{this_name}.")
-  end
-  def toHost(offset,suite, parent = "", this_name=nil)
-    if (this_name == nil)
-      this_name = @name
-    end
-    @type.toHost(offset, suite, parent + "#{this_name}.")
-  end
-  def set_message_builder(suite, this_name=nil)
-    if (this_name == nil)
-      this_name = @name
-    end
-    suite << "msg_ptr_->#{this_name} = #{this_name}"
-  end
-
-  def zeroCall(suite, parent = "", this_name=nil)
-    if (this_name == nil)
-      this_name = @name
-    end
-    @type.zeroCall(suite, parent + "#{this_name}.")
-  end
-  def simpleStr()
-    "#{@type.simpleStr()} #{@name}"
-  end
-  def getTypeID()
-    return @type.getTypeID()
-  end
-end
diff --git a/aos/build/queues/output/queue_dec.rb b/aos/build/queues/output/queue_dec.rb
deleted file mode 100644
index 031c033..0000000
--- a/aos/build/queues/output/queue_dec.rb
+++ /dev/null
@@ -1,89 +0,0 @@
-class Target::QueueDec < Target::Node
-	attr_accessor :name,:loc
-	def initialize(type,name)
-		@type,@name = type,name
-	end
-	def msg_hash()
-		return @type.msg_hash
-	end
-	def full_message_name(cpp_tree)
-		type = cpp_tree.get(@type)
-		return @type.loc.to_cpp_id(type.name)
-	end
-	def full_builder_name(cpp_tree)
-		return "::aos::MessageBuilder< #{full_message_name(cpp_tree)}>"
-	end
-	def full_type_name(cpp_tree)
-		return "::aos::Queue< #{full_message_name(cpp_tree)}>"
-	end
-	def type_name(cpp_tree,queue_type = "::aos::Queue")
-		type = cpp_tree.get(@type)
-		if(@type.loc == @loc) #use relative name
-			return "#{queue_type}<#{type.name}>"
-		else #use full name
-			return "#{queue_type}< #{@type.loc.to_cpp_id(type.name)}>"
-		end
-	end
-	def create_usage(cpp_tree)
-		"#{type_name(cpp_tree)} #{@name}"
-	end
-	def create(cpp_tree)
-		namespace = cpp_tree.get(@loc)
-		type = cpp_tree.get(@type)
-		cpp_tree.set(self,self)
-		type_name = type_name(cpp_tree)
-		full_type_name = full_type_name(cpp_tree)
-		namespace.add_cc("static #{type_name} *#{@name}_ptr")
-		counter = "#{@name}_counter"
-		namespace.add_cc("static int #{counter}")
-
-		str = <<COMMENT_END
-Schwarz counter to construct and destruct the #{@name} queue.
-Must be constructed before &#{@name} is constructed so that #{@name}_ptr
-is valid so we can store a reference to the object.
-COMMENT_END
-		str.split(/\n/).each do |str_sec|
-			namespace.class_comment(str_sec)
-		end
-		init_class = namespace.add_class("InitializerFor_" + @name)
-
-		init_class.add_cc_comment(
-        "The counter is initialized at load-time, i.e., before any of the static",
-		"objects are initialized.")
-
-
-		cons = CPP::Constructor.new(init_class)
-		init_class.add_member(:public,cons)
-		cons.suite << if_stmt = CPP::If.new("0 == #{counter}++")
-
-		cons_call = CPP::FuncCall.new("new #{type_name}")
-		cons_call.args.push(@loc.queue_name(@name).inspect)
-		if_stmt.suite << CPP::Assign.new("#{@name}_ptr",cons_call)
-
-
-		destruct = CPP::Destructor.new(init_class)
-		init_class.add_member(:public,destruct)
-		destruct.suite << if_stmt = CPP::If.new("0 == --#{counter}")
-		if_stmt.suite << "delete #{@name}_ptr"
-		if_stmt.suite << CPP::Assign.new("#{@name}_ptr","NULL")
-
-		init_class.static = true
-		init_class.dec = @name + "_initializer";
-
-		str = <<COMMENT_END
-Create a reference to the new object in the pointer.  Since we have already
-created the initializer
-COMMENT_END
-		str.split(/\n/).map{|str_sec| CPP::Comment.new(str_sec)}.each do |comment|
-      namespace.add(comment)
-    end
-		namespace.add("static UNUSED_VARIABLE #{type_name} &#{@name}" +
-                  " = #{@name}_initializer.get()")
-
-		get = init_class.def_func(full_type_name,"get")
-		get.pre_func_types = "&"
-		get.suite << CPP::Return.new("*#{@name}_ptr")
-		
-	end
-end
-
diff --git a/aos/build/queues/print_field.rb b/aos/build/queues/print_field.rb
deleted file mode 100644
index 4f26d04..0000000
--- a/aos/build/queues/print_field.rb
+++ /dev/null
@@ -1,118 +0,0 @@
-require_relative 'load.rb'
-
-# TODO(brians): Special-case Time too and float/double if we can find a good way to do it.
-GenericTypeNames = ['float', 'double', 'char']
-TimeTypeNames = ['::aos::monotonic_clock::time_point']
-IntegerSizes = [8, 16, 32, 64]
-
-WriteIffChanged.open(ARGV[0]) do |output|
-  output.puts <<END
-// This file is generated by #{File.expand_path(__FILE__)}.
-// DO NOT EDIT BY HAND!
-
-#include <sys/types.h>
-#include <stdint.h>
-#include <inttypes.h>
-#include <stdio.h>
-
-#include "aos/byteorder.h"
-#include "aos/time/time.h"
-#include "aos/print_field_helpers.h"
-#include "aos/logging/printf_formats.h"
-
-namespace aos {
-
-bool PrintField(char *output, size_t *output_bytes, const void *input,
-                size_t *input_bytes, uint32_t type) {
-  switch (type) {
-#{GenericTypeNames.collect do |name|
-  message_element = Target::MessageElement.new(name, 'value')
-  statement = MessageElementStmt.new(name, 'value')
-  message_element.size = statement.size
-  print_args = []
-  message_element.fetchPrintArgs(print_args)
-  next <<END2
-    case #{message_element.getTypeID()}:
-      {
-        if (*input_bytes < #{statement.size}) return false;
-        *input_bytes -= #{statement.size};
-        #{name} value;
-        to_host(static_cast<const char *>(input), &value);
-        int ret = snprintf(output, *output_bytes,
-                           "#{statement.toPrintFormat()}",
-                           #{print_args[0]});
-        if (ret < 0) return false;
-        if (static_cast<unsigned int>(ret) >= *output_bytes) return false;
-        *output_bytes -= ret;
-        return true;
-      }
-END2
-end.join('')}
-#{TimeTypeNames.collect do |name|
-  message_element = Target::MessageElement.new(name, 'value')
-  statement = MessageElementStmt.new(name, 'value')
-  message_element.size = statement.size
-  print_args = []
-  message_element.fetchPrintArgs(print_args)
-  next <<END2
-    case #{message_element.getTypeID()}:
-      {
-        if (*input_bytes < #{statement.size}) return false;
-        *input_bytes -= #{statement.size};
-        int32_t upper;
-        uint32_t lower;
-        to_host(static_cast<const char *>(input), &upper);
-        to_host(static_cast<const char *>(input) + 4, &lower);
-        #{name} value(::std::chrono::seconds(upper) + ::std::chrono::nanoseconds(lower));
-        int ret = snprintf(output, *output_bytes,
-                           "#{statement.toPrintFormat()}",
-                           #{print_args[0]});
-        if (ret < 0) return false;
-        if (static_cast<unsigned int>(ret) >= *output_bytes) return false;
-        *output_bytes -= ret;
-        return true;
-      }
-END2
-end.join('')}
-#{IntegerSizes.collect do |size|
-  [true, false].collect do |signed|
-    size_bytes = size / 8
-    name = "#{signed ? '' : 'u'}int#{size}_t"
-    message_element = Target::MessageElement.new(name, 'value')
-    message_element.size = size_bytes
-    next <<END2
-    case #{message_element.getTypeID()}:
-      {
-        if (*input_bytes < #{size_bytes}) return false;
-        *input_bytes -= #{size_bytes};
-        #{name} value;
-        to_host(static_cast<const char *>(input), &value);
-        return PrintInteger<#{name}>(output, value, output_bytes);
-      }
-END2
-  end
-end.flatten.join('')}
-#{
-  message_element = Target::MessageElement.new('bool', 'value')
-  message_element.size = 1
-  r = <<END2
-    case #{message_element.getTypeID()}:
-      {
-        if (*input_bytes < 1) return false;
-        if (*output_bytes < 1) return false;
-        *input_bytes -= 1;
-        bool value = static_cast<const char *>(input)[0];
-        *output_bytes -= 1;
-        *output = value ? 'T' : 'f';
-        return true;
-      }
-END2
-}
-    default:
-      return false;
-  }
-}
-
-}  // namespace aos
-END
-end
diff --git a/aos/build/queues/q_specs/nested_structs.q b/aos/build/queues/q_specs/nested_structs.q
deleted file mode 100644
index 7162620..0000000
--- a/aos/build/queues/q_specs/nested_structs.q
+++ /dev/null
@@ -1,12 +0,0 @@
-package aos.test;
-
-import "q_specs/struct_test.q";
-
-
-message Position {
-	int32_t a;
-	int32_t[2] b;
-	.aos.test2.ClawHalfPosition top;
-	.aos.test2.ClawHalfPosition bottom;
-	bool c;
-};
diff --git a/aos/build/queues/q_specs/struct_queue_group.q b/aos/build/queues/q_specs/struct_queue_group.q
deleted file mode 100644
index 2bc5046..0000000
--- a/aos/build/queues/q_specs/struct_queue_group.q
+++ /dev/null
@@ -1,20 +0,0 @@
-package aos.test;
-
-struct Claw {
-	int32_t a;
-	int32_t b;
-};
-
-	message HPosition {
-		Claw top;
-	};
-
-// All angles here are 0 horizontal, positive up. 
-queue_group ClawGroup {
-
-	message Position {
-		Claw top;
-	};
-	queue Position kjks;
-};
-
diff --git a/aos/build/queues/q_specs/struct_test.q b/aos/build/queues/q_specs/struct_test.q
deleted file mode 100644
index afb22ac..0000000
--- a/aos/build/queues/q_specs/struct_test.q
+++ /dev/null
@@ -1,12 +0,0 @@
-package aos.test2;
-
-struct SubStruct {
-	int32_t g;
-};
-
-struct ClawHalfPosition {
-	double position; 
-	bool hall_effect;
-	SubStruct clampy;
-};
-
diff --git a/aos/build/queues/queue_primitives.rb b/aos/build/queues/queue_primitives.rb
deleted file mode 100644
index a5f6624..0000000
--- a/aos/build/queues/queue_primitives.rb
+++ /dev/null
@@ -1,54 +0,0 @@
-require_relative 'load.rb'
-
-require 'fileutils'
-
-TypeNames = [8, 16, 32, 64].collect do |size|
-  ["uint#{size}_t", "int#{size}_t"]
-end.flatten + ['bool', 'float', 'char', 'double', '::aos::monotonic_clock::time_point']
-
-FileUtils.mkdir_p(File.dirname(ARGV[0]))
-WriteIffChanged.open(ARGV[0]) do |output|
-  output.puts <<END
-// This file is generated by #{File.expand_path(__FILE__)}.
-// DO NOT EDIT BY HAND!
-
-#include <stdint.h>
-
-#include "aos/time/time.h"
-
-namespace aos {
-namespace queue_primitive_types {
-#{TypeNames.collect do |name|
-  message_element = Target::MessageElement.new(name, 'value')
-  statement = MessageElementStmt.new(name, 'value')
-  message_element.size = statement.size
-  name = 'Time' if name == '::aos::monotonic_clock::time_point'
-  next <<END2
-  static const uint32_t #{name}_p = #{message_element.getTypeID()};
-END2
-end.join('')}
-}  // namespace queue_primitive_types
-
-// A class for mapping an actual type to a type ID.
-// There are specializations for all of the actual primitive types.
-template<typename T>
-class TypeID {
- public:
-  static const uint32_t id;
-};
-
-#{TypeNames.collect do |name|
-  message_element = Target::MessageElement.new(name, 'value')
-  statement = MessageElementStmt.new(name, 'value')
-  message_element.size = statement.size
-  next <<END2
-template<>
-class TypeID< #{name}> {
- public:
-  static const uint32_t id = #{message_element.getTypeID()};
-};
-END2
-end.join('')}
-}  // namespace aos
-END
-end
diff --git a/aos/build/queues/write_iff_changed.rb b/aos/build/queues/write_iff_changed.rb
deleted file mode 100644
index 74373a9..0000000
--- a/aos/build/queues/write_iff_changed.rb
+++ /dev/null
@@ -1,30 +0,0 @@
-require 'tempfile'
-
-# Writes a file like normal except doesn't do anything if the new contents are
-# the same as what's already there. Useful for helping build tools not rebuild
-# if generated files are re-generated but don't change.
-# Usable as a standard File, including to redirect to with IO.popen etc.
-class WriteIffChanged < Tempfile
-  def initialize(filename)
-    super('write_iff_changed')
-    @filename = filename
-  end
-  def WriteIffChanged.open(filename)
-    out = WriteIffChanged.new(filename)
-    yield out
-    out.close
-  end
-  def close
-    flush
-    contents = File.open(path, 'r') do |f|
-      f.readlines(nil)
-    end
-    if !File.exists?(@filename) ||
-        File.new(@filename, 'r').readlines(nil) != contents
-      File.open(@filename, 'w') do |out|
-        out.write(contents[0])
-      end
-    end
-    super
-  end
-end
diff --git a/aos/condition.cc b/aos/condition.cc
index 0c81e2c..e4276b6 100644
--- a/aos/condition.cc
+++ b/aos/condition.cc
@@ -4,9 +4,9 @@
 #include <inttypes.h>
 #include <time.h>
 
-#include "aos/logging/logging.h"
 #include "aos/mutex/mutex.h"
 #include "aos/type_traits/type_traits.h"
+#include "glog/logging.h"
 
 namespace aos {
 
@@ -28,7 +28,7 @@
   const bool do_timeout = timeout != chrono::nanoseconds(0);
 
   if (do_timeout) {
-    AOS_PCHECK(clock_gettime(CLOCK_MONOTONIC, &end_time) == 0);
+    PCHECK(clock_gettime(CLOCK_MONOTONIC, &end_time) == 0);
     timeout += chrono::nanoseconds(end_time.tv_nsec);
     chrono::seconds timeout_seconds =
         chrono::duration_cast<chrono::seconds>(timeout);
diff --git a/aos/config.bzl b/aos/config.bzl
new file mode 100644
index 0000000..3f78422
--- /dev/null
+++ b/aos/config.bzl
@@ -0,0 +1,60 @@
+load("//tools/build_rules:label.bzl", "expand_label")
+
+AosConfigInfo = provider(fields = ["transitive_flatbuffers", "transitive_src"])
+
+def aos_config(name, src, flatbuffers, deps = [], visibility = None):
+    _aos_config(
+        name = name,
+        src = src,
+        deps = deps,
+        flatbuffers = [expand_label(flatbuffer) + "_reflection_out" for flatbuffer in flatbuffers],
+        visibility = visibility,
+    )
+
+def _aos_config_impl(ctx):
+    flatbuffers_depset = depset(
+        ctx.files.flatbuffers,
+        transitive = [dep[AosConfigInfo].transitive_flatbuffers for dep in ctx.attr.deps],
+    )
+
+    src_depset = depset(
+        ctx.files.src,
+        transitive = [dep[AosConfigInfo].transitive_src for dep in ctx.attr.deps],
+    )
+
+    all_files = flatbuffers_depset.to_list() + src_depset.to_list()
+    ctx.actions.run(
+        outputs = [ctx.outputs.config],
+        inputs = all_files,
+        arguments = [ctx.outputs.config.path, ctx.files.src[0].path] + [f.path for f in flatbuffers_depset.to_list()],
+        progress_message = "Flattening config",
+        executable = ctx.executable._config_flattener,
+    )
+    return AosConfigInfo(
+        transitive_flatbuffers = flatbuffers_depset,
+        transitive_src = src_depset,
+    )
+
+_aos_config = rule(
+    attrs = {
+        "_config_flattener": attr.label(
+            executable = True,
+            cfg = "host",
+            default = Label("//aos:config_flattener"),
+        ),
+        "src": attr.label(
+            mandatory = True,
+            allow_files = True,
+        ),
+        "deps": attr.label_list(
+            providers = [AosConfigInfo],
+        ),
+        "flatbuffers": attr.label_list(
+            mandatory = False,
+        ),
+    },
+    outputs = {
+        "config": "%{name}.json",
+    },
+    implementation = _aos_config_impl,
+)
diff --git a/aos/config/10-net-eth0.rules b/aos/config/10-net-eth0.rules
deleted file mode 100644
index 0d8d807..0000000
--- a/aos/config/10-net-eth0.rules
+++ /dev/null
@@ -1,6 +0,0 @@
-# This is a file that will make any NIC eth0.
-# It prevents the persistent net rules generator from running because that ends
-# up naming the 1 NIC eth1 instead of when you move a disk between boxes.
-# Put it in /etc/udev/rules.d/ to use it.
-
-SUBSYSTEM=="net", ACTION=="add", ATTR{type}=="1", KERNEL=="eth*", NAME="eth0"
diff --git a/aos/config/BUILD b/aos/config/BUILD
deleted file mode 100644
index 07394d4..0000000
--- a/aos/config/BUILD
+++ /dev/null
@@ -1,14 +0,0 @@
-filegroup(
-  name = 'rio_robotCommand',
-  srcs = [ 'robotCommand' ],
-)
-
-sh_binary(
-  name = 'setup_roborio',
-  srcs = [ 'setup_roborio.sh' ],
-  visibility = [ '//visibility:public' ],
-  data = [
-    ':rio_robotCommand',
-    '@arm_frc_linux_gnueabi_repo//:compiler_pieces',
-  ],
-)
diff --git a/aos/config/aos.conf b/aos/config/aos.conf
deleted file mode 100644
index bda250f..0000000
--- a/aos/config/aos.conf
+++ /dev/null
@@ -1,6 +0,0 @@
-# put this file in /etc/security/limits.d/ to make it work
-# you have to create a group named aos (groupadd aos) and then add anybody you want to it (vim /etc/group)
-# See limits.conf(5) for details.
-
-@aos hard memlock unlimited
-@aos hard rtprio 40
diff --git a/aos/config/robotCommand b/aos/config/robotCommand
deleted file mode 100755
index 7b726a7..0000000
--- a/aos/config/robotCommand
+++ /dev/null
@@ -1 +0,0 @@
-/home/admin/robot_code/starter.sh
diff --git a/aos/config/setup_roborio.sh b/aos/config/setup_roborio.sh
deleted file mode 100755
index 70c4a73..0000000
--- a/aos/config/setup_roborio.sh
+++ /dev/null
@@ -1,41 +0,0 @@
-#!/bin/bash
-#
-# Note: this should be run from within bazel
-
-set -Eeuo pipefail
-
-if [ $# != 1 ];
-then
-  echo "# setup_robot.sh is used to configure a newly flashed roboRIO"
-  echo ""
-  echo "Usage: setup_roborio.sh 10.9.71.2"
-  echo ""
-  echo "# or if that does not work, try"
-  echo ""
-  echo "Usage: setup_roborio.sh roboRIO-971-frc.local"
-  exit 1
-fi
-
-readonly ROBOT_HOSTNAME="$1"
-
-echo "Looking to see if l is aliased right."
-
-if ! HAS_ALIAS=$(ssh "admin@${ROBOT_HOSTNAME}" "cat /etc/profile"); then
-  echo "ssh command failed remotely"
-  exit 1
-elif echo "${HAS_ALIAS}" | grep -Fq "alias l"; then
-  echo "Already has l alias"
-else
-  echo "Adding l alias"
-  ssh "admin@${ROBOT_HOSTNAME}" 'echo "alias l=\"ls -la\"" >> /etc/profile'
-  echo "Adding symbolic link to loging directory"
-  ssh "admin@${ROBOT_HOSTNAME}" ln -s /media/sda1 logs
-  ssh "admin@${ROBOT_HOSTNAME}" mkdir robot_code
-  ssh "admin@${ROBOT_HOSTNAME}" ln -s /media/sda1/aos_log-current robot_code/aos_log-current
-fi
-
-# This fails if the code isn't running.
-ssh "admin@${ROBOT_HOSTNAME}" 'PATH="${PATH}":/usr/local/natinst/bin/ /usr/local/frc/bin/frcKillRobot.sh -r -t' || true
-
-echo "Deploying robotCommand startup script"
-scp aos/config/robotCommand "admin@${ROBOT_HOSTNAME}:/home/lvuser/"
diff --git a/aos/config/setup_rt_caps.sh b/aos/config/setup_rt_caps.sh
deleted file mode 100755
index 1ba4f65..0000000
--- a/aos/config/setup_rt_caps.sh
+++ /dev/null
@@ -1,8 +0,0 @@
-#!/bin/bash
-
-# Sets capabilities on a binary so it can run as realtime code as a user who
-# doesn't have those rlimits or some other reason they can.
-# Has to be run as root.
-
-setcap 'CAP_IPC_LOCK+pie CAP_SYS_NICE+pie' $0
-
diff --git a/aos/config_flattener.cc b/aos/config_flattener.cc
new file mode 100644
index 0000000..71cda32
--- /dev/null
+++ b/aos/config_flattener.cc
@@ -0,0 +1,41 @@
+#include <string>
+#include <vector>
+
+#include "aos/configuration.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/util/file.h"
+#include "gflags/gflags.h"
+#include "glog/logging.h"
+
+namespace aos {
+
+int Main(int argc, char **argv) {
+  CHECK_GE(argc, 3) << ": Too few arguments";
+
+  VLOG(1) << "Reading " << argv[2];
+  FlatbufferDetachedBuffer<Configuration> config =
+      configuration::ReadConfig(argv[2]);
+
+  std::vector<aos::FlatbufferString<reflection::Schema>> schemas;
+
+  for (int i = 3; i < argc; ++i) {
+    schemas.emplace_back(util::ReadFileToStringOrDie(argv[i]));
+  }
+
+  const std::string merged_config = FlatbufferToJson(
+      &configuration::MergeConfiguration(config, schemas).message(), true);
+
+  // TODO(austin): Figure out how to squash the schemas onto 1 line so it is
+  // easier to read?
+  VLOG(1) << "Flattened config is " << merged_config;
+  util::WriteStringToFileOrDie(argv[1], merged_config);
+  return 0;
+}
+
+}  // namespace aos
+
+int main(int argc, char **argv) {
+  aos::InitGoogle(&argc, &argv);
+  return aos::Main(argc, argv);
+}
diff --git a/aos/configuration.cc b/aos/configuration.cc
index cd92f20..bcb67ba 100644
--- a/aos/configuration.cc
+++ b/aos/configuration.cc
@@ -22,11 +22,6 @@
 
 // Define the compare and equal operators for Channel and Application so we can
 // insert them in the btree below.
-//
-// These are not in headers because they are only comparing part of the
-// flatbuffer, and it seems weird to expose that as *the* compare operator.  And
-// I can't put them in an anonymous namespace because they wouldn't be found
-// that way by the btree.
 bool operator<(const FlatbufferDetachedBuffer<Channel> &lhs,
                const FlatbufferDetachedBuffer<Channel> &rhs) {
   int name_compare = lhs.message().name()->string_view().compare(
@@ -154,8 +149,12 @@
 
 FlatbufferDetachedBuffer<Configuration> ReadConfig(
     const absl::string_view path, absl::btree_set<std::string> *visited_paths) {
-  FlatbufferDetachedBuffer<Configuration> config(JsonToFlatbuffer(
-      util::ReadFileToStringOrDie(path), ConfigurationTypeTable()));
+  flatbuffers::DetachedBuffer buffer = JsonToFlatbuffer(
+      util::ReadFileToStringOrDie(path), ConfigurationTypeTable());
+
+  CHECK_GT(buffer.size(), 0u) << ": Failed to parse JSON file";
+
+  FlatbufferDetachedBuffer<Configuration> config(std::move(buffer));
   // Depth first.  Take the following example:
   //
   // config1.json:
@@ -222,7 +221,54 @@
   return config;
 }
 
-// Remove duplicate entries, and handle overrides.
+// Compares (c < p) a channel, and a name, type tuple.
+bool CompareChannels(const Channel *c,
+                     ::std::pair<absl::string_view, absl::string_view> p) {
+  int name_compare = c->name()->string_view().compare(p.first);
+  if (name_compare == 0) {
+    return c->type()->string_view() < p.second;
+  } else if (name_compare < 0) {
+    return true;
+  } else {
+    return false;
+  }
+};
+
+// Compares for equality (c == p) a channel, and a name, type tuple.
+bool EqualsChannels(const Channel *c,
+                     ::std::pair<absl::string_view, absl::string_view> p) {
+  return c->name()->string_view() == p.first &&
+         c->type()->string_view() == p.second;
+}
+
+// Compares (c < p) an application, and a name;
+bool CompareApplications(const Application *a, absl::string_view name) {
+  return a->name()->string_view() < name;
+};
+
+// Compares for equality (c == p) an application, and a name;
+bool EqualsApplications(const Application *a, absl::string_view name) {
+  return a->name()->string_view() == name;
+}
+
+// Maps name for the provided maps.  Modifies name.
+void HandleMaps(const flatbuffers::Vector<flatbuffers::Offset<aos::Map>> *maps,
+                absl::string_view *name) {
+  // For the same reason we merge configs in reverse order, we want to process
+  // maps in reverse order.  That lets the outer config overwrite channels from
+  // the inner configs.
+  for (auto i = maps->rbegin(); i != maps->rend(); ++i) {
+    if (i->has_match() && i->match()->has_name() && i->has_rename() &&
+        i->rename()->has_name() && i->match()->name()->string_view() == *name) {
+      VLOG(1) << "Renamed \"" << *name << "\" to \""
+              << i->rename()->name()->string_view() << "\"";
+      *name = i->rename()->name()->string_view();
+    }
+  }
+}
+
+}  // namespace
+
 FlatbufferDetachedBuffer<Configuration> MergeConfiguration(
     const Flatbuffer<Configuration> &config) {
   // Store all the channels in a sorted set.  This lets us track channels we
@@ -316,54 +362,6 @@
   return fbb.Release();
 }
 
-// Compares (c < p) a channel, and a name, type tuple.
-bool CompareChannels(const Channel *c,
-                     ::std::pair<absl::string_view, absl::string_view> p) {
-  int name_compare = c->name()->string_view().compare(p.first);
-  if (name_compare == 0) {
-    return c->type()->string_view() < p.second;
-  } else if (name_compare < 0) {
-    return true;
-  } else {
-    return false;
-  }
-};
-
-// Compares for equality (c == p) a channel, and a name, type tuple.
-bool EqualsChannels(const Channel *c,
-                     ::std::pair<absl::string_view, absl::string_view> p) {
-  return c->name()->string_view() == p.first &&
-         c->type()->string_view() == p.second;
-}
-
-// Compares (c < p) an application, and a name;
-bool CompareApplications(const Application *a, absl::string_view name) {
-  return a->name()->string_view() < name;
-};
-
-// Compares for equality (c == p) an application, and a name;
-bool EqualsApplications(const Application *a, absl::string_view name) {
-  return a->name()->string_view() == name;
-}
-
-// Maps name for the provided maps.  Modifies name.
-void HandleMaps(const flatbuffers::Vector<flatbuffers::Offset<aos::Map>> *maps,
-                absl::string_view *name) {
-  // For the same reason we merge configs in reverse order, we want to process
-  // maps in reverse order.  That lets the outer config overwrite channels from
-  // the inner configs.
-  for (auto i = maps->rbegin(); i != maps->rend(); ++i) {
-    if (i->has_match() && i->match()->has_name() && i->has_rename() &&
-        i->rename()->has_name() && i->match()->name()->string_view() == *name) {
-      VLOG(1) << "Renamed \"" << *name << "\" to \""
-              << i->rename()->name()->string_view() << "\"";
-      *name = i->rename()->name()->string_view();
-    }
-  }
-}
-
-}  // namespace
-
 const char *GetRootDirectory() {
   static  char* root_dir;// return value
   static absl::once_flag once_;
@@ -417,6 +415,9 @@
     HandleMaps(config->maps(), &name);
   }
 
+  VLOG(1) << "Acutally looking up { \"name\": \"" << name << "\", \"type\": \""
+          << type << "\" }";
+
   // Then look for the channel.
   auto channel_iterator =
       std::lower_bound(config->channels()->cbegin(),
@@ -435,5 +436,96 @@
   }
 }
 
+FlatbufferDetachedBuffer<Configuration> MergeConfiguration(
+    const Flatbuffer<Configuration> &config,
+    const std::vector<aos::FlatbufferString<reflection::Schema>> &schemas) {
+  flatbuffers::FlatBufferBuilder fbb;
+  fbb.ForceDefaults(1);
+
+  flatbuffers::Offset<flatbuffers::Vector<flatbuffers::Offset<Channel>>>
+      channels_offset;
+  if (config.message().has_channels()) {
+    std::vector<flatbuffers::Offset<Channel>> channel_offsets;
+    for (const Channel *c : *config.message().channels()) {
+      flatbuffers::FlatBufferBuilder channel_fbb;
+      channel_fbb.ForceDefaults(1);
+
+      // Search for a schema with a matching type.
+      const aos::FlatbufferString<reflection::Schema> *found_schema = nullptr;
+      for (const aos::FlatbufferString<reflection::Schema> &schema: schemas) {
+        if (schema.message().root_table() != nullptr) {
+          if (schema.message().root_table()->name()->string_view() ==
+              c->type()->string_view()) {
+            found_schema = &schema;
+          }
+        }
+      }
+
+      CHECK(found_schema != nullptr)
+          << ": Failed to find schema for " << FlatbufferToJson(c);
+
+      // The following is wasteful, but works.
+      //
+      // Copy it into a Channel object by creating an object with only the
+      // schema populated and merge that into the current channel.
+      flatbuffers::Offset<reflection::Schema> schema_offset =
+          CopyFlatBuffer<reflection::Schema>(&found_schema->message(),
+                                             &channel_fbb);
+      Channel::Builder channel_builder(channel_fbb);
+      channel_builder.add_schema(schema_offset);
+      channel_fbb.Finish(channel_builder.Finish());
+      FlatbufferDetachedBuffer<Channel> channel_schema_flatbuffer(
+          channel_fbb.Release());
+
+      FlatbufferDetachedBuffer<Channel> merged_channel(
+          MergeFlatBuffers(channel_schema_flatbuffer, CopyFlatBuffer(c)));
+
+      channel_offsets.emplace_back(
+          CopyFlatBuffer<Channel>(&merged_channel.message(), &fbb));
+    }
+    channels_offset = fbb.CreateVector(channel_offsets);
+  }
+
+  // Copy the applications and maps unmodified.
+  flatbuffers::Offset<flatbuffers::Vector<flatbuffers::Offset<Application>>>
+      applications_offset;
+  {
+    ::std::vector<flatbuffers::Offset<Application>> applications_offsets;
+    if (config.message().has_applications()) {
+      for (const Application *a : *config.message().applications()) {
+        applications_offsets.emplace_back(CopyFlatBuffer<Application>(a, &fbb));
+      }
+    }
+    applications_offset = fbb.CreateVector(applications_offsets);
+  }
+
+  flatbuffers::Offset<flatbuffers::Vector<flatbuffers::Offset<Map>>>
+      maps_offset;
+  {
+    ::std::vector<flatbuffers::Offset<Map>> map_offsets;
+    if (config.message().has_maps()) {
+      for (const Map *m : *config.message().maps()) {
+        map_offsets.emplace_back(CopyFlatBuffer<Map>(m, &fbb));
+      }
+      maps_offset = fbb.CreateVector(map_offsets);
+    }
+  }
+
+  // Now insert eerything else in unmodified.
+  ConfigurationBuilder configuration_builder(fbb);
+  if (config.message().has_channels()) {
+    configuration_builder.add_channels(channels_offset);
+  }
+  if (config.message().has_maps()) {
+    configuration_builder.add_maps(maps_offset);
+  }
+  if (config.message().has_applications()) {
+    configuration_builder.add_applications(applications_offset);
+  }
+
+  fbb.Finish(configuration_builder.Finish());
+  return fbb.Release();
+}
+
 }  // namespace configuration
 }  // namespace aos
diff --git a/aos/configuration.fbs b/aos/configuration.fbs
index d23c4b9..a5cb59f 100644
--- a/aos/configuration.fbs
+++ b/aos/configuration.fbs
@@ -1,3 +1,5 @@
+include "reflection/reflection.fbs";
+
 namespace aos;
 
 // Table representing a channel.  Channels are where data is published and
@@ -12,6 +14,9 @@
   // Max size of the data being published.  (This will be automatically
   // computed in the future.)
   max_size:int = 1000;
+
+  // The schema for the data sent on this channel.
+  schema:reflection.Schema;
 }
 
 // Table to support renaming channel names.
diff --git a/aos/configuration.h b/aos/configuration.h
index 3cee8e7..e777f41 100644
--- a/aos/configuration.h
+++ b/aos/configuration.h
@@ -21,6 +21,16 @@
 FlatbufferDetachedBuffer<Configuration> ReadConfig(
     const absl::string_view path);
 
+// Sorts and merges entries in a config.
+FlatbufferDetachedBuffer<Configuration> MergeConfiguration(
+    const Flatbuffer<Configuration> &config);
+
+// Adds schema definitions to a sorted and merged config from the provided
+// schema list.
+FlatbufferDetachedBuffer<Configuration> MergeConfiguration(
+    const Flatbuffer<Configuration> &config,
+    const std::vector<aos::FlatbufferString<reflection::Schema>> &schemas);
+
 // Returns the resolved location for a name, type, and application name. Returns
 // nullptr if none is found.
 //
@@ -37,6 +47,8 @@
   return GetChannel(&config.message(), name, type, application_name);
 }
 
+// TODO(austin): GetSchema<T>(const Flatbuffer<Configuration> &config);
+
 // Returns "our" IP address.
 const in_addr &GetOwnIPAddress();
 
@@ -51,6 +63,13 @@
 const char *GetLoggingDirectory();
 
 }  // namespace configuration
+
+// Compare and equality operators for Channel.  Note: these only check the name
+// and type for equality.
+bool operator<(const FlatbufferDetachedBuffer<Channel> &lhs,
+               const FlatbufferDetachedBuffer<Channel> &rhs);
+bool operator==(const FlatbufferDetachedBuffer<Channel> &lhs,
+                const FlatbufferDetachedBuffer<Channel> &rhs);
 }  // namespace aos
 
 #endif  // AOS_CONFIGURATION_H_
diff --git a/aos/configuration_test.cc b/aos/configuration_test.cc
index 0f13041..e20b308 100644
--- a/aos/configuration_test.cc
+++ b/aos/configuration_test.cc
@@ -4,6 +4,8 @@
 #include "aos/json_to_flatbuffer.h"
 #include "aos/testing/test_logging.h"
 #include "aos/util/file.h"
+#include "flatbuffers/reflection.h"
+#include "glog/logging.h"
 #include "gtest/gtest.h"
 
 namespace aos {
@@ -25,7 +27,7 @@
 TEST_F(ConfigurationTest, ConfigMerge) {
   FlatbufferDetachedBuffer<Configuration> config =
       ReadConfig("aos/testdata/config1.json");
-  printf("Read: %s\n", FlatbufferToJson(config, true).c_str());
+  LOG(INFO) << "Read: " << FlatbufferToJson(config, true);
 
   EXPECT_EQ(
       absl::StripSuffix(
@@ -33,6 +35,19 @@
       FlatbufferToJson(config, true));
 }
 
+// Tests that we sort the entries in a config so we can look entries up.
+TEST_F(ConfigurationTest, UnsortedConfig) {
+  FlatbufferDetachedBuffer<Configuration> config =
+      ReadConfig("aos/testdata/backwards.json");
+
+  LOG(INFO) << "Read: " << FlatbufferToJson(config, true);
+
+  EXPECT_EQ(FlatbufferToJson(GetChannel(config, ".aos.robot_state",
+                                        "aos.RobotState", "app1")),
+            "{ \"name\": \".aos.robot_state\", \"type\": \"aos.RobotState\", "
+            "\"max_size\": 5 }");
+}
+
 // Tests that we die when a file is imported twice.
 TEST_F(ConfigurationDeathTest, DuplicateFile) {
   EXPECT_DEATH(
diff --git a/aos/controls/BUILD b/aos/controls/BUILD
index a612ecb..c45a345 100644
--- a/aos/controls/BUILD
+++ b/aos/controls/BUILD
@@ -1,23 +1,9 @@
 package(default_visibility = ["//visibility:public"])
 
-load("//aos/build:queues.bzl", "queue_library")
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
 load("//tools:environments.bzl", "mcu_cpus")
 
 cc_library(
-    name = "replay_control_loop",
-    hdrs = [
-        "replay_control_loop.h",
-    ],
-    deps = [
-        ":control_loop",
-        "//aos:queues",
-        "//aos/logging:queue_logging",
-        "//aos/logging:replay",
-        "//aos/time",
-    ],
-)
-
-cc_library(
     name = "control_loop_test",
     testonly = True,
     srcs = [
@@ -27,11 +13,13 @@
         "control_loop_test.h",
     ],
     deps = [
+        "//aos:flatbuffers",
+        "//aos:json_to_flatbuffer",
         "//aos/events:simulated_event_loop",
-        "//aos/logging:queue_logging",
-        "//aos/robot_state",
+        "//aos/robot_state:joystick_state_fbs",
+        "//aos/robot_state:robot_state_fbs",
         "//aos/testing:googletest",
-        "//aos/testing:test_shm",
+        "//aos/testing:test_logging",
         "//aos/time",
     ],
 )
@@ -43,7 +31,7 @@
     ],
     restricted_to = mcu_cpus,
     deps = [
-        "//third_party/eigen",
+        "@org_tuxfamily_eigen//:eigen",
     ],
 )
 
@@ -54,9 +42,9 @@
     ],
     deps = [
         "//aos/logging",
-        "//aos/logging:matrix_logging",
         "//third_party/cddlib",
-        "//third_party/eigen",
+        "@com_github_google_glog//:glog",
+        "@org_tuxfamily_eigen//:eigen",
     ],
 )
 
@@ -69,14 +57,14 @@
         ":polytope",
         "//aos/testing:googletest",
         "//aos/testing:test_logging",
-        "//third_party/eigen",
+        "@org_tuxfamily_eigen//:eigen",
     ],
 )
 
-queue_library(
-    name = "control_loop_queues",
+flatbuffer_cc_library(
+    name = "control_loop_fbs",
     srcs = [
-        "control_loops.q",
+        "control_loops.fbs",
     ],
 )
 
@@ -90,13 +78,11 @@
         "control_loop.h",
     ],
     deps = [
-        ":control_loop_queues",
-        "//aos:queues",
-        "//aos/events:event-loop",
-        "//aos/events:shm-event-loop",
+        "//aos/events:event_loop",
+        "//aos/events:shm_event_loop",
         "//aos/logging",
-        "//aos/logging:queue_logging",
-        "//aos/robot_state",
+        "//aos/robot_state:joystick_state_fbs",
+        "//aos/robot_state:robot_state_fbs",
         "//aos/time",
         "//aos/util:log_interval",
     ],
diff --git a/aos/controls/control_loop-tmpl.h b/aos/controls/control_loop-tmpl.h
index 7628c26..f937bb4 100644
--- a/aos/controls/control_loop-tmpl.h
+++ b/aos/controls/control_loop-tmpl.h
@@ -2,65 +2,63 @@
 #include <inttypes.h>
 
 #include "aos/logging/logging.h"
-#include "aos/logging/queue_logging.h"
 
 namespace aos {
 namespace controls {
 
 // TODO(aschuh): Tests.
 
-template <class T>
-constexpr ::std::chrono::milliseconds ControlLoop<T>::kStaleLogInterval;
-template <class T>
-constexpr ::std::chrono::milliseconds ControlLoop<T>::kPwmDisableTime;
+template <class GoalType, class PositionType, class StatusType,
+          class OutputType>
+constexpr ::std::chrono::milliseconds ControlLoop<
+    GoalType, PositionType, StatusType, OutputType>::kStaleLogInterval;
+template <class GoalType, class PositionType, class StatusType,
+          class OutputType>
+constexpr ::std::chrono::milliseconds ControlLoop<
+    GoalType, PositionType, StatusType, OutputType>::kPwmDisableTime;
 
-template <class T>
-void ControlLoop<T>::ZeroOutputs() {
-  typename ::aos::Sender<OutputType>::Message output =
-      output_sender_.MakeMessage();
-  Zero(output.get());
-  output.Send();
+template <class GoalType, class PositionType, class StatusType,
+          class OutputType>
+void ControlLoop<GoalType, PositionType, StatusType, OutputType>::ZeroOutputs() {
+  typename ::aos::Sender<OutputType>::Builder builder =
+      output_sender_.MakeBuilder();
+  builder.Send(Zero(&builder));
 }
 
-template <class T>
-void ControlLoop<T>::IteratePosition(const PositionType &position) {
+template <class GoalType, class PositionType, class StatusType,
+          class OutputType>
+void ControlLoop<GoalType, PositionType, StatusType,
+                 OutputType>::IteratePosition(const PositionType &position) {
   no_goal_.Print();
   no_sensor_state_.Print();
   motors_off_log_.Print();
 
-  AOS_LOG_STRUCT(DEBUG, "position", position);
-
   // Fetch the latest control loop goal. If there is no new
   // goal, we will just reuse the old one.
   goal_fetcher_.Fetch();
   const GoalType *goal = goal_fetcher_.get();
-  if (goal) {
-    AOS_LOG_STRUCT(DEBUG, "goal", *goal);
-  } else {
-    AOS_LOG_INTERVAL(no_goal_);
-  }
 
   const bool new_robot_state = robot_state_fetcher_.Fetch();
   if (!robot_state_fetcher_.get()) {
     AOS_LOG_INTERVAL(no_sensor_state_);
     return;
   }
-  if (sensor_reader_pid_ != robot_state_fetcher_->reader_pid) {
+  if (sensor_reader_pid_ != robot_state_fetcher_->reader_pid()) {
     AOS_LOG(INFO, "new sensor reader PID %" PRId32 ", old was %" PRId32 "\n",
-            robot_state_fetcher_->reader_pid, sensor_reader_pid_);
+            robot_state_fetcher_->reader_pid(), sensor_reader_pid_);
     reset_ = true;
-    sensor_reader_pid_ = robot_state_fetcher_->reader_pid;
+    sensor_reader_pid_ = robot_state_fetcher_->reader_pid();
   }
 
-  bool outputs_enabled = robot_state_fetcher_->outputs_enabled;
+  bool outputs_enabled = robot_state_fetcher_->outputs_enabled();
 
   // Check to see if we got a driver station packet recently.
   if (new_robot_state) {
-    if (robot_state_fetcher_->outputs_enabled) {
+    if (robot_state_fetcher_->outputs_enabled()) {
       // If the driver's station reports being disabled, we're probably not
       // actually going to send motor values regardless of what the FPGA
       // reports.
-      last_pwm_sent_ = robot_state_fetcher_->sent_time;
+      last_pwm_sent_ = robot_state_fetcher_.context().monotonic_sent_time;
     }
   }
 
@@ -69,35 +67,27 @@
   const bool motors_off = monotonic_now >= kPwmDisableTime + last_pwm_sent_;
   joystick_state_fetcher_.Fetch();
   if (motors_off) {
-    if (joystick_state_fetcher_.get() && joystick_state_fetcher_->enabled) {
+    if (joystick_state_fetcher_.get() && joystick_state_fetcher_->enabled()) {
       AOS_LOG_INTERVAL(motors_off_log_);
     }
     outputs_enabled = false;
   }
 
-  typename ::aos::Sender<StatusType>::Message status =
-      status_sender_.MakeMessage();
-  if (status.get() == nullptr) {
-    return;
-  }
-
+  typename ::aos::Sender<StatusType>::Builder status =
+      status_sender_.MakeBuilder();
   if (outputs_enabled) {
-    typename ::aos::Sender<OutputType>::Message output =
-        output_sender_.MakeMessage();
-    RunIteration(goal, &position, output.get(), status.get());
+    typename ::aos::Sender<OutputType>::Builder output =
+        output_sender_.MakeBuilder();
+    RunIteration(goal, &position, &output, &status);
 
-    output->SetTimeToNow();
-    AOS_LOG_STRUCT(DEBUG, "output", *output);
-    output.Send();
+    output.CheckSent();
   } else {
     // The outputs are disabled, so pass nullptr in for the output.
-    RunIteration(goal, &position, nullptr, status.get());
+    RunIteration(goal, &position, nullptr, &status);
     ZeroOutputs();
   }
 
-  status->SetTimeToNow();
-  AOS_LOG_STRUCT(DEBUG, "status", *status);
-  status.Send();
+  status.CheckSent();
 }
 
 }  // namespace controls
diff --git a/aos/controls/control_loop.h b/aos/controls/control_loop.h
index fe72022..6f1b487 100644
--- a/aos/controls/control_loop.h
+++ b/aos/controls/control_loop.h
@@ -4,10 +4,9 @@
 #include <string.h>
 #include <atomic>
 
-#include "aos/events/event-loop.h"
-#include "aos/events/shm-event-loop.h"
-#include "aos/queue.h"
-#include "aos/robot_state/robot_state.q.h"
+#include "aos/events/event_loop.h"
+#include "aos/robot_state/joystick_state_generated.h"
+#include "aos/robot_state/robot_state_generated.h"
 #include "aos/time/time.h"
 #include "aos/type_traits/type_traits.h"
 #include "aos/util/log_interval.h"
@@ -20,39 +19,24 @@
     ::std::chrono::milliseconds(5);
 
 // Provides helper methods to assist in writing control loops.
-// This template expects to be constructed with a queue group as an argument
-// that has a goal, position, status, and output queue.
 // It will then call the RunIteration method every cycle that it has enough
 // valid data for the control loop to run.
-template <class T>
+template <class GoalType, class PositionType, class StatusType,
+          class OutputType>
 class ControlLoop {
  public:
-  // Create some convenient typedefs to reference the Goal, Position, Status,
-  // and Output structures.
-  typedef typename std::remove_reference<decltype(
-      *(static_cast<T *>(NULL)->goal.MakeMessage().get()))>::type GoalType;
-  typedef typename std::remove_reference<
-      decltype(*(static_cast<T *>(NULL)->position.MakeMessage().get()))>::type
-      PositionType;
-  typedef typename std::remove_reference<decltype(
-      *(static_cast<T *>(NULL)->status.MakeMessage().get()))>::type StatusType;
-  typedef typename std::remove_reference<decltype(
-      *(static_cast<T *>(NULL)->output.MakeMessage().get()))>::type OutputType;
-
   ControlLoop(EventLoop *event_loop, const ::std::string &name)
       : event_loop_(event_loop), name_(name) {
-    output_sender_ = event_loop_->MakeSender<OutputType>(name_ + ".output");
-    status_sender_ = event_loop_->MakeSender<StatusType>(name_ + ".status");
-    goal_fetcher_ = event_loop_->MakeFetcher<GoalType>(name_ + ".goal");
-    robot_state_fetcher_ =
-        event_loop_->MakeFetcher<::aos::RobotState>(".aos.robot_state");
+    output_sender_ = event_loop_->MakeSender<OutputType>(name_);
+    status_sender_ = event_loop_->MakeSender<StatusType>(name_);
+    goal_fetcher_ = event_loop_->MakeFetcher<GoalType>(name_);
+    robot_state_fetcher_ = event_loop_->MakeFetcher<::aos::RobotState>("/aos");
     joystick_state_fetcher_ =
-        event_loop_->MakeFetcher<::aos::JoystickState>(".aos.joystick_state");
+        event_loop_->MakeFetcher<::aos::JoystickState>("/aos");
 
-    event_loop_->MakeWatcher(name_ + ".position",
-                             [this](const PositionType &position) {
-                               this->IteratePosition(position);
-                             });
+    event_loop_->MakeWatcher(name_, [this](const PositionType &position) {
+      this->IteratePosition(position);
+    });
   }
 
   const ::aos::RobotState &robot_state() const { return *robot_state_fetcher_; }
@@ -80,7 +64,10 @@
   // Sets the output to zero.
   // Override this if a value of zero (or false) is not "off" for this
   // subsystem.
-  virtual void Zero(OutputType *output) { output->Zero(); }
+  virtual flatbuffers::Offset<OutputType> Zero(
+      typename ::aos::Sender<OutputType>::Builder *builder) {
+    return builder->template MakeBuilder<OutputType>().Finish();
+  }
 
  protected:
   // Runs one cycle of the loop.
@@ -88,6 +75,10 @@
 
   EventLoop *event_loop() { return event_loop_; }
 
+  // Returns the position context.  This is only valid inside the RunIteration
+  // method.
+  const aos::Context &position_context() { return event_loop_->context(); }
+
   // Runs an iteration of the control loop.
   // goal is the last goal that was sent.  It might be any number of cycles old
   // or nullptr if we haven't ever received a goal.
@@ -97,8 +88,10 @@
   // output is going to be ignored and set to 0.
   // status is the status of the control loop.
   // Both output and status should be filled in by the implementation.
-  virtual void RunIteration(const GoalType *goal, const PositionType *position,
-                            OutputType *output, StatusType *status) = 0;
+  virtual void RunIteration(
+      const GoalType *goal, const PositionType *position,
+      typename ::aos::Sender<OutputType>::Builder *output,
+      typename ::aos::Sender<StatusType>::Builder *status) = 0;
 
  private:
   static constexpr ::std::chrono::milliseconds kStaleLogInterval =
diff --git a/aos/controls/control_loop_test.h b/aos/controls/control_loop_test.h
index ff11987..b8ebc67 100644
--- a/aos/controls/control_loop_test.h
+++ b/aos/controls/control_loop_test.h
@@ -5,10 +5,12 @@
 
 #include "gtest/gtest.h"
 
-#include "aos/events/simulated-event-loop.h"
-#include "aos/logging/queue_logging.h"
-#include "aos/robot_state/robot_state.q.h"
-#include "aos/testing/test_shm.h"
+#include "aos/events/simulated_event_loop.h"
+#include "aos/flatbuffers.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/robot_state/joystick_state_generated.h"
+#include "aos/robot_state/robot_state_generated.h"
+#include "aos/testing/test_logging.h"
 #include "aos/time/time.h"
 
 namespace aos {
@@ -22,14 +24,28 @@
 template <typename TestBaseClass>
 class ControlLoopTestTemplated : public TestBaseClass {
  public:
-  ControlLoopTestTemplated(::std::chrono::nanoseconds dt = kTimeTick)
-      : dt_(dt), robot_status_event_loop_(MakeEventLoop()) {
+  // Builds a control loop test with the provided configuration.  Note: this
+  // merges and sorts the config to reduce user errors.
+  ControlLoopTestTemplated(absl::string_view configuration,
+                           ::std::chrono::nanoseconds dt = kTimeTick)
+      : ControlLoopTestTemplated(
+            configuration::MergeConfiguration(
+                aos::FlatbufferDetachedBuffer<Configuration>(JsonToFlatbuffer(
+                    configuration, Configuration::MiniReflectTypeTable()))),
+            dt) {}
+
+  ControlLoopTestTemplated(
+      FlatbufferDetachedBuffer<Configuration> configuration,
+      ::std::chrono::nanoseconds dt = kTimeTick)
+      : configuration_(std::move(configuration)),
+        event_loop_factory_(&configuration_.message()),
+        dt_(dt),
+        robot_status_event_loop_(MakeEventLoop()) {
+    testing::EnableTestLogging();
     robot_state_sender_ =
-        robot_status_event_loop_->MakeSender<::aos::RobotState>(
-            ".aos.robot_state");
+        robot_status_event_loop_->MakeSender<::aos::RobotState>("/aos");
     joystick_state_sender_ =
-        robot_status_event_loop_->MakeSender<::aos::JoystickState>(
-            ".aos.joystick_state");
+        robot_status_event_loop_->MakeSender<::aos::JoystickState>("/aos");
 
     // Schedule the robot status send 1 nanosecond before the loop runs.
     send_robot_state_phased_loop_ = robot_status_event_loop_->AddPhasedLoop(
@@ -91,15 +107,17 @@
   void SendJoystickState() {
     if (monotonic_now() >= kDSPacketTime + last_ds_time_ ||
         last_enabled_ != enabled_) {
-      auto new_state = joystick_state_sender_.MakeMessage();
-      new_state->fake = true;
+      auto new_state = joystick_state_sender_.MakeBuilder();
+      ::aos::JoystickState::Builder builder =
+          new_state.template MakeBuilder<::aos::JoystickState>();
 
-      new_state->enabled = enabled_;
-      new_state->autonomous = false;
-      new_state->team_id = team_id_;
+      builder.add_fake(true);
 
-      AOS_LOG_STRUCT(INFO, "joystick_state", *new_state);
-      new_state.Send();
+      builder.add_enabled(enabled_);
+      builder.add_autonomous(false);
+      builder.add_team_id(team_id_);
+
+      new_state.Send(builder.Finish());
 
       last_ds_time_ = monotonic_now();
       last_enabled_ = enabled_;
@@ -109,31 +127,35 @@
   bool last_enabled_ = false;
 
   void SendRobotState() {
-    auto new_state = robot_state_sender_.MakeMessage();
+    auto new_state = robot_state_sender_.MakeBuilder();
 
-    new_state->reader_pid = reader_pid_;
-    new_state->outputs_enabled = enabled_;
-    new_state->browned_out = false;
+    ::aos::RobotState::Builder builder =
+        new_state.template MakeBuilder<::aos::RobotState>();
 
-    new_state->is_3v3_active = true;
-    new_state->is_5v_active = true;
-    new_state->voltage_3v3 = 3.3;
-    new_state->voltage_5v = 5.0;
+    builder.add_reader_pid(reader_pid_);
+    builder.add_outputs_enabled(enabled_);
+    builder.add_browned_out(false);
 
-    new_state->voltage_roborio_in = battery_voltage_;
-    new_state->voltage_battery = battery_voltage_;
+    builder.add_is_3v3_active(true);
+    builder.add_is_5v_active(true);
+    builder.add_voltage_3v3(3.3);
+    builder.add_voltage_5v(5.0);
 
-    AOS_LOG_STRUCT(INFO, "robot_state", *new_state);
-    new_state.Send();
+    builder.add_voltage_roborio_in(battery_voltage_);
+    builder.add_voltage_battery(battery_voltage_);
+
+    new_state.Send(builder.Finish());
   }
 
   static constexpr ::std::chrono::microseconds kTimeTick{5000};
   static constexpr ::std::chrono::milliseconds kDSPacketTime{20};
 
-  const ::std::chrono::nanoseconds dt_;
+  FlatbufferDetachedBuffer<Configuration> configuration_;
 
   SimulatedEventLoopFactory event_loop_factory_;
 
+  const ::std::chrono::nanoseconds dt_;
+
   uint16_t team_id_ = 971;
   int32_t reader_pid_ = 1;
   double battery_voltage_ = 12.4;
diff --git a/aos/controls/control_loops.fbs b/aos/controls/control_loops.fbs
new file mode 100644
index 0000000..8456bfa
--- /dev/null
+++ b/aos/controls/control_loops.fbs
@@ -0,0 +1,24 @@
+namespace aos.control_loops;
+// This file defines basic messages for a Single Input Single Output (SISO)
+// control loop.
+
+table Goal {
+  goal:double;
+}
+
+table Position {
+  position:double;
+}
+
+table Output {
+  voltage:double;
+}
+
+table Status {
+  done:bool;
+}
+
+root_type Goal;
+root_type Position;
+root_type Output;
+root_type Status;
diff --git a/aos/controls/control_loops.q b/aos/controls/control_loops.q
deleted file mode 100644
index 2b0bfb1..0000000
--- a/aos/controls/control_loops.q
+++ /dev/null
@@ -1,34 +0,0 @@
-package aos.control_loops;
-
-interface ControlLoop {
-  queue goal;
-  queue position;
-  queue output;
-  queue status;
-};
-
-message Goal {
-  double goal;
-};
-
-message Position {
-  double position;
-};
-
-message Output {
-  double voltage;
-};
-
-message Status {
-  bool done;
-};
-
-// Single Input Single Output control loop.
-queue_group SISO {
-  implements ControlLoop;
-
-  queue Goal goal;
-  queue Position position;
-  queue Output output;
-  queue Status status;
-};
diff --git a/aos/controls/polytope.h b/aos/controls/polytope.h
index 5248ea3..c63166f 100644
--- a/aos/controls/polytope.h
+++ b/aos/controls/polytope.h
@@ -7,8 +7,7 @@
 #include "third_party/cddlib/lib-src/setoper.h"
 #include "third_party/cddlib/lib-src/cdd.h"
 
-#include "aos/logging/logging.h"
-#include "aos/logging/matrix_logging.h"
+#include "glog/logging.h"
 #endif  // __linux__
 
 namespace aos {
@@ -191,9 +190,9 @@
   if (error != dd_NoError || polyhedra == NULL) {
     dd_WriteErrorMessages(stderr, error);
     dd_FreeMatrix(matrix);
-    AOS_LOG_MATRIX(ERROR, "bad H", H);
-    AOS_LOG_MATRIX(ERROR, "bad k_", k);
-    AOS_LOG(FATAL, "dd_DDMatrix2Poly failed\n");
+    LOG(ERROR) << "bad H" << H;
+    LOG(ERROR) << "bad k_" << k;
+    LOG(FATAL) << "dd_DDMatrix2Poly failed";
   }
 
   dd_MatrixPtr vertex_matrix = dd_CopyGenerators(polyhedra);
@@ -209,7 +208,7 @@
   }
 
   // Rays are unsupported right now.  This may change in the future.
-  AOS_CHECK_EQ(0, num_rays);
+  CHECK_EQ(0, num_rays);
 
   Eigen::Matrix<double, number_of_dimensions, Eigen::Dynamic> vertices(
       number_of_dimensions, num_vertices);
diff --git a/aos/controls/replay_control_loop.h b/aos/controls/replay_control_loop.h
deleted file mode 100644
index 23593ab..0000000
--- a/aos/controls/replay_control_loop.h
+++ /dev/null
@@ -1,195 +0,0 @@
-#ifndef AOS_CONTROLS_REPLAY_CONTROL_LOOP_H_
-#define AOS_CONTROLS_REPLAY_CONTROL_LOOP_H_
-
-#include <fcntl.h>
-
-#include "aos/queue.h"
-#include "aos/controls/control_loop.h"
-#include "aos/logging/replay.h"
-#include "aos/logging/queue_logging.h"
-#include "aos/time/time.h"
-#include "aos/macros.h"
-
-namespace aos {
-namespace controls {
-
-// Handles reading logged messages and running them through a control loop
-// again.
-// T should be a queue group suitable for use with ControlLoop.
-template <class T>
-class ControlLoopReplayer {
- public:
-  typedef typename ControlLoop<T>::GoalType GoalType;
-  typedef typename ControlLoop<T>::PositionType PositionType;
-  typedef typename ControlLoop<T>::StatusType StatusType;
-  typedef typename ControlLoop<T>::OutputType OutputType;
-
-  // loop_group is where to send the messages out.
-  // process_name is the name of the process which wrote the log messages in the
-  // file(s).
-  ControlLoopReplayer(T *loop_group, const ::std::string &process_name)
-      : loop_group_(loop_group) {
-    // Clear out any old messages which will confuse the code.
-    loop_group_->status.FetchLatest();
-    loop_group_->output.FetchLatest();
-
-    AddDirectQueueSender<::aos::JoystickState>(
-        "wpilib_interface.DSReader", "joystick_state", ".aos.joystick_state");
-    AddDirectQueueSender<::aos::RobotState>("wpilib_interface.SensorReader",
-                                            "robot_state", ".aos.robot_state");
-
-    replayer_.AddHandler(
-        process_name, "position",
-        ::std::function<void(const PositionType &)>(::std::ref(position_)));
-    replayer_.AddHandler(
-        process_name, "output",
-        ::std::function<void(const OutputType &)>(::std::ref(output_)));
-    replayer_.AddHandler(
-        process_name, "status",
-        ::std::function<void(const StatusType &)>(::std::ref(status_)));
-    // The timing of goal messages doesn't matter, and we don't need to look
-    // back at them after running the loop.
-    AddDirectQueueSender<GoalType>(
-        process_name, "goal", ::std::string(loop_group_->name()) + ".goal");
-  }
-
-  template <class QT>
-  void AddDirectQueueSender(const ::std::string &process_name,
-                            const ::std::string &log_message,
-                            const ::std::string &name) {
-    replayer_.AddDirectQueueSender<QT>(process_name, log_message, name);
-  }
-
-  // Replays messages from a file.
-  // filename can be straight from the command line; all sanity checking etc is
-  // handled by this function.
-  void ProcessFile(const char *filename);
-
- private:
-  // A message handler which saves off messages and records whether it currently
-  // has a new one or not.
-  template <class S>
-  class CaptureMessage {
-   public:
-    CaptureMessage() {}
-
-    void operator()(const S &message) {
-      AOS_CHECK(!have_new_message_);
-      saved_message_ = message;
-      have_new_message_ = true;
-    }
-
-    const S &saved_message() const { return saved_message_; }
-    bool have_new_message() const { return have_new_message_; }
-    void clear_new_message() { have_new_message_ = false; }
-
-   private:
-    S saved_message_;
-    bool have_new_message_ = false;
-
-    DISALLOW_COPY_AND_ASSIGN(CaptureMessage);
-  };
-
-  // Runs through the file currently loaded in replayer_.
-  // Returns after going through the entire file.
-  void DoProcessFile();
-
-  ::aos::ShmEventLoop event_loop_;
-
-  T *const loop_group_;
-
-  CaptureMessage<PositionType> position_;
-  CaptureMessage<OutputType> output_;
-  CaptureMessage<StatusType> status_;
-
-  // The output that the loop sends for ZeroOutputs(). It might not actually be
-  // all fields zeroed, so we pick the first one and remember it to compare.
-  CaptureMessage<OutputType> zero_output_;
-
-  ::aos::logging::linux_code::LogReplayer replayer_;
-};
-
-template <class T>
-void ControlLoopReplayer<T>::ProcessFile(const char *filename) {
-  int fd;
-  if (strcmp(filename, "-") == 0) {
-    fd = STDIN_FILENO;
-  } else {
-    fd = open(filename, O_RDONLY);
-  }
-  if (fd == -1) {
-    AOS_PLOG(FATAL, "couldn't open file '%s' for reading", filename);
-  }
-
-  replayer_.OpenFile(fd);
-  DoProcessFile();
-  replayer_.CloseCurrentFile();
-
-  AOS_PCHECK(close(fd));
-}
-
-template <class T>
-void ControlLoopReplayer<T>::DoProcessFile() {
-  while (true) {
-    // Dig through messages until we get a status, which indicates the end of
-    // the control loop cycle.
-    while (!status_.have_new_message()) {
-      if (replayer_.ProcessMessage()) return;
-    }
-
-    // Send out the position message (after adjusting the time offset) so the
-    // loop will run right now.
-    if (!position_.have_new_message()) {
-      AOS_LOG(WARNING, "don't have a new position this cycle -> skipping\n");
-      status_.clear_new_message();
-      position_.clear_new_message();
-      output_.clear_new_message();
-      continue;
-    }
-    ::aos::time::OffsetToNow(position_.saved_message().sent_time);
-    {
-      auto position_message = loop_group_->position.MakeMessage();
-      *position_message = position_.saved_message();
-      AOS_CHECK(position_message.Send());
-    }
-    position_.clear_new_message();
-
-    // Wait for the loop to finish running.
-    loop_group_->status.FetchNextBlocking();
-
-    // Point out if the status is different.
-    if (!loop_group_->status->EqualsNoTime(status_.saved_message())) {
-      AOS_LOG_STRUCT(WARNING, "expected status", status_.saved_message());
-      AOS_LOG_STRUCT(WARNING, "got status", *loop_group_->status);
-    }
-    status_.clear_new_message();
-
-    // Point out if the output is different. This is a lot more complicated than
-    // for the status because there isn't always an output logged.
-    bool loop_new_output = loop_group_->output.FetchLatest();
-    if (output_.have_new_message()) {
-      if (!loop_new_output) {
-        AOS_LOG_STRUCT(WARNING, "no output, expected", output_.saved_message());
-      } else if (!loop_group_->output->EqualsNoTime(output_.saved_message())) {
-        AOS_LOG_STRUCT(WARNING, "expected output", output_.saved_message());
-        AOS_LOG_STRUCT(WARNING, "got output", *loop_group_->output);
-      }
-    } else if (loop_new_output) {
-      if (zero_output_.have_new_message()) {
-        if (!loop_group_->output->EqualsNoTime(zero_output_.saved_message())) {
-          AOS_LOG_STRUCT(WARNING, "expected null output",
-                         zero_output_.saved_message());
-          AOS_LOG_STRUCT(WARNING, "got output", *loop_group_->output);
-        }
-      } else {
-        zero_output_(*loop_group_->output);
-      }
-    }
-    output_.clear_new_message();
-  }
-}
-
-}  // namespace controls
-}  // namespace aos
-
-#endif  // AOS_CONTROLS_REPLAY_CONTROL_LOOP_H_
diff --git a/aos/downloader/BUILD b/aos/downloader/BUILD
deleted file mode 100644
index 1aab653..0000000
--- a/aos/downloader/BUILD
+++ /dev/null
@@ -1,12 +0,0 @@
-py_binary(
-    name = "downloader",
-    srcs = [
-        "downloader.py",
-    ],
-    data = [
-        "@rsync",
-        "@ssh",
-        "@ssh//:scp",
-    ],
-    visibility = ["//visibility:public"],
-)
diff --git a/aos/downloader/downloader.bzl b/aos/downloader/downloader.bzl
deleted file mode 100644
index 139401a..0000000
--- a/aos/downloader/downloader.bzl
+++ /dev/null
@@ -1,116 +0,0 @@
-def _aos_downloader_impl(ctx):
-  all_files = ctx.files.srcs + ctx.files.start_srcs + [ctx.outputs._startlist]
-  ctx.file_action(
-    output = ctx.outputs.executable,
-    executable = True,
-    content = '\n'.join([
-      '#!/bin/bash',
-      'set -e',
-      'cd "${BASH_SOURCE[0]}.runfiles/%s"' % ctx.workspace_name,
-    ] + ['%s %s --dirs %s -- %s "$@"' % (
-       ctx.executable._downloader.short_path,
-       ' '.join([src.short_path for src in d.downloader_srcs]),
-       d.downloader_dir,
-       ctx.attr.default_target) for d in ctx.attr.dirs] + [
-      'exec %s %s -- %s "$@"' % (ctx.executable._downloader.short_path,
-                                 ' '.join([src.short_path for src in all_files]),
-                                 ctx.attr.default_target),
-    ]),
-  )
-
-  ctx.file_action(
-    output = ctx.outputs._startlist,
-    content = '\n'.join([f.basename for f in ctx.files.start_srcs]) + '\n',
-  )
-
-  to_download = [ctx.outputs._startlist]
-  to_download += all_files
-  for d in ctx.attr.dirs:
-    to_download += d.downloader_srcs
-
-  return struct(
-    runfiles = ctx.runfiles(
-      files = to_download + ctx.files._downloader,
-      transitive_files = ctx.attr._downloader.default_runfiles.files,
-      collect_data = True,
-      collect_default = True,
-    ),
-    files = depset([ctx.outputs.executable]),
-  )
-
-def _aos_downloader_dir_impl(ctx):
-  return struct(
-    downloader_dir = ctx.attr.dir,
-    downloader_srcs = ctx.files.srcs
-  )
-
-"""Creates a binary which downloads code to a robot.
-
-Running this with `bazel run` will actually download everything.
-
-This also generates a start_list.txt file with the names of binaries to start.
-
-Attrs:
-  srcs: The files to download. They currently all get shoved into one folder.
-  dirs: A list of aos_downloader_dirs to download too.
-  start_srcs: Like srcs, except they also get put into start_list.txt.
-  default_target: The default host to download to. If not specified, defaults to
-                  roboRIO-971.local.
-"""
-
-aos_downloader = rule(
-    attrs = {
-        "_downloader": attr.label(
-            executable = True,
-            cfg = "host",
-            default = Label("//aos/downloader"),
-        ),
-        "start_srcs": attr.label_list(
-            mandatory = True,
-            allow_files = True,
-        ),
-        "srcs": attr.label_list(
-            mandatory = True,
-            allow_files = True,
-        ),
-        "dirs": attr.label_list(
-            mandatory = False,
-            providers = [
-                "downloader_dir",
-                "downloader_srcs",
-            ],
-        ),
-        "default_target": attr.string(
-            default = "roboRIO-971-frc.local",
-        ),
-    },
-    executable = True,
-    outputs = {
-        "_startlist": "%{name}.start_list.dir/start_list.txt",
-    },
-    implementation = _aos_downloader_impl,
-)
-
-"""Downloads files to a specific directory.
-
-This rule does nothing by itself. Use it by adding to the dirs attribute of an
-aos_downloader rule.
-
-Attrs:
-  srcs: The files to download. They all go in the same directory.
-  dir: The directory (relative to the standard download directory) to put all
-       the files in.
-"""
-
-aos_downloader_dir = rule(
-    attrs = {
-        "srcs": attr.label_list(
-            mandatory = True,
-            allow_files = True,
-        ),
-        "dir": attr.string(
-            mandatory = True,
-        ),
-    },
-    implementation = _aos_downloader_dir_impl,
-)
diff --git a/aos/downloader/downloader.py b/aos/downloader/downloader.py
deleted file mode 100644
index e49ee5d..0000000
--- a/aos/downloader/downloader.py
+++ /dev/null
@@ -1,94 +0,0 @@
-# This file is run by shell scripts generated by the aos_downloader Skylark
-# macro. Everything before the first -- is a hard-coded list of files to
-# download.
-
-from __future__ import print_function
-
-import sys
-import subprocess
-import re
-import os
-
-
-def install(ssh_target, pkg):
-    """Installs a package from NI on the ssh target."""
-    print("Installing", pkg)
-    PKG_URL = "http://download.ni.com/ni-linux-rt/feeds/2015/arm/ipk/cortexa9-vfpv3/" + pkg
-    subprocess.check_call(["wget", PKG_URL, "-O", pkg])
-    try:
-        subprocess.check_call([
-            "external/ssh/usr/bin/scp", "-S", "external/ssh/usr/bin/ssh", pkg,
-            ssh_target + ":/tmp/" + pkg
-        ])
-        subprocess.check_call([
-            "external/ssh/usr/bin/ssh", ssh_target, "opkg", "install",
-            "/tmp/" + pkg
-        ])
-        subprocess.check_call(
-            ["external/ssh/usr/bin/ssh", ssh_target, "rm", "/tmp/" + pkg])
-    finally:
-        subprocess.check_call(["rm", pkg])
-
-
-def main(argv):
-    args = argv[argv.index("--") + 1:]
-
-    relative_dir = ""
-    recursive = False
-
-    if "--dirs" in argv:
-        dirs_index = argv.index("--dirs")
-        srcs = argv[1:dirs_index]
-        relative_dir = argv[dirs_index + 1]
-        recursive = True
-    else:
-        srcs = argv[1:argv.index("--")]
-
-    ROBORIO_TARGET_DIR = "/home/admin/robot_code"
-    ROBORIO_USER = "admin"
-
-    target_dir = ROBORIO_TARGET_DIR
-    user = ROBORIO_USER
-    destination = args[-1]
-
-    result = re.match("(?:([^:@]+)@)?([^:@]+)(?::([^:@]+))?", destination)
-    if not result:
-        print(
-            "Not sure how to parse destination \"%s\"!" % destination,
-            file=sys.stderr)
-        return 1
-    if result.group(1):
-        user = result.group(1)
-    hostname = result.group(2)
-    if result.group(3):
-        target_dir = result.group(3)
-
-    ssh_target = "%s@%s" % (user, hostname)
-
-    rsync_cmd = ([
-        "external/rsync/usr/bin/rsync", "-e", "external/ssh/usr/bin/ssh", "-c",
-        "-v", "-z", "--copy-links"
-    ] + srcs + ["%s:%s/%s" % (ssh_target, target_dir, relative_dir)])
-    try:
-        subprocess.check_call(rsync_cmd)
-    except subprocess.CalledProcessError as e:
-        if e.returncode == 127:
-            print("Unconfigured roboRIO, installing rsync.")
-            install(ssh_target, "libattr1_2.4.47-r0.36_cortexa9-vfpv3.ipk")
-            install(ssh_target, "libacl1_2.2.52-r0.36_cortexa9-vfpv3.ipk")
-            install(ssh_target, "rsync_3.1.0-r0.7_cortexa9-vfpv3.ipk")
-            subprocess.check_call(rsync_cmd)
-        else:
-            raise e
-
-    if not recursive:
-        subprocess.check_call(
-            ("external/ssh/usr/bin/ssh", ssh_target, "&&".join([
-                "chmod u+s %s/starter_exe" % target_dir,
-                "echo \'Done moving new executables into place\'",
-                "bash -c \'sync && sync && sync\'",
-            ])))
-
-
-if __name__ == "__main__":
-    main(sys.argv)
diff --git a/aos/event.cc b/aos/event.cc
index a0115dc..1b60362 100644
--- a/aos/event.cc
+++ b/aos/event.cc
@@ -3,7 +3,7 @@
 #include <chrono>
 
 #include "aos/type_traits/type_traits.h"
-#include "aos/logging/logging.h"
+#include "glog/logging.h"
 
 namespace aos {
 
@@ -16,8 +16,8 @@
   while (__atomic_load_n(&impl_, __ATOMIC_SEQ_CST) == 0) {
     const int ret = futex_wait(&impl_);
     if (ret != 0) {
-      AOS_CHECK_EQ(-1, ret);
-      AOS_PLOG(FATAL, "futex_wait(%p) failed", &impl_);
+      CHECK_EQ(-1, ret);
+      PLOG(FATAL) << "futex_wait(" << &impl_ << ") failed";
     }
   }
 }
@@ -37,8 +37,8 @@
     const int ret = futex_wait_timeout(&impl_, &timeout_timespec);
     if (ret != 0) {
       if (ret == 2) return false;
-      AOS_CHECK_EQ(-1, ret);
-      AOS_PLOG(FATAL, "futex_wait(%p) failed", &impl_);
+      CHECK_EQ(-1, ret);
+      PLOG(FATAL) << "futex_wait(" << &impl_ << ") failed";
     }
   }
 }
@@ -47,7 +47,7 @@
 // to condition variable-based implementations.
 void Event::Set() {
   if (futex_set(&impl_) == -1) {
-    AOS_PLOG(FATAL, "futex_set(%p) failed", &impl_);
+    PLOG(FATAL) << "futex_set(" << &impl_ << ") failed";
   }
 }
 
diff --git a/aos/events/BUILD b/aos/events/BUILD
index b69fc66..17ed688 100644
--- a/aos/events/BUILD
+++ b/aos/events/BUILD
@@ -1,3 +1,19 @@
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
+
+package(default_visibility = ["//visibility:public"])
+
+flatbuffer_cc_library(
+    name = "test_message_fbs",
+    srcs = ["test_message.fbs"],
+    gen_reflections = 1,
+)
+
+flatbuffer_cc_library(
+    name = "pingpong_fbs",
+    srcs = ["pingpong.fbs"],
+    gen_reflections = 1,
+)
+
 cc_library(
     name = "epoll",
     srcs = ["epoll.cc"],
@@ -10,72 +26,97 @@
 )
 
 cc_library(
-    name = "raw-event-loop",
-    hdrs = ["raw-event-loop.h"],
-    deps = [
-        "//aos:queues",
-        "//aos/time",
-    ],
-)
-
-cc_library(
-    name = "event-loop",
-    srcs = ["event-loop-tmpl.h"],
+    name = "event_loop",
+    srcs = ["event_loop_tmpl.h"],
     hdrs = [
-        "event-loop.h",
-        "raw-event-loop.h",
+        "event_loop.h",
     ],
     visibility = ["//visibility:public"],
     deps = [
-        ":raw-event-loop",
-        "//aos:queues",
+        "//aos:configuration",
+        "//aos:configuration_fbs",
+        "//aos:flatbuffers",
         "//aos/time",
+        "@com_github_google_flatbuffers//:flatbuffers",
+    ],
+)
+
+cc_binary(
+    name = "ping",
+    srcs = [
+        "ping.cc",
+    ],
+    data = ["config.fb.json"],
+    deps = [
+        ":pingpong_fbs",
+        ":shm_event_loop",
+        "//aos:configuration",
+        "//aos:init",
+        "//aos:json_to_flatbuffer",
+        "@com_github_google_glog//:glog",
+    ],
+)
+
+cc_binary(
+    name = "pong",
+    srcs = [
+        "pong.cc",
+    ],
+    data = ["config.fb.json"],
+    deps = [
+        ":pingpong_fbs",
+        ":shm_event_loop",
+        "//aos:configuration",
+        "//aos:init",
+        "//aos:json_to_flatbuffer",
+        "@com_github_google_glog//:glog",
     ],
 )
 
 cc_library(
-    name = "shm-event-loop",
-    srcs = ["shm-event-loop.cc"],
-    hdrs = ["shm-event-loop.h"],
+    name = "shm_event_loop",
+    srcs = ["shm_event_loop.cc"],
+    hdrs = ["shm_event_loop.h"],
     visibility = ["//visibility:public"],
     deps = [
         ":epoll",
-        ":event-loop",
-        "//aos:init",
-        "//aos:queues",
-        "//aos/logging",
+        ":event_loop",
+        ":test_message_fbs",
+        "//aos:realtime",
+        "//aos/ipc_lib:lockless_queue",
+        "//aos/ipc_lib:signalfd",
         "//aos/util:phased_loop",
     ],
 )
 
 cc_test(
-    name = "shm-event-loop_test",
-    srcs = ["shm-event-loop_test.cc"],
+    name = "shm_event_loop_test",
+    srcs = ["shm_event_loop_test.cc"],
     shard_count = 5,
     deps = [
-        ":event-loop_param_test",
-        ":shm-event-loop",
-        "//aos/testing:test_shm",
+        ":event_loop_param_test",
+        ":shm_event_loop",
+        ":test_message_fbs",
     ],
 )
 
 cc_library(
-    name = "event-loop_param_test",
+    name = "event_loop_param_test",
     testonly = True,
-    srcs = ["event-loop_param_test.cc"],
-    hdrs = ["event-loop_param_test.h"],
+    srcs = ["event_loop_param_test.cc"],
+    hdrs = ["event_loop_param_test.h"],
     deps = [
-        ":event-loop",
-        "//aos/logging:queue_logging",
+        ":event_loop",
+        ":test_message_fbs",
         "//aos/testing:googletest",
     ],
 )
 
 cc_test(
     name = "simulated_event_loop_test",
-    srcs = ["simulated-event-loop_test.cc"],
+    srcs = ["simulated_event_loop_test.cc"],
     deps = [
-        ":event-loop_param_test",
+        ":event_loop_param_test",
         ":simulated_event_loop",
         "//aos/testing:googletest",
     ],
@@ -84,14 +125,19 @@
 cc_library(
     name = "simulated_event_loop",
     testonly = True,
-    srcs = ["simulated-event-loop.cc"],
-    hdrs = ["simulated-event-loop.h"],
+    srcs = [
+        "event_scheduler.cc",
+        "simulated_event_loop.cc",
+    ],
+    hdrs = [
+        "event_scheduler.h",
+        "simulated_event_loop.h",
+    ],
     visibility = ["//visibility:public"],
     deps = [
-        ":event-loop",
-        "//aos:queues",
-        "//aos/logging",
-        "//aos/testing:test_logging",
+        ":event_loop",
+        "//aos/ipc_lib:index",
         "//aos/util:phased_loop",
+        "@com_google_absl//absl/container:btree",
     ],
 )
diff --git a/aos/events/config.fb.json b/aos/events/config.fb.json
new file mode 100644
index 0000000..4068243
--- /dev/null
+++ b/aos/events/config.fb.json
@@ -0,0 +1,12 @@
+{
+  "channels": [
+    {
+      "name": "/test",
+      "type": "aos.examples.Ping"
+    },
+    {
+      "name": "/test",
+      "type": "aos.examples.Pong"
+    }
+  ]
+}
diff --git a/aos/events/epoll.h b/aos/events/epoll.h
index f6ebe95..0f335e5 100644
--- a/aos/events/epoll.h
+++ b/aos/events/epoll.h
@@ -6,6 +6,7 @@
 #include <sys/timerfd.h>
 #include <unistd.h>
 #include <atomic>
+#include <functional>
 #include <vector>
 
 #include "aos/time/time.h"
diff --git a/aos/events/event-loop-tmpl.h b/aos/events/event-loop-tmpl.h
deleted file mode 100644
index 4c53be3..0000000
--- a/aos/events/event-loop-tmpl.h
+++ /dev/null
@@ -1,40 +0,0 @@
-#ifndef _AOS_EVENTS_EVENT_LOOP_TMPL_H_
-#define _AOS_EVENTS_EVENT_LOOP_TMPL_H_
-
-#include <type_traits>
-#include "aos/events/event-loop.h"
-
-namespace aos {
-
-// From a watch functor, this will extract the message type of the argument.
-// This is the template forward declaration, and it extracts the call operator
-// as a PTMF to be used by the following specialization.
-template <class T>
-struct watch_message_type_trait
-    : watch_message_type_trait<decltype(&T::operator())> {};
-
-// From a watch functor, this will extract the message type of the argument.
-// This is the template specialization.
-template <class ClassType, class ReturnType, class A1>
-struct watch_message_type_trait<ReturnType (ClassType::*)(A1) const> {
-  using message_type = typename std::decay<A1>::type;
-};
-
-template <typename T>
-typename Sender<T>::Message Sender<T>::MakeMessage() {
-  return Message(sender_.get());
-}
-
-template <typename Watch>
-void EventLoop::MakeWatcher(const std::string &path, Watch &&w) {
-  using T = typename watch_message_type_trait<Watch>::message_type;
-
-  return MakeRawWatcher(path, QueueTypeInfo::Get<T>(),
-                        [w](const Message *message) {
-                          w(*reinterpret_cast<const T *>(message));
-                        });
-}
-
-}  // namespace aos
-
-#endif  // _AOS_EVENTS_EVENT_LOOP_TMPL_H
diff --git a/aos/events/event-loop.h b/aos/events/event-loop.h
deleted file mode 100644
index 4d6fda5..0000000
--- a/aos/events/event-loop.h
+++ /dev/null
@@ -1,143 +0,0 @@
-#ifndef _AOS_EVENTS_EVENT_LOOP_H_
-#define _AOS_EVENTS_EVENT_LOOP_H_
-
-#include <string>
-#include "aos/queue.h"
-#include "aos/time/time.h"
-#include "aos/events/raw-event-loop.h"
-
-namespace aos {
-
-// Fetches the newest message from a queue.
-template <typename T>
-class Fetcher {
- public:
-  Fetcher() {}
-  // Fetches the next message. Returns true if it fetched a new message.  This
-  // method will only return messages sent after the Fetcher was created.
-  bool FetchNext() { return fetcher_->FetchNext(); }
-  // Fetches the most recent message. Returns true if it fetched a new message.
-  // This will return the latest message regardless of if it was sent before or
-  // after the fetcher was created.
-  bool Fetch() { return fetcher_->Fetch(); }
-
-  const T *get() const {
-    return reinterpret_cast<const T *>(fetcher_->most_recent());
-  }
-  const T &operator*() const { return *get(); }
-  const T *operator->() const { return get(); }
-
- private:
-  friend class EventLoop;
-  Fetcher(::std::unique_ptr<RawFetcher> fetcher) : fetcher_(::std::move(fetcher)) {}
-  ::std::unique_ptr<RawFetcher> fetcher_;
-};
-
-// Sends messages to a queue.
-template <typename T>
-class Sender {
- public:
-  typedef T Type;
-
-  Sender() {}
-
-  // Represents a single message about to be sent to the queue.
-  // The lifecycle goes:
-  //
-  // Message msg = sender.MakeMessage();
-  // Populate(msg.get());
-  // msg.Send();
-  //
-  // Or:
-  //
-  // Message msg = sender.MakeMessage();
-  // PopulateOrNot(msg.get());
-  class Message {
-   public:
-    Message(RawSender *sender)
-        : msg_(reinterpret_cast<T *>(sender->GetMessage()), *sender) {
-      msg_->Zero();
-    }
-
-    T *get() { return msg_.get(); }
-    const T *get() const { return msg_.get(); }
-    T &operator*() { return *get(); }
-    T *operator->() { return get(); }
-    const T &operator*() const { return *get(); }
-    const T *operator->() const { return get(); }
-
-    // Sends the message to the queue. Should only be called once.  Returns true
-    // if the message was successfully sent, and false otherwise.
-    bool Send() {
-      RawSender *sender = &msg_.get_deleter();
-      return sender->Send(msg_.release());
-    }
-
-   private:
-    std::unique_ptr<T, RawSender &> msg_;
-  };
-
-  // Constructs an above message.
-  Message MakeMessage();
-
-  // Returns the name of the underlying queue.
-  const char *name() const { return sender_->name(); }
-
- private:
-  friend class EventLoop;
-  Sender(::std::unique_ptr<RawSender> sender) : sender_(::std::move(sender)) {}
-  ::std::unique_ptr<RawSender> sender_;
-};
-
-// TODO(parker): Consider making EventLoop wrap a RawEventLoop rather than
-// inheriting.
-class EventLoop : public RawEventLoop {
- public:
-  virtual ~EventLoop() {}
-
-  // Current time.
-  virtual monotonic_clock::time_point monotonic_now() = 0;
-
-  // Note, it is supported to create:
-  //   multiple fetchers, and (one sender or one watcher) per <path, type>
-  //   tuple.
-
-  // Makes a class that will always fetch the most recent value
-  // sent to path.
-  template <typename T>
-  Fetcher<T> MakeFetcher(const ::std::string &path) {
-    return Fetcher<T>(MakeRawFetcher(path, QueueTypeInfo::Get<T>()));
-  }
-
-  // Makes class that allows constructing and sending messages to
-  // address path.
-  template <typename T>
-  Sender<T> MakeSender(const ::std::string &path) {
-    return Sender<T>(MakeRawSender(path, QueueTypeInfo::Get<T>()));
-  }
-
-  // Watch is a functor that have a call signature like so:
-  // void Event(const MessageType& type);
-  //
-  // This will watch messages sent to path.
-  // Note that T needs to match both send and recv side.
-  // TODO(parker): Need to support ::std::bind.  For now, use lambdas.
-  template <typename Watch>
-  void MakeWatcher(const ::std::string &path, Watch &&w);
-
-  // The passed in function will be called when the event loop starts.
-  // Use this to run code once the thread goes into "real-time-mode",
-  virtual void OnRun(::std::function<void()>) = 0;
-
-  // TODO(austin): OnExit
-
-  // Sets the scheduler priority to run the event loop at.  This may not be
-  // called after we go into "real-time-mode".
-  virtual void SetRuntimeRealtimePriority(int priority) = 0;
-};
-
-}  // namespace aos
-
-#include "aos/events/event-loop-tmpl.h"
-
-#endif  // _AOS_EVENTS_EVENT_LOOP_H
diff --git a/aos/events/event_loop.h b/aos/events/event_loop.h
new file mode 100644
index 0000000..f614517
--- /dev/null
+++ b/aos/events/event_loop.h
@@ -0,0 +1,328 @@
+#ifndef AOS_EVENTS_EVENT_LOOP_H_
+#define AOS_EVENTS_EVENT_LOOP_H_
+
+#include <atomic>
+#include <string>
+
+#include "absl/strings/string_view.h"
+#include "aos/configuration.h"
+#include "aos/configuration_generated.h"
+#include "aos/flatbuffers.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/time/time.h"
+#include "flatbuffers/flatbuffers.h"
+#include "glog/logging.h"
+
+namespace aos {
+
+// Struct available on Watchers and Fetchers with context about the current
+// message.
+struct Context {
+  // Time that the message was sent.
+  monotonic_clock::time_point monotonic_sent_time;
+  realtime_clock::time_point realtime_sent_time;
+  // Index in the queue.
+  uint32_t queue_index;
+  // Size of the data sent.
+  size_t size;
+  // Pointer to the data.
+  void *data;
+};
+
+// Raw version of fetcher. Contains a local variable that the fetcher will
+// update.  This is used for reflection and as an interface to implement typed
+// fetchers.
+class RawFetcher {
+ public:
+  RawFetcher() {}
+  virtual ~RawFetcher() {}
+
+  // Non-blocking fetch of the next message in the queue. Returns true if there
+  // was a new message and we got it.
+  virtual bool FetchNext() = 0;
+
+  // Non-blocking fetch of the latest message:
+  virtual bool Fetch() = 0;
+
+  // Returns a pointer to data in the most recent message, or nullptr if there
+  // is no message.
+  const void *most_recent_data() const { return data_; }
+
+  const Context &context() const { return context_; }
+
+ protected:
+  RawFetcher(const RawFetcher &) = delete;
+  RawFetcher &operator=(const RawFetcher &) = delete;
+
+  void *data_ = nullptr;
+  Context context_;
+};
+
+// Raw version of sender.  Sends a block of data.  This is used for reflection
+// and as a building block to implement typed senders.
+class RawSender {
+ public:
+  RawSender() {}
+  virtual ~RawSender() {}
+
+  // Sends a message without copying it.  The users starts by copying up to
+  // size() bytes into the data backed by data().  They then call Send to send.
+  // Returns true on a successful send.
+  virtual void *data() = 0;
+  virtual size_t size() = 0;
+  virtual bool Send(size_t size) = 0;
+
+  // Sends a single block of data by copying it.
+  virtual bool Send(void *data, size_t size) = 0;
+
+  // Returns the name of this sender.
+  virtual const absl::string_view name() const = 0;
+
+ protected:
+  RawSender(const RawSender &) = delete;
+  RawSender &operator=(const RawSender &) = delete;
+};
+
+
+// Fetches the newest message from a channel.
+// This provides a polling based interface for channels.
+template <typename T>
+class Fetcher {
+ public:
+  Fetcher() {}
+
+  // Fetches the next message. Returns true if it fetched a new message.  This
+  // method will only return messages sent after the Fetcher was created.
+  bool FetchNext() { return fetcher_->FetchNext(); }
+
+  // Fetches the most recent message. Returns true if it fetched a new message.
+  // This will return the latest message regardless of if it was sent before or
+  // after the fetcher was created.
+  bool Fetch() { return fetcher_->Fetch(); }
+
+  // Returns a pointer to the contained flatbuffer, or nullptr if there is no
+  // available message.
+  const T *get() const {
+    return fetcher_->most_recent_data() != nullptr
+               ? flatbuffers::GetRoot<T>(reinterpret_cast<const char *>(
+                     fetcher_->most_recent_data()))
+               : nullptr;
+  }
+
+  // Returns the context holding timestamps and other metadata about the
+  // message.
+  const Context &context() const { return fetcher_->context(); }
+
+  const T &operator*() const { return *get(); }
+  const T *operator->() const { return get(); }
+
+ private:
+  friend class EventLoop;
+  Fetcher(::std::unique_ptr<RawFetcher> fetcher)
+      : fetcher_(::std::move(fetcher)) {}
+  ::std::unique_ptr<RawFetcher> fetcher_;
+};
+
+// Sends messages to a channel.
+template <typename T>
+class Sender {
+ public:
+  Sender() {}
+
+  // Represents a single message about to be sent to the queue.
+  // The lifecycle goes:
+  //
+  // Builder builder = sender.MakeBuilder();
+  // T::Builder t_builder = builder.MakeBuilder<T>();
+  // Populate(&t_builder);
+  // builder.Send(t_builder.Finish());
+  class Builder {
+   public:
+    Builder(RawSender *sender, void *data, size_t size)
+        : alloc_(data, size), fbb_(size, &alloc_), sender_(sender) {
+      fbb_.ForceDefaults(1);
+    }
+
+    flatbuffers::FlatBufferBuilder *fbb() { return &fbb_; }
+
+    template <typename T2>
+    typename T2::Builder MakeBuilder() {
+      return typename T2::Builder(fbb_);
+    }
+
+    bool Send(flatbuffers::Offset<T> offset) {
+      fbb_.Finish(offset);
+      return sender_->Send(fbb_.GetSize());
+    }
+
+    // CHECKs that this message was sent.
+    void CheckSent() { fbb_.Finished(); }
+
+   private:
+    PreallocatedAllocator alloc_;
+    flatbuffers::FlatBufferBuilder fbb_;
+    RawSender *sender_;
+  };
+
+  // Constructs an above builder.
+  Builder MakeBuilder();
+
+  // Returns the name of the underlying queue.
+  const absl::string_view name() const { return sender_->name(); }
+
+ private:
+  friend class EventLoop;
+  Sender(std::unique_ptr<RawSender> sender) : sender_(std::move(sender)) {}
+  std::unique_ptr<RawSender> sender_;
+};
+
+// Interface for timers
+class TimerHandler {
+ public:
+  virtual ~TimerHandler() {}
+
+  // Timer should sleep until base, base + offset, base + offset * 2, ...
+  // If repeat_offset isn't set, the timer only expires once.
+  virtual void Setup(monotonic_clock::time_point base,
+                     monotonic_clock::duration repeat_offset =
+                         ::aos::monotonic_clock::zero()) = 0;
+
+  // Stop future calls to callback().
+  virtual void Disable() = 0;
+};
+
+// Interface for phased loops.  They are built on timers.
+class PhasedLoopHandler {
+ public:
+  virtual ~PhasedLoopHandler() {}
+
+  // Sets the interval and offset.  Any changes to interval and offset only take
+  // effect when the handler finishes running.
+  virtual void set_interval_and_offset(
+      const monotonic_clock::duration interval,
+      const monotonic_clock::duration offset) = 0;
+};
+
+// TODO(austin): Ping pong example apps, and then start doing introspection.
+// TODO(austin): Timing reporter.  Publish statistics on latencies of
+// handlers.
+class EventLoop {
+ public:
+  EventLoop(const Configuration *configuration)
+      : configuration_(configuration) {}
+
+  virtual ~EventLoop() {}
+
+  // Current time.
+  virtual monotonic_clock::time_point monotonic_now() = 0;
+  virtual realtime_clock::time_point realtime_now() = 0;
+
+  // Note, it is supported to create:
+  //   multiple fetchers, and (one sender or one watcher) per <name, type>
+  //   tuple.
+
+  // Makes a class that will always fetch the most recent value
+  // sent to the provided channel.
+  template <typename T>
+  Fetcher<T> MakeFetcher(const absl::string_view channel_name) {
+    const Channel *channel = configuration::GetChannel(
+        configuration_, channel_name, T::GetFullyQualifiedName(), name());
+    CHECK(channel != nullptr)
+        << ": Channel { \"name\": \"" << channel_name << "\", \"type\": \""
+        << T::GetFullyQualifiedName() << "\" } not found in config.";
+
+    return Fetcher<T>(MakeRawFetcher(channel));
+  }
+
+  // Makes class that allows constructing and sending messages to
+  // the provided channel.
+  template <typename T>
+  Sender<T> MakeSender(const absl::string_view channel_name) {
+    const Channel *channel = configuration::GetChannel(
+        configuration_, channel_name, T::GetFullyQualifiedName(), name());
+    CHECK(channel != nullptr)
+        << ": Channel { \"name\": \"" << channel_name << "\", \"type\": \""
+        << T::GetFullyQualifiedName() << "\" } not found in config.";
+
+    return Sender<T>(MakeRawSender(channel));
+  }
+
+  // This will watch messages sent to the provided channel.
+  //
+  // Watch is a functor that have a call signature like so:
+  // void Event(const MessageType& type);
+  //
+  // TODO(parker): Need to support ::std::bind.  For now, use lambdas.
+  // TODO(austin): Do we need a functor?  Or is a std::function good enough?
+  template <typename Watch>
+  void MakeWatcher(const absl::string_view name, Watch &&w);
+
+  // The passed in function will be called when the event loop starts.
+  // Use this to run code once the thread goes into "real-time-mode",
+  virtual void OnRun(::std::function<void()> on_run) = 0;
+
+  // Sets the name of the event loop.  This is the application name.
+  virtual void set_name(const absl::string_view name) = 0;
+  // Gets the name of the event loop.
+  virtual const absl::string_view name() const = 0;
+
+  // Creates a timer that executes callback when the timer expires
+  // Returns a TimerHandle for configuration of the timer
+  virtual TimerHandler *AddTimer(::std::function<void()> callback) = 0;
+
+  // Creates a timer that executes callback periodically at the specified
+  // interval and offset.  Returns a PhasedLoopHandler for interacting with the
+  // timer.
+  virtual PhasedLoopHandler *AddPhasedLoop(
+      ::std::function<void(int)> callback,
+      const monotonic_clock::duration interval,
+      const monotonic_clock::duration offset = ::std::chrono::seconds(0)) = 0;
+
+  // TODO(austin): OnExit
+
+  // Threadsafe.
+  bool is_running() const { return is_running_.load(); }
+
+  // Sets the scheduler priority to run the event loop at.  This may not be
+  // called after we go into "real-time-mode".
+  virtual void SetRuntimeRealtimePriority(int priority) = 0;
+
+  // Fetches new messages from the provided channel (path, type).  Note: this
+  // channel must be a member of the exact configuration object this was built
+  // with.
+  virtual std::unique_ptr<RawFetcher> MakeRawFetcher(
+      const Channel *channel) = 0;
+
+  // Will watch channel (name, type) for new messages
+  virtual void MakeRawWatcher(
+      const Channel *channel,
+      std::function<void(const Context &context, const void *message)>
+          watcher) = 0;
+
+  // Returns the context for the current message.
+  // TODO(austin): Fill out whatever is useful for timers.
+  const Context &context() const { return context_; }
+
+  // Returns the configuration that this event loop was built with.
+  const Configuration *configuration() const { return configuration_; }
+
+ protected:
+  void set_is_running(bool value) { is_running_.store(value); }
+
+  // Will send new messages from channel (path, type).
+  virtual std::unique_ptr<RawSender> MakeRawSender(const Channel *channel) = 0;
+
+ private:
+  ::std::atomic<bool> is_running_{false};
+
+  // Context available for watchers.
+  Context context_;
+
+  const Configuration *configuration_;
+};
+
+}  // namespace aos
+
+#include "aos/events/event_loop_tmpl.h"
+
+#endif  // AOS_EVENTS_EVENT_LOOP_H
diff --git a/aos/events/event-loop_param_test.cc b/aos/events/event_loop_param_test.cc
similarity index 64%
rename from aos/events/event-loop_param_test.cc
rename to aos/events/event_loop_param_test.cc
index 04343cc..8a0f9b6 100644
--- a/aos/events/event-loop_param_test.cc
+++ b/aos/events/event_loop_param_test.cc
@@ -1,11 +1,13 @@
-#include "aos/events/event-loop_param_test.h"
+#include "aos/events/event_loop_param_test.h"
 
 #include <chrono>
 
+#include "glog/logging.h"
 #include "gmock/gmock.h"
 #include "gtest/gtest.h"
 
 #include "glog/logging.h"
+#include "aos/events/test_message_generated.h"
 
 namespace aos {
 namespace testing {
@@ -13,39 +15,27 @@
 namespace chrono = ::std::chrono;
 }  // namespace
 
-struct TestMessage : public ::aos::Message {
-  enum { kQueueLength = 100, kHash = 0x696c0cdc };
-  int msg_value;
-
-  void Zero() {
-    ::aos::Message::Zero();
-    msg_value = 0;
-  }
-  static size_t Size() { return 1 + ::aos::Message::Size(); }
-  size_t Print(char *buffer, size_t length) const;
-  TestMessage() { Zero(); }
-};
-
 // Tests that watcher can receive messages from a sender.
 // Also tests that OnRun() works.
 TEST_P(AbstractEventLoopTest, Basic) {
   auto loop1 = Make();
   auto loop2 = MakePrimary();
 
-  auto sender = loop1->MakeSender<TestMessage>("/test");
+  aos::Sender<TestMessage> sender = loop1->MakeSender<TestMessage>("/test");
 
   bool happened = false;
 
   loop2->OnRun([&]() {
     happened = true;
 
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 200;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(200);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   });
 
   loop2->MakeWatcher("/test", [&](const TestMessage &message) {
-    EXPECT_EQ(message.msg_value, 200);
+    EXPECT_EQ(message.value(), 200);
     this->Exit();
   });
 
@@ -67,13 +57,14 @@
 
   EXPECT_FALSE(fetcher.Fetch());
 
-  auto msg = sender.MakeMessage();
-  msg->msg_value = 200;
-  msg.Send();
+  aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+  TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+  builder.add_value(200);
+  ASSERT_TRUE(msg.Send(builder.Finish()));
 
   EXPECT_TRUE(fetcher.Fetch());
   ASSERT_FALSE(fetcher.get() == nullptr);
-  EXPECT_EQ(fetcher->msg_value, 200);
+  EXPECT_EQ(fetcher.get()->value(), 200);
 }
 
 // Tests that watcher will receive all messages sent if they are sent after
@@ -87,7 +78,7 @@
   ::std::vector<int> values;
 
   loop2->MakeWatcher("/test", [&](const TestMessage &message) {
-    values.push_back(message.msg_value);
+    values.push_back(message.value());
     if (values.size() == 2) {
       this->Exit();
     }
@@ -95,21 +86,24 @@
 
   // Before Run, should be ignored.
   {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 199;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(199);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   }
 
   loop2->OnRun([&]() {
     {
-      auto msg = sender.MakeMessage();
-      msg->msg_value = 200;
-      msg.Send();
+      aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+      TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+      builder.add_value(200);
+      ASSERT_TRUE(msg.Send(builder.Finish()));
     }
     {
-      auto msg = sender.MakeMessage();
-      msg->msg_value = 201;
-      msg.Send();
+      aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+      TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+      builder.add_value(201);
+      ASSERT_TRUE(msg.Send(builder.Finish()));
     }
   });
 
@@ -129,18 +123,20 @@
   ::std::vector<int> values;
 
   {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 200;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(200);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   }
   {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 201;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(201);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   }
 
   loop2->MakeWatcher("/test", [&](const TestMessage &message) {
-    values.push_back(message.msg_value);
+    values.push_back(message.value());
   });
 
   // Add a timer to actually quit.
@@ -164,20 +160,22 @@
   ::std::vector<int> values;
 
   {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 200;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(200);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   }
   {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 201;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(201);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   }
 
   // Add a timer to actually quit.
   auto test_timer = loop2->AddTimer([&fetcher, &values, this]() {
     while (fetcher.FetchNext()) {
-      values.push_back(fetcher->msg_value);
+      values.push_back(fetcher.get()->value());
     }
     this->Exit();
   });
@@ -200,14 +198,16 @@
   ::std::vector<int> values;
 
   {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 200;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(200);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   }
   {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 201;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(201);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   }
 
   auto fetcher = loop2->MakeFetcher<TestMessage>("/test");
@@ -215,7 +215,7 @@
   // Add a timer to actually quit.
   auto test_timer = loop2->AddTimer([&fetcher, &values, this]() {
     while (fetcher.FetchNext()) {
-      values.push_back(fetcher->msg_value);
+      values.push_back(fetcher.get()->value());
     }
     this->Exit();
   });
@@ -239,14 +239,16 @@
   ::std::vector<int> values;
 
   {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 200;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(200);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   }
   {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 201;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(201);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   }
 
   auto fetcher = loop2->MakeFetcher<TestMessage>("/test");
@@ -254,11 +256,11 @@
   // Add a timer to actually quit.
   auto test_timer = loop2->AddTimer([&fetcher, &values, this]() {
     if (fetcher.Fetch()) {
-      values.push_back(fetcher->msg_value);
+      values.push_back(fetcher.get()->value());
     }
     // Do it again to make sure we don't double fetch.
     if (fetcher.Fetch()) {
-      values.push_back(fetcher->msg_value);
+      values.push_back(fetcher.get()->value());
     }
     this->Exit();
   });
@@ -281,14 +283,16 @@
   ::std::vector<int> values;
 
   {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 200;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(200);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   }
   {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 201;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(201);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   }
 
   auto fetcher = loop2->MakeFetcher<TestMessage>("/test");
@@ -296,31 +300,34 @@
   // Add a timer to actually quit.
   auto test_timer = loop2->AddTimer([&fetcher, &values, &sender, this]() {
     if (fetcher.Fetch()) {
-      values.push_back(fetcher->msg_value);
+      values.push_back(fetcher.get()->value());
     }
 
     {
-      auto msg = sender.MakeMessage();
-      msg->msg_value = 202;
-      msg.Send();
+      aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+      TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+      builder.add_value(202);
+      ASSERT_TRUE(msg.Send(builder.Finish()));
     }
     {
-      auto msg = sender.MakeMessage();
-      msg->msg_value = 203;
-      msg.Send();
+      aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+      TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+      builder.add_value(203);
+      ASSERT_TRUE(msg.Send(builder.Finish()));
     }
     {
-      auto msg = sender.MakeMessage();
-      msg->msg_value = 204;
-      msg.Send();
+      aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+      TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+      builder.add_value(204);
+      ASSERT_TRUE(msg.Send(builder.Finish()));
     }
 
     if (fetcher.FetchNext()) {
-      values.push_back(fetcher->msg_value);
+      values.push_back(fetcher.get()->value());
     }
 
     if (fetcher.Fetch()) {
-      values.push_back(fetcher->msg_value);
+      values.push_back(fetcher.get()->value());
     }
 
     this->Exit();
@@ -345,29 +352,31 @@
   Fetcher<TestMessage> fetcher = fetch_loop->MakeFetcher<TestMessage>("/test");
 
   {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 100;
-    ASSERT_TRUE(msg.Send());
+      aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+      TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+      builder.add_value(100);
+      ASSERT_TRUE(msg.Send(builder.Finish()));
   }
 
   {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 200;
-    ASSERT_TRUE(msg.Send());
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(200);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   }
 
   ASSERT_TRUE(fetcher.FetchNext());
   ASSERT_NE(nullptr, fetcher.get());
-  EXPECT_EQ(100, fetcher->msg_value);
+  EXPECT_EQ(100, fetcher.get()->value());
 
   ASSERT_TRUE(fetcher.FetchNext());
   ASSERT_NE(nullptr, fetcher.get());
-  EXPECT_EQ(200, fetcher->msg_value);
+  EXPECT_EQ(200, fetcher.get()->value());
 
   // When we run off the end of the queue, expect to still have the old message:
   ASSERT_FALSE(fetcher.FetchNext());
   ASSERT_NE(nullptr, fetcher.get());
-  EXPECT_EQ(200, fetcher->msg_value);
+  EXPECT_EQ(200, fetcher.get()->value());
 }
 
 // Verify that making a fetcher and watcher for "/test" succeeds.
@@ -384,6 +393,14 @@
   auto fetcher2 = loop->MakeFetcher<TestMessage>("/test");
 }
 
+// Verify that registering a watcher for an invalid channel name dies.
+TEST_P(AbstractEventLoopDeathTest, InvalidChannelName) {
+  auto loop = Make();
+  EXPECT_DEATH(
+      { loop->MakeWatcher("/test/invalid", [&](const TestMessage &) {}); },
+      "/test/invalid");
+}
+
 // Verify that registering a watcher twice for "/test" fails.
 TEST_P(AbstractEventLoopDeathTest, TwoWatcher) {
   auto loop = Make();
@@ -438,16 +455,17 @@
 
   loop2->MakeWatcher("/test1", [&](const TestMessage &) {});
   loop2->MakeWatcher("/test2", [&](const TestMessage &message) {
-    EXPECT_EQ(message.msg_value, 200);
+    EXPECT_EQ(message.value(), 200);
     this->Exit();
   });
 
   auto sender = loop1->MakeSender<TestMessage>("/test2");
 
   loop2->OnRun([&]() {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 200;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(200);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
   });
 
   Run();
@@ -525,9 +543,18 @@
   auto fetcher = loop2->MakeFetcher<TestMessage>("/test");
 
   auto test_timer = loop1->AddTimer([&sender]() {
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 200;
-    msg.Send();
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(200);
+    ASSERT_TRUE(msg.Send(builder.Finish()));
+  });
+
+  loop2->MakeWatcher("/test", [&loop2](const TestMessage &msg) {
+    // Confirm that the data pointer makes sense from a watcher.
+    EXPECT_GT(&msg, loop2->context().data);
+    EXPECT_LT(&msg, reinterpret_cast<void *>(
+                        reinterpret_cast<char *>(loop2->context().data) +
+                        loop2->context().size));
   });
 
   test_timer->Setup(loop1->monotonic_now() + ::std::chrono::seconds(1));
@@ -537,15 +564,36 @@
 
   EXPECT_TRUE(fetcher.Fetch());
 
-  monotonic_clock::duration time_offset =
-      fetcher->sent_time - (loop1->monotonic_now() - ::std::chrono::seconds(1));
+  monotonic_clock::duration monotonic_time_offset =
+      fetcher.context().monotonic_sent_time -
+      (loop1->monotonic_now() - ::std::chrono::seconds(1));
+  realtime_clock::duration realtime_time_offset =
+      fetcher.context().realtime_sent_time -
+      (loop1->realtime_now() - ::std::chrono::seconds(1));
 
-  EXPECT_TRUE(time_offset > ::std::chrono::milliseconds(-500))
-      << ": Got " << fetcher->sent_time.time_since_epoch().count()
+  EXPECT_TRUE(monotonic_time_offset > ::std::chrono::milliseconds(-500))
+      << ": Got "
+      << fetcher.context().monotonic_sent_time.time_since_epoch().count()
       << " expected " << loop1->monotonic_now().time_since_epoch().count();
-  EXPECT_TRUE(time_offset < ::std::chrono::milliseconds(500))
-      << ": Got " << fetcher->sent_time.time_since_epoch().count()
+  // Confirm that the data pointer makes sense.
+  EXPECT_GT(fetcher.get(), fetcher.context().data);
+  EXPECT_LT(fetcher.get(),
+            reinterpret_cast<void *>(
+                reinterpret_cast<char *>(fetcher.context().data) +
+                fetcher.context().size));
+  EXPECT_TRUE(monotonic_time_offset < ::std::chrono::milliseconds(500))
+      << ": Got "
+      << fetcher.context().monotonic_sent_time.time_since_epoch().count()
       << " expected " << loop1->monotonic_now().time_since_epoch().count();
+
+  EXPECT_TRUE(realtime_time_offset > ::std::chrono::milliseconds(-500))
+      << ": Got "
+      << fetcher.context().realtime_sent_time.time_since_epoch().count()
+      << " expected " << loop1->realtime_now().time_since_epoch().count();
+  EXPECT_TRUE(realtime_time_offset < ::std::chrono::milliseconds(500))
+      << ": Got "
+      << fetcher.context().realtime_sent_time.time_since_epoch().count()
+      << " expected " << loop1->realtime_now().time_since_epoch().count();
 }
 
 // Tests that a couple phased loops run in a row result in the correct offset
@@ -612,41 +660,5 @@
               1.0, 0.1);
 }
 
-// Verify that sending lots and lots of messages and using FetchNext gets a
-// contiguous block of messages and doesn't crash.
-// TODO(austin): We should store the same number of messages in simulation and
-// reality.
-TEST_P(AbstractEventLoopTest, LotsOfSends) {
-  auto loop1 = MakePrimary();
-  auto loop2 = Make();
-  auto sender = loop1->MakeSender<TestMessage>("/test");
-  auto fetcher = loop2->MakeFetcher<TestMessage>("/test");
-
-  auto test_timer = loop1->AddTimer([&sender, &fetcher, this]() {
-    for (int i = 0; i < 100000; ++i) {
-      auto msg = sender.MakeMessage();
-      msg->msg_value = i;
-      msg.Send();
-    }
-
-    int last = 0;
-    if (fetcher.FetchNext()) {
-      last = fetcher->msg_value;
-    }
-    while (fetcher.FetchNext()) {
-      EXPECT_EQ(last + 1, fetcher->msg_value);
-      ++last;
-    }
-
-    this->Exit();
-  });
-
-  loop1->OnRun([&test_timer, &loop1]() {
-    test_timer->Setup(loop1->monotonic_now() + ::std::chrono::milliseconds(10));
-  });
-
-  Run();
-}
-
 }  // namespace testing
 }  // namespace aos
diff --git a/aos/events/event-loop_param_test.h b/aos/events/event_loop_param_test.h
similarity index 61%
rename from aos/events/event-loop_param_test.h
rename to aos/events/event_loop_param_test.h
index 83f0b37..fb08ac3 100644
--- a/aos/events/event-loop_param_test.h
+++ b/aos/events/event_loop_param_test.h
@@ -3,7 +3,9 @@
 
 #include <vector>
 
-#include "aos/events/event-loop.h"
+#include "aos/events/event_loop.h"
+#include "aos/flatbuffers.h"
+#include "aos/json_to_flatbuffer.h"
 #include "gtest/gtest.h"
 
 namespace aos {
@@ -11,6 +13,25 @@
 
 class EventLoopTestFactory {
  public:
+  EventLoopTestFactory()
+      : flatbuffer_(JsonToFlatbuffer("{\n"
+                                     "  \"channels\": [ \n"
+                                     "    {\n"
+                                     "      \"name\": \"/test\",\n"
+                                     "      \"type\": \"aos.TestMessage\"\n"
+                                     "    },\n"
+                                     "    {\n"
+                                     "      \"name\": \"/test1\",\n"
+                                     "      \"type\": \"aos.TestMessage\"\n"
+                                     "    },\n"
+                                     "    {\n"
+                                     "      \"name\": \"/test2\",\n"
+                                     "      \"type\": \"aos.TestMessage\"\n"
+                                     "    }\n"
+                                     "  ]\n"
+                                     "}\n",
+                                     Configuration::MiniReflectTypeTable())) {}
+
   virtual ~EventLoopTestFactory() {}
 
   // Makes a connected event loop.
@@ -27,6 +48,11 @@
 
   // Advances time by sleeping.  Can't be called from inside a loop.
   virtual void SleepFor(::std::chrono::nanoseconds duration) = 0;
+
+  const Configuration *configuration() { return &flatbuffer_.message(); }
+
+ private:
+  FlatbufferDetachedBuffer<Configuration> flatbuffer_;
 };
 
 class AbstractEventLoopTestBase
diff --git a/aos/events/event_loop_tmpl.h b/aos/events/event_loop_tmpl.h
new file mode 100644
index 0000000..9910d4d
--- /dev/null
+++ b/aos/events/event_loop_tmpl.h
@@ -0,0 +1,48 @@
+#ifndef AOS_EVENTS_EVENT_LOOP_TMPL_H_
+#define AOS_EVENTS_EVENT_LOOP_TMPL_H_
+
+#include <type_traits>
+#include "aos/events/event_loop.h"
+#include "glog/logging.h"
+
+namespace aos {
+
+// From a watch functor, this will extract the message type of the argument.
+// This is the template forward declaration, and it extracts the call operator
+// as a PTMF to be used by the following specialization.
+template <class T>
+struct watch_message_type_trait
+    : watch_message_type_trait<decltype(&T::operator())> {};
+
+// From a watch functor, this will extract the message type of the argument.
+// This is the template specialization.
+template <class ClassType, class ReturnType, class A1>
+struct watch_message_type_trait<ReturnType (ClassType::*)(A1) const> {
+  using message_type = typename std::decay<A1>::type;
+};
+
+template <typename T>
+typename Sender<T>::Builder Sender<T>::MakeBuilder() {
+  return Builder(sender_.get(), sender_->data(), sender_->size());
+}
+
+template <typename Watch>
+void EventLoop::MakeWatcher(const absl::string_view channel_name, Watch &&w) {
+  using T = typename watch_message_type_trait<Watch>::message_type;
+  const Channel *channel = configuration::GetChannel(
+      configuration_, channel_name, T::GetFullyQualifiedName(), name());
+
+  CHECK(channel != nullptr)
+      << ": Channel { \"name\": \"" << channel_name << "\", \"type\": \""
+      << T::GetFullyQualifiedName() << "\" } not found in config.";
+
+  return MakeRawWatcher(
+      channel, [this, w](const Context &context, const void *message) {
+        context_ = context;
+        w(*flatbuffers::GetRoot<T>(reinterpret_cast<const char *>(message)));
+      });
+}
+
+}  // namespace aos
+
+#endif  // AOS_EVENTS_EVENT_LOOP_TMPL_H
diff --git a/aos/events/event_scheduler.cc b/aos/events/event_scheduler.cc
new file mode 100644
index 0000000..a4cfa72
--- /dev/null
+++ b/aos/events/event_scheduler.cc
@@ -0,0 +1,48 @@
+#include "aos/events/event_scheduler.h"
+
+#include <algorithm>
+#include <deque>
+
+#include "aos/events/event_loop.h"
+
+namespace aos {
+
+EventScheduler::Token EventScheduler::Schedule(
+    ::aos::monotonic_clock::time_point time, ::std::function<void()> callback) {
+  return events_list_.emplace(time, callback);
+}
+
+void EventScheduler::Deschedule(EventScheduler::Token token) {
+  events_list_.erase(token);
+}
+
+void EventScheduler::RunFor(monotonic_clock::duration duration) {
+  const ::aos::monotonic_clock::time_point end_time =
+      monotonic_now() + duration;
+  is_running_ = true;
+  while (!events_list_.empty() && is_running_) {
+    auto iter = events_list_.begin();
+    ::aos::monotonic_clock::time_point next_time = iter->first;
+    if (next_time > end_time) {
+      break;
+    }
+    now_ = iter->first;
+    ::std::function<void()> callback = ::std::move(iter->second);
+    events_list_.erase(iter);
+    callback();
+  }
+  now_ = end_time;
+}
+
+void EventScheduler::Run() {
+  is_running_ = true;
+  while (!events_list_.empty() && is_running_) {
+    auto iter = events_list_.begin();
+    now_ = iter->first;
+    ::std::function<void()> callback = ::std::move(iter->second);
+    events_list_.erase(iter);
+    callback();
+  }
+}
+
+}  // namespace aos
diff --git a/aos/events/event_scheduler.h b/aos/events/event_scheduler.h
new file mode 100644
index 0000000..66d34b3
--- /dev/null
+++ b/aos/events/event_scheduler.h
@@ -0,0 +1,61 @@
+#ifndef AOS_EVENTS_EVENT_SCHEDULER_H_
+#define AOS_EVENTS_EVENT_SCHEDULER_H_
+
+#include <algorithm>
+#include <map>
+#include <memory>
+#include <unordered_set>
+#include <utility>
+#include <vector>
+
+#include "aos/events/event_loop.h"
+#include "aos/time/time.h"
+#include "glog/logging.h"
+
+namespace aos {
+
+class EventScheduler {
+ public:
+  using ChannelType =
+      std::multimap<monotonic_clock::time_point, std::function<void()>>;
+  using Token = ChannelType::iterator;
+
+  // Schedule an event with a callback function
+  // Returns an iterator to the event
+  Token Schedule(monotonic_clock::time_point time,
+                 std::function<void()> callback);
+
+  Token InvalidToken() { return events_list_.end(); }
+
+  // Deschedule an event by its iterator
+  void Deschedule(Token token);
+
+  // Runs until exited.
+  void Run();
+  // Runs for a duration.
+  void RunFor(monotonic_clock::duration duration);
+
+  void Exit() { is_running_ = false; }
+
+  bool is_running() const { return is_running_; }
+
+  monotonic_clock::time_point monotonic_now() const { return now_; }
+  realtime_clock::time_point realtime_now() const {
+    // TODO(austin): Make this all configurable...
+    return realtime_clock::epoch() + now_.time_since_epoch() +
+           std::chrono::seconds(1000000);
+  }
+
+ private:
+  // Current execution time.
+  monotonic_clock::time_point now_ = monotonic_clock::epoch();
+
+  // Multimap holding times to run functions.  These are stored in order, and
+  // the order is the callback tree.
+  ChannelType events_list_;
+  bool is_running_ = false;
+};
+
+}  // namespace aos
+
+#endif  // AOS_EVENTS_EVENT_SCHEDULER_H_
diff --git a/aos/events/ping.cc b/aos/events/ping.cc
new file mode 100644
index 0000000..b904cb2
--- /dev/null
+++ b/aos/events/ping.cc
@@ -0,0 +1,88 @@
+#include <chrono>
+
+#include "aos/configuration.h"
+#include "aos/events/pingpong_generated.h"
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "gflags/gflags.h"
+#include "glog/logging.h"
+
+DEFINE_int32(sleep_ms, 10, "Time to sleep between pings");
+
+namespace aos {
+
+namespace chrono = std::chrono;
+
+class Ping {
+ public:
+  Ping(EventLoop *event_loop)
+      : event_loop_(event_loop),
+        sender_(event_loop_->MakeSender<examples::Ping>("/test")) {
+    timer_handle_ = event_loop_->AddTimer([this]() { SendPing(); });
+
+    event_loop_->MakeWatcher(
+        "/test", [this](const examples::Pong &pong) { HandlePong(pong); });
+
+    event_loop_->OnRun([this]() {
+      timer_handle_->Setup(event_loop_->monotonic_now(),
+                           chrono::milliseconds(FLAGS_sleep_ms));
+    });
+
+    event_loop_->SetRuntimeRealtimePriority(5);
+  }
+
+  void SendPing() {
+    ++count_;
+    aos::Sender<examples::Ping>::Builder msg = sender_.MakeBuilder();
+    examples::Ping::Builder builder = msg.MakeBuilder<examples::Ping>();
+    builder.add_value(count_);
+    builder.add_send_time(
+        event_loop_->monotonic_now().time_since_epoch().count());
+    CHECK(msg.Send(builder.Finish()));
+    VLOG(2) << "Sending ping";
+  }
+
+  void HandlePong(const examples::Pong &pong) {
+    const aos::monotonic_clock::time_point monotonic_send_time(
+        chrono::nanoseconds(pong.initial_send_time()));
+    const aos::monotonic_clock::time_point monotonic_now =
+        event_loop_->monotonic_now();
+
+    const chrono::nanoseconds round_trip_time =
+        monotonic_now - monotonic_send_time;
+
+    if (pong.value() == count_) {
+      VLOG(1) << "Elapsed time " << round_trip_time.count() << " ns "
+              << FlatbufferToJson(&pong);
+    } else {
+      VLOG(1) << "Missmatched pong message";
+    }
+  }
+
+ private:
+  EventLoop *event_loop_;
+  aos::Sender<examples::Ping> sender_;
+  TimerHandler *timer_handle_;
+  int count_ = 0;
+};
+
+}  // namespace aos
+
+int main(int argc, char **argv) {
+  FLAGS_logtostderr = true;
+  google::InitGoogleLogging(argv[0]);
+  ::gflags::ParseCommandLineFlags(&argc, &argv, true);
+
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig("aos/events/config.fb.json");
+
+  ::aos::ShmEventLoop event_loop(&config.message());
+
+  aos::Ping ping(&event_loop);
+
+  event_loop.Run();
+
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/aos/events/pingpong.fbs b/aos/events/pingpong.fbs
new file mode 100644
index 0000000..67e5015
--- /dev/null
+++ b/aos/events/pingpong.fbs
@@ -0,0 +1,14 @@
+namespace aos.examples;
+
+table Ping {
+  value:int;
+  send_time:long;
+}
+
+table Pong {
+  value:int;
+  initial_send_time:long;
+}
+
+root_type Ping;
+root_type Pong;
diff --git a/aos/events/pong.cc b/aos/events/pong.cc
new file mode 100644
index 0000000..1504bfb
--- /dev/null
+++ b/aos/events/pong.cc
@@ -0,0 +1,54 @@
+#include <chrono>
+
+#include "aos/configuration.h"
+#include "aos/events/pingpong_generated.h"
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "gflags/gflags.h"
+#include "glog/logging.h"
+
+namespace aos {
+
+namespace chrono = std::chrono;
+
+class Pong {
+ public:
+  Pong(EventLoop *event_loop)
+      : event_loop_(event_loop),
+        sender_(event_loop_->MakeSender<examples::Pong>("/test")) {
+    event_loop_->MakeWatcher("/test", [this](const examples::Ping &ping) {
+      aos::Sender<examples::Pong>::Builder msg = sender_.MakeBuilder();
+      examples::Pong::Builder builder = msg.MakeBuilder<examples::Pong>();
+      builder.add_value(ping.value());
+      builder.add_initial_send_time(ping.send_time());
+      CHECK(msg.Send(builder.Finish()));
+    });
+
+    event_loop_->SetRuntimeRealtimePriority(5);
+  }
+
+ private:
+  EventLoop *event_loop_;
+  aos::Sender<examples::Pong> sender_;
+};
+
+}  // namespace aos
+
+int main(int argc, char **argv) {
+  FLAGS_logtostderr = true;
+  google::InitGoogleLogging(argv[0]);
+  ::gflags::ParseCommandLineFlags(&argc, &argv, true);
+
+  aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+      aos::configuration::ReadConfig("aos/events/config.fb.json");
+
+  ::aos::ShmEventLoop event_loop(&config.message());
+
+  aos::Pong ping(&event_loop);
+
+  event_loop.Run();
+
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/aos/events/raw-event-loop.h b/aos/events/raw-event-loop.h
deleted file mode 100644
index 887c7ab..0000000
--- a/aos/events/raw-event-loop.h
+++ /dev/null
@@ -1,179 +0,0 @@
-#ifndef _AOS_EVENTS_RAW_EVENT_LOOP_H_
-#define _AOS_EVENTS_RAW_EVENT_LOOP_H_
-
-#include <atomic>
-#include <memory>
-#include <string>
-#include "aos/queue.h"
-#include "aos/time/time.h"
-
-// This file contains raw versions of the classes in event-loop.h.
-//
-// Users should look exclusively at event-loop.h. Only people who wish to
-// implement a new IPC layer (like a fake layer for example) may wish to use
-// these classes.
-namespace aos {
-
-// Raw version of fetcher. Contains a local variable that the fetcher will
-// update.
-// It is the job of the typed version to cast this to the appropriate type.
-class RawFetcher {
- public:
-  RawFetcher() {}
-  virtual ~RawFetcher() {}
-
-  // Non-blocking fetch of the next message in the queue. Returns true if there
-  // was a new message and we got it.
-  virtual bool FetchNext() = 0;
-  // Non-blocking fetch of the latest message:
-  virtual bool Fetch() = 0;
-
-  const void *most_recent() { return most_recent_; }
-
- protected:
-  RawFetcher(const RawFetcher &) = delete;
-  RawFetcher &operator=(const RawFetcher &) = delete;
-  void set_most_recent(const void *most_recent) { most_recent_ = most_recent; }
-
- private:
-  const void *most_recent_ = nullptr;
-};
-
-// Raw version of sender. Sending a message is a 3 part process. Fetch an opaque
-// token, cast that token to the message type, populate and then calling one of
-// Send() or Free().
-class RawSender {
- public:
-  RawSender() {}
-  virtual ~RawSender() {}
-
-  virtual aos::Message *GetMessage() = 0;
-
-  virtual void Free(aos::Message *msg) = 0;
-
-  virtual bool Send(aos::Message *msg) = 0;
-
-  // Call operator that calls Free().
-  template <typename T>
-  void operator()(T *t) {
-    Free(t);
-  }
-
-  virtual const char *name() const = 0;
-
- protected:
-  RawSender(const RawSender &) = delete;
-  RawSender &operator=(const RawSender &) = delete;
-};
-
-// Opaque Information extracted from a particular type passed to the underlying
-// system so that it knows how much memory to allocate etc.
-struct QueueTypeInfo {
-  // Message size:
-  size_t size;
-  // This should be a globally unique identifier for the type.
-  int hash;
-  // Config parameter for how long the queue should be.
-  int queue_length;
-
-  template <typename T>
-  static QueueTypeInfo Get() {
-    QueueTypeInfo info;
-    info.size = sizeof(T);
-    info.hash = T::kHash;
-    info.queue_length = T::kQueueLength;
-    return info;
-  }
-
-  // Necessary for the comparison of QueueTypeInfo objects in the
-  // SimulatedEventLoop.
-  bool operator<(const QueueTypeInfo &other) const {
-    if (size != other.size) return size < other.size;
-    if (hash != other.hash) return hash < other.hash;
-    return queue_length < other.queue_length;
-  }
-};
-
-// Interface for timers
-class TimerHandler {
- public:
-  virtual ~TimerHandler() {}
-
-  // Timer should sleep until base, base + offset, base + offset * 2, ...
-  // If repeat_offset isn't set, the timer only expires once.
-  virtual void Setup(monotonic_clock::time_point base,
-                     monotonic_clock::duration repeat_offset =
-                         ::aos::monotonic_clock::zero()) = 0;
-
-  // Stop future calls to callback().
-  virtual void Disable() = 0;
-};
-
-// Interface for phased loops.  They are built on timers.
-class PhasedLoopHandler {
- public:
-  virtual ~PhasedLoopHandler() {}
-
-  // Sets the interval and offset.  Any changes to interval and offset only take
-  // effect when the handler finishes running.
-  virtual void set_interval_and_offset(
-      const monotonic_clock::duration interval,
-      const monotonic_clock::duration offset) = 0;
-};
-
-class EventScheduler;
-
-// Virtual base class for all event queue-types.
-class RawEventLoop {
- public:
-  virtual ~RawEventLoop() {}
-
-  // Current time.
-  virtual monotonic_clock::time_point monotonic_now() = 0;
-
-  // The passed in function will be called when the event loop starts.
-  // Use this to run code once the thread goes into "real-time-mode",
-  virtual void OnRun(::std::function<void()> on_run) = 0;
-
-  // Sets the name of the event loop.
-  virtual void set_name(const char *name) = 0;
-
-  // Threadsafe.
-  bool is_running() const { return is_running_.load(); }
-
-  // Creates a timer that executes callback when the timer expires
-  // Returns a TimerHandle for configuration of the timer
-  virtual TimerHandler *AddTimer(::std::function<void()> callback) = 0;
-
-  // Creates a timer that executes callback periodically at the specified
-  // interval and offset.  Returns a PhasedLoopHandler for interacting with the
-  // timer.
-  virtual PhasedLoopHandler *AddPhasedLoop(
-      ::std::function<void(int)> callback,
-      const monotonic_clock::duration interval,
-      const monotonic_clock::duration offset = ::std::chrono::seconds(0)) = 0;
-
- protected:
-  friend class EventScheduler;
-  void set_is_running(bool value) { is_running_.store(value); }
-
-  // Will send new messages from (path, type).
-  virtual std::unique_ptr<RawSender> MakeRawSender(
-      const std::string &path, const QueueTypeInfo &type) = 0;
-
-  // Will fetch new messages from (path, type).
-  virtual std::unique_ptr<RawFetcher> MakeRawFetcher(
-      const std::string &path, const QueueTypeInfo &type) = 0;
-
-  // Will watch (path, type) for new messages
-  virtual void MakeRawWatcher(
-      const std::string &path, const QueueTypeInfo &type,
-      std::function<void(const Message *message)> watcher) = 0;
-
- private:
-  ::std::atomic<bool> is_running_{false};
-};
-
-}  // namespace aos
-
-#endif  // _AOS_EVENTS_RAW_EVENT_LOOP_H_
diff --git a/aos/events/shm-event-loop.cc b/aos/events/shm-event-loop.cc
deleted file mode 100644
index 5034f0b..0000000
--- a/aos/events/shm-event-loop.cc
+++ /dev/null
@@ -1,507 +0,0 @@
-#include "aos/events/shm-event-loop.h"
-
-#include <sys/timerfd.h>
-#include <algorithm>
-#include <atomic>
-#include <chrono>
-#include <stdexcept>
-
-#include "aos/events/epoll.h"
-#include "aos/init.h"
-#include "aos/logging/logging.h"
-#include "aos/queue.h"
-#include "aos/util/phased_loop.h"
-
-namespace aos {
-
-ShmEventLoop::ShmEventLoop() {}
-
-namespace {
-
-namespace chrono = ::std::chrono;
-
-class ShmFetcher : public RawFetcher {
- public:
-  explicit ShmFetcher(RawQueue *queue) : queue_(queue) {
-    // Move index_ to point to the end of the queue as it is at construction
-    // time.  Also grab the oldest message but don't expose it to the user yet.
-    static constexpr Options<RawQueue> kOptions =
-        RawQueue::kFromEnd | RawQueue::kNonBlock;
-    msg_ = queue_->ReadMessageIndex(kOptions, &index_);
-  }
-  ~ShmFetcher() {
-    if (msg_) {
-      queue_->FreeMessage(msg_);
-    }
-  }
-
-  bool FetchNext() override {
-    const void *msg = queue_->ReadMessageIndex(RawQueue::kNonBlock, &index_);
-    // Only update the internal pointer if we got a new message.
-    if (msg != nullptr) {
-      queue_->FreeMessage(msg_);
-      msg_ = msg;
-      set_most_recent(msg_);
-    }
-    return msg != nullptr;
-  }
-
-  bool Fetch() override {
-    static constexpr Options<RawQueue> kOptions =
-        RawQueue::kFromEnd | RawQueue::kNonBlock;
-    const void *msg = queue_->ReadMessageIndex(kOptions, &index_);
-    // Only update the internal pointer if we got a new message.
-    if (msg != nullptr && msg != msg_) {
-      queue_->FreeMessage(msg_);
-      msg_ = msg;
-      set_most_recent(msg_);
-      return true;
-    } else {
-      // The message has to get freed if we didn't use it (and
-      // RawQueue::FreeMessage is ok to call on nullptr).
-      queue_->FreeMessage(msg);
-
-      // We have a message from construction time.  Give it to the user now.
-      if (msg_ != nullptr && most_recent() != msg_) {
-        set_most_recent(msg_);
-        return true;
-      } else {
-        return false;
-      }
-    }
-  }
-
- private:
-  int index_ = 0;
-  RawQueue *queue_;
-  const void *msg_ = nullptr;
-};
-
-class ShmSender : public RawSender {
- public:
-  explicit ShmSender(RawQueue *queue) : queue_(queue) {}
-
-  ::aos::Message *GetMessage() override {
-    return reinterpret_cast<::aos::Message *>(queue_->GetMessage());
-  }
-
-  void Free(::aos::Message *msg) override { queue_->FreeMessage(msg); }
-
-  bool Send(::aos::Message *msg) override {
-    assert(queue_ != nullptr);
-    {
-      // TODO(austin): This lets multiple senders reorder messages since time
-      // isn't acquired with a lock held.
-      if (msg->sent_time == monotonic_clock::min_time) {
-        msg->sent_time = monotonic_clock::now();
-      }
-    }
-    return queue_->WriteMessage(msg, RawQueue::kOverride);
-  }
-
-  const char *name() const override { return queue_->name(); }
-
- private:
-  RawQueue *queue_;
-};
-
-}  // namespace
-
-namespace internal {
-
-// Class to manage the state for a Watcher.
-class WatcherThreadState {
- public:
-  WatcherThreadState(
-      ShmEventLoop::ThreadState *thread_state, RawQueue *queue,
-      ::std::function<void(const ::aos::Message *message)> watcher)
-      : thread_state_(thread_state),
-        queue_(queue),
-        index_(0),
-        watcher_(::std::move(watcher)) {}
-
-  ~WatcherThreadState() {
-    // Only kill the thread if it is running.
-    if (running_) {
-      // TODO(austin): CHECK that we aren't RT here.
-
-      // Try joining.  If we fail, we weren't asleep on the condition in the
-      // queue.  So hit it again and again until that's true.
-      struct timespec end_time;
-      AOS_PCHECK(clock_gettime(CLOCK_REALTIME, &end_time) == 0);
-      while (true) {
-        void *retval = nullptr;
-        end_time.tv_nsec += 100000000;
-        if (end_time.tv_nsec > 1000000000L) {
-          end_time.tv_nsec -= 1000000000L;
-          ++end_time.tv_sec;
-        }
-        int ret = pthread_timedjoin_np(pthread_, &retval, &end_time);
-        if (ret == ETIMEDOUT) continue;
-        AOS_PCHECK(ret == 0);
-        break;
-      }
-    }
-  }
-
-  // Starts the thread and waits until it is running.
-  void Start() {
-    AOS_PCHECK(pthread_create(&pthread_, nullptr, &StaticRun, this) == 0);
-    IPCRecursiveMutexLocker locker(&thread_started_mutex_);
-    if (locker.owner_died()) ::aos::Die("Owner died");
-    while (!running_) {
-      AOS_CHECK(!thread_started_condition_.Wait());
-    }
-  }
-
-  void GrabQueueIndex() {
-    // Right after we are signaled to start, point index to the current index
-    // so we don't read any messages received before now.  Otherwise we will
-    // get a significantly delayed read.
-    static constexpr Options<RawQueue> kOptions =
-        RawQueue::kFromEnd | RawQueue::kNonBlock;
-    const void *msg = queue_->ReadMessageIndex(kOptions, &index_);
-    if (msg) {
-      queue_->FreeMessage(msg);
-    }
-  }
-
- private:
-  // Runs Run given a WatcherThreadState as the argument.  This is an adapter
-  // between pthreads and Run.
-  static void *StaticRun(void *arg) {
-    WatcherThreadState *watcher_thread_state =
-        reinterpret_cast<WatcherThreadState *>(arg);
-    watcher_thread_state->Run();
-    return nullptr;
-  }
-
-  // Runs the watcher callback on new messages.
-  void Run() {
-    ::aos::SetCurrentThreadName(thread_state_->name() + ".watcher");
-
-    // Signal the main thread that we are now ready.
-    thread_state_->MaybeSetCurrentThreadRealtimePriority();
-    {
-      IPCRecursiveMutexLocker locker(&thread_started_mutex_);
-      if (locker.owner_died()) ::aos::Die("Owner died");
-      running_ = true;
-      thread_started_condition_.Broadcast();
-    }
-
-    // Wait for the global start before handling events.
-    thread_state_->WaitForStart();
-
-    // Bail immediately if we are supposed to stop.
-    if (!thread_state_->is_running()) {
-      ::aos::UnsetCurrentThreadRealtimePriority();
-      return;
-    }
-
-    const void *msg = nullptr;
-    while (true) {
-      msg = queue_->ReadMessageIndex(RawQueue::kBlock, &index_,
-                                     chrono::seconds(1));
-      // We hit a timeout.  Confirm that we should be running and retry.  Note,
-      // is_running is threadsafe (it's an atomic underneath).  Worst case, we
-      // check again in a second.
-      if (msg == nullptr) {
-        if (!thread_state_->is_running()) break;
-        continue;
-      }
-
-      {
-        // Grab the lock so that only one callback can be called at a time.
-        MutexLocker locker(&thread_state_->mutex_);
-        if (!thread_state_->is_running()) break;
-
-        watcher_(reinterpret_cast<const Message *>(msg));
-        // watcher_ may have exited the event loop.
-        if (!thread_state_->is_running()) break;
-      }
-      // Drop the reference.
-      queue_->FreeMessage(msg);
-    }
-
-    // And drop the last reference.
-    queue_->FreeMessage(msg);
-    // Now that everything is cleaned up, drop RT priority before destroying the
-    // thread.
-    ::aos::UnsetCurrentThreadRealtimePriority();
-  }
-  pthread_t pthread_;
-  ShmEventLoop::ThreadState *thread_state_;
-  RawQueue *queue_;
-  int32_t index_;
-  bool running_ = false;
-
-  ::std::function<void(const Message *message)> watcher_;
-
-  // Mutex and condition variable used to wait until the thread is started
-  // before going RT.
-  ::aos::Mutex thread_started_mutex_;
-  ::aos::Condition thread_started_condition_{&thread_started_mutex_};
-};
-
-// Adapter class to adapt a timerfd to a TimerHandler.
-// The part of the API which is accessed by the TimerHandler interface needs to
-// be threadsafe.  This means Setup and Disable.
-class TimerHandlerState : public TimerHandler {
- public:
-  TimerHandlerState(ShmEventLoop *shm_event_loop, ::std::function<void()> fn)
-      : shm_event_loop_(shm_event_loop), fn_(::std::move(fn)) {
-    shm_event_loop_->epoll_.OnReadable(timerfd_.fd(), [this]() {
-      MutexLocker locker(&shm_event_loop_->thread_state_.mutex_);
-      timerfd_.Read();
-      fn_();
-    });
-  }
-
-  ~TimerHandlerState() { shm_event_loop_->epoll_.DeleteFd(timerfd_.fd()); }
-
-  void Setup(monotonic_clock::time_point base,
-             monotonic_clock::duration repeat_offset) override {
-    // SetTime is threadsafe already.
-    timerfd_.SetTime(base, repeat_offset);
-  }
-
-  void Disable() override {
-    // Disable is also threadsafe already.
-    timerfd_.Disable();
-  }
-
- private:
-  ShmEventLoop *shm_event_loop_;
-
-  TimerFd timerfd_;
-
-  // Function to be run on the thread
-  ::std::function<void()> fn_;
-};
-
-// Adapter class to the timerfd and PhasedLoop.
-// The part of the API which is accessed by the PhasedLoopHandler interface
-// needs to be threadsafe.  This means set_interval_and_offset
-class PhasedLoopHandler : public ::aos::PhasedLoopHandler {
- public:
-  PhasedLoopHandler(ShmEventLoop *shm_event_loop, ::std::function<void(int)> fn,
-                    const monotonic_clock::duration interval,
-                    const monotonic_clock::duration offset)
-      : shm_event_loop_(shm_event_loop),
-        phased_loop_(interval, shm_event_loop_->monotonic_now(), offset),
-        fn_(::std::move(fn)) {
-    shm_event_loop_->epoll_.OnReadable(timerfd_.fd(), [this]() {
-      MutexLocker locker(&shm_event_loop_->thread_state_.mutex_);
-      {
-        MutexLocker locker(&mutex_);
-        timerfd_.Read();
-      }
-      // Call the function.  To avoid needing a recursive mutex, drop the lock
-      // before running the function.
-      fn_(cycles_elapsed_);
-      {
-        MutexLocker locker(&mutex_);
-        Reschedule();
-      }
-    });
-  }
-
-  ~PhasedLoopHandler() { shm_event_loop_->epoll_.DeleteFd(timerfd_.fd()); }
-
-  void set_interval_and_offset(
-      const monotonic_clock::duration interval,
-      const monotonic_clock::duration offset) override {
-    MutexLocker locker(&mutex_);
-    phased_loop_.set_interval_and_offset(interval, offset);
-  }
-
-  void Startup() {
-    MutexLocker locker(&mutex_);
-    phased_loop_.Reset(shm_event_loop_->monotonic_now());
-    Reschedule();
-  }
-
- private:
-  // Reschedules the timer.  Must be called with the mutex held.
-  void Reschedule() {
-    cycles_elapsed_ = phased_loop_.Iterate(shm_event_loop_->monotonic_now());
-    timerfd_.SetTime(phased_loop_.sleep_time(), ::aos::monotonic_clock::zero());
-  }
-
-  ShmEventLoop *shm_event_loop_;
-
-  // Mutex to protect access to the timerfd_ (not strictly necessary), and the
-  // phased_loop (necessary).
-  ::aos::Mutex mutex_;
-
-  TimerFd timerfd_;
-  time::PhasedLoop phased_loop_;
-
-  int cycles_elapsed_ = 1;
-
-  // Function to be run
-  const ::std::function<void(int)> fn_;
-};
-}  // namespace internal
-
-::std::unique_ptr<RawFetcher> ShmEventLoop::MakeRawFetcher(
-    const ::std::string &path, const QueueTypeInfo &type) {
-  return ::std::unique_ptr<RawFetcher>(new ShmFetcher(
-      RawQueue::Fetch(path.c_str(), type.size, type.hash, type.queue_length)));
-}
-
-::std::unique_ptr<RawSender> ShmEventLoop::MakeRawSender(
-    const ::std::string &path, const QueueTypeInfo &type) {
-  Take(path);
-  return ::std::unique_ptr<RawSender>(new ShmSender(
-      RawQueue::Fetch(path.c_str(), type.size, type.hash, type.queue_length)));
-}
-
-void ShmEventLoop::MakeRawWatcher(
-    const ::std::string &path, const QueueTypeInfo &type,
-    ::std::function<void(const Message *message)> watcher) {
-  Take(path);
-  ::std::unique_ptr<internal::WatcherThreadState> state(
-      new internal::WatcherThreadState(
-          &thread_state_, RawQueue::Fetch(path.c_str(), type.size, type.hash,
-                                          type.queue_length),
-          std::move(watcher)));
-  watchers_.push_back(::std::move(state));
-}
-
-TimerHandler *ShmEventLoop::AddTimer(::std::function<void()> callback) {
-  ::std::unique_ptr<internal::TimerHandlerState> timer(
-      new internal::TimerHandlerState(this, ::std::move(callback)));
-
-  timers_.push_back(::std::move(timer));
-
-  return timers_.back().get();
-}
-
-PhasedLoopHandler *ShmEventLoop::AddPhasedLoop(
-    ::std::function<void(int)> callback,
-    const monotonic_clock::duration interval,
-    const monotonic_clock::duration offset) {
-  ::std::unique_ptr<internal::PhasedLoopHandler> phased_loop(
-      new internal::PhasedLoopHandler(this, ::std::move(callback), interval,
-                                      offset));
-
-  phased_loops_.push_back(::std::move(phased_loop));
-
-  return phased_loops_.back().get();
-}
-
-void ShmEventLoop::OnRun(::std::function<void()> on_run) {
-  on_run_.push_back(::std::move(on_run));
-}
-
-void ShmEventLoop::set_name(const char *name) { thread_state_.name_ = name; }
-
-void ShmEventLoop::Run() {
-  // Start all the watcher threads.
-  for (::std::unique_ptr<internal::WatcherThreadState> &watcher : watchers_) {
-    watcher->Start();
-  }
-
-  ::aos::SetCurrentThreadName(thread_state_.name());
-
-  // Now, all the threads are up.  Lock everything into memory and go RT.
-  if (thread_state_.priority_ != -1) {
-    ::aos::InitRT();
-  }
-  thread_state_.MaybeSetCurrentThreadRealtimePriority();
-  set_is_running(true);
-
-  // Now that we are realtime (but before the OnRun handlers run), snap the
-  // queue index.
-  for (::std::unique_ptr<internal::WatcherThreadState> &watcher : watchers_) {
-    watcher->GrabQueueIndex();
-  }
-
-  // Now that we are RT, run all the OnRun handlers.
-  for (const auto &run : on_run_) {
-    run();
-  }
-
-  // Start up all the phased loops.
-  for (::std::unique_ptr<internal::PhasedLoopHandler> &phased_loop :
-       phased_loops_) {
-    phased_loop->Startup();
-  }
-  // TODO(austin): We don't need a separate watcher thread if there are only
-  // watchers and fetchers.  Could lazily create the epoll loop and pick a
-  // victim watcher to run in this thread.
-  // Trigger all the threads to start now.
-  thread_state_.Start();
-
-  // And start our main event loop which runs all the timers and handles Quit.
-  epoll_.Run();
-
-  // Once epoll exits, there is no useful nonrt work left to do.
-  set_is_running(false);
-
-  // Signal all the watcher threads to exit.  After this point, no more
-  // callbacks will be handled.
-  thread_state_.Exit();
-
-  // Nothing time or synchronization critical needs to happen after this point.
-  // Drop RT priority.
-  ::aos::UnsetCurrentThreadRealtimePriority();
-
-  // The watcher threads get cleaned up in the destructor.
-}
-
-void ShmEventLoop::ThreadState::Start() {
-  MutexLocker locker(&mutex_);
-  loop_running_ = true;
-  if (loop_finished_) ::aos::Die("Cannot restart an ShmEventLoop()");
-  loop_running_cond_.Broadcast();
-}
-
-void ShmEventLoop::ThreadState::WaitForStart() {
-  MutexLocker locker(&mutex_);
-  while (!(loop_running_ || loop_finished_)) {
-    Condition::WaitResult wait_result =
-        loop_running_cond_.WaitTimed(chrono::milliseconds(1000));
-    if (wait_result == Condition::WaitResult::kOwnerDied) {
-      ::aos::Die("ShmEventLoop mutex lock problem.\n");
-    }
-  }
-}
-
-void ShmEventLoop::ThreadState::MaybeSetCurrentThreadRealtimePriority() {
-  if (priority_ != -1) {
-    ::aos::SetCurrentThreadRealtimePriority(priority_);
-  }
-}
-
-void ShmEventLoop::Exit() { epoll_.Quit(); }
-
-void ShmEventLoop::ThreadState::Exit() {
-  IPCRecursiveMutexLocker locker(&mutex_);
-  if (locker.owner_died()) ::aos::Die("Owner died");
-  loop_running_ = false;
-  loop_finished_ = true;
-  loop_running_cond_.Broadcast();
-}
-
-ShmEventLoop::~ShmEventLoop() {
-  if (is_running()) {
-    ::aos::Die("ShmEventLoop destroyed while running\n");
-  }
-}
-
-void ShmEventLoop::Take(const ::std::string &path) {
-  if (is_running()) {
-    ::aos::Die("Cannot add new objects while running.\n");
-  }
-
-  const auto prior = ::std::find(taken_.begin(), taken_.end(), path);
-  if (prior != taken_.end()) {
-    ::aos::Die("%s is already being used.", path.c_str());
-  } else {
-    taken_.emplace_back(path);
-  }
-}
-
-}  // namespace aos
diff --git a/aos/events/shm-event-loop.h b/aos/events/shm-event-loop.h
deleted file mode 100644
index 5db8319..0000000
--- a/aos/events/shm-event-loop.h
+++ /dev/null
@@ -1,124 +0,0 @@
-#ifndef AOS_EVENTS_SHM_EVENT_LOOP_H_
-#define AOS_EVENTS_SHM_EVENT_LOOP_H_
-
-#include <unordered_set>
-#include <vector>
-
-#include "aos/condition.h"
-#include "aos/events/epoll.h"
-#include "aos/events/event-loop.h"
-#include "aos/mutex/mutex.h"
-
-namespace aos {
-namespace internal {
-
-class WatcherThreadState;
-class TimerHandlerState;
-class PhasedLoopHandler;
-
-}  // namespace internal
-
-// Specialization of EventLoop that is built from queues running out of shared
-// memory. See more details at aos/queue.h
-//
-// This object must be interacted with from one thread, but the Senders and
-// Fetchers may be used from multiple threads afterwords (as long as their
-// destructors are called back in one thread again)
-class ShmEventLoop : public EventLoop {
- public:
-  ShmEventLoop();
-  ~ShmEventLoop() override;
-
-  ::aos::monotonic_clock::time_point monotonic_now() override {
-    return ::aos::monotonic_clock::now();
-  }
-
-  ::std::unique_ptr<RawSender> MakeRawSender(
-      const ::std::string &path, const QueueTypeInfo &type) override;
-  ::std::unique_ptr<RawFetcher> MakeRawFetcher(
-      const ::std::string &path, const QueueTypeInfo &type) override;
-
-  void MakeRawWatcher(
-      const ::std::string &path, const QueueTypeInfo &type,
-      ::std::function<void(const aos::Message *message)> watcher) override;
-
-  TimerHandler *AddTimer(::std::function<void()> callback) override;
-  ::aos::PhasedLoopHandler *AddPhasedLoop(
-      ::std::function<void(int)> callback,
-      const monotonic_clock::duration interval,
-      const monotonic_clock::duration offset =
-          ::std::chrono::seconds(0)) override;
-
-  void OnRun(::std::function<void()> on_run) override;
-  void Run();
-  void Exit();
-
-  // TODO(austin): Add a function to register control-C call.
-
-  void SetRuntimeRealtimePriority(int priority) override {
-    if (is_running()) {
-      ::aos::Die("Cannot set realtime priority while running.");
-    }
-    thread_state_.priority_ = priority;
-  }
-
-  void set_name(const char *name) override;
-
- private:
-  friend class internal::WatcherThreadState;
-  friend class internal::TimerHandlerState;
-  friend class internal::PhasedLoopHandler;
-  // This ThreadState ensures that two watchers in the same loop cannot be
-  // triggered concurrently.  Because watchers block threads indefinitely, this
-  // has to be shared_ptr in case the EventLoop is destroyed before the thread
-  // receives any new events.
-  class ThreadState {
-   public:
-    void WaitForStart();
-
-    bool is_running() { return loop_running_; }
-
-    void Start();
-
-    void Exit();
-
-    void MaybeSetCurrentThreadRealtimePriority();
-
-    const ::std::string &name() const { return name_; }
-
-   private:
-    friend class internal::WatcherThreadState;
-    friend class internal::TimerHandlerState;
-    friend class internal::PhasedLoopHandler;
-    friend class ShmEventLoop;
-
-    // This mutex ensures that only one watch event happens at a time.
-    ::aos::Mutex mutex_;
-    // Block on this until the loop starts.
-    ::aos::Condition loop_running_cond_{&mutex_};
-    // Used to notify watchers that the loop is done.
-    ::std::atomic<bool> loop_running_{false};
-    bool loop_finished_ = false;
-    int priority_ = -1;
-
-    // Immutable after Start is called.
-    ::std::string name_;
-  };
-
-  // Tracks that we can't have multiple watchers or a sender and a watcher (or
-  // multiple senders) on a single queue (path).
-  void Take(const ::std::string &path);
-
-  ::std::vector<::std::function<void()>> on_run_;
-  ThreadState thread_state_;
-  ::std::vector<::std::string> taken_;
-  internal::EPoll epoll_;
-
-  ::std::vector<::std::unique_ptr<internal::TimerHandlerState>> timers_;
-  ::std::vector<::std::unique_ptr<internal::PhasedLoopHandler>> phased_loops_;
-  ::std::vector<::std::unique_ptr<internal::WatcherThreadState>> watchers_;
-};
-
-}  // namespace aos
-
-#endif  // AOS_EVENTS_SHM_EVENT_LOOP_H_
diff --git a/aos/events/shm_event_loop.cc b/aos/events/shm_event_loop.cc
new file mode 100644
index 0000000..5a88717
--- /dev/null
+++ b/aos/events/shm_event_loop.cc
@@ -0,0 +1,611 @@
+#include "glog/logging.h"
+
+#include "aos/events/shm_event_loop.h"
+
+#include <sys/mman.h>
+#include <sys/stat.h>
+#include <sys/timerfd.h>
+#include <sys/types.h>
+#include <unistd.h>
+#include <algorithm>
+#include <atomic>
+#include <chrono>
+#include <stdexcept>
+
+#include "aos/events/epoll.h"
+#include "aos/ipc_lib/lockless_queue.h"
+#include "aos/realtime.h"
+#include "aos/util/phased_loop.h"
+
+DEFINE_string(shm_base, "/dev/shm/aos",
+              "Directory to place queue backing mmaped files in.");
+DEFINE_uint32(permissions, 0770,
+              "Permissions to make shared memory files and folders.");
+
+namespace aos {
+
+std::string ShmFolder(const Channel *channel) {
+  CHECK(channel->has_name());
+  CHECK_EQ(channel->name()->string_view()[0], '/');
+  return FLAGS_shm_base + channel->name()->str() + "/";
+}
+std::string ShmPath(const Channel *channel) {
+  CHECK(channel->has_type());
+  return ShmFolder(channel) + channel->type()->str() + ".v0";
+}
+
+class MMapedQueue {
+ public:
+  MMapedQueue(const Channel *channel) {
+    std::string path = ShmPath(channel);
+
+    // TODO(austin): Pull these out into the config if there is a need.
+    config_.num_watchers = 10;
+    config_.num_senders = 10;
+    config_.queue_size = 2 * channel->frequency();
+    config_.message_data_size = channel->max_size();
+
+    size_ = ipc_lib::LocklessQueueMemorySize(config_);
+
+    MkdirP(path);
+
+    // There are 2 cases.  Either the file already exists, or it does not
+    // already exist and we need to create it.  Start by trying to create it. If
+    // that fails, the file has already been created and we can open it
+    // normally..  Once the file has been created it wil never be deleted.
+    fd_ = open(path.c_str(), O_RDWR | O_CREAT | O_EXCL,
+               O_CLOEXEC | FLAGS_permissions);
+    if (fd_ == -1 && errno == EEXIST) {
+      VLOG(1) << path << " already created.";
+      // File already exists.
+      fd_ = open(path.c_str(), O_RDWR, O_CLOEXEC);
+      PCHECK(fd_ != -1) << ": Failed to open " << path;
+      while (true) {
+        struct stat st;
+        PCHECK(fstat(fd_, &st) == 0);
+        if (st.st_size != 0) {
+          CHECK_EQ(static_cast<size_t>(st.st_size), size_)
+              << ": Size of " << path
+              << " doesn't match expected size of backing queue file.  Did the "
+                 "queue definition change?";
+          break;
+        } else {
+          // The creating process didn't get around to it yet.  Give it a bit.
+          std::this_thread::sleep_for(std::chrono::milliseconds(10));
+          VLOG(1) << path << " is zero size, waiting";
+        }
+      }
+    } else {
+      VLOG(1) << "Created " << path;
+      PCHECK(fd_ != -1) << ": Failed to open " << path;
+      PCHECK(ftruncate(fd_, size_) == 0);
+    }
+
+    data_ = mmap(NULL, size_, PROT_READ | PROT_WRITE, MAP_SHARED, fd_, 0);
+    PCHECK(data_ != MAP_FAILED);
+
+    ipc_lib::InitializeLocklessQueueMemory(memory(), config_);
+  }
+
+  ~MMapedQueue() {
+    PCHECK(munmap(data_, size_) == 0);
+    PCHECK(close(fd_) == 0);
+  }
+
+  ipc_lib::LocklessQueueMemory *memory() const {
+    return reinterpret_cast<ipc_lib::LocklessQueueMemory *>(data_);
+  }
+
+  const ipc_lib::LocklessQueueConfiguration &config() const {
+    return config_;
+  }
+
+ private:
+  void MkdirP(absl::string_view path) {
+    struct stat st;
+    auto last_slash_pos = path.find_last_of("/");
+
+    std::string folder(last_slash_pos == absl::string_view::npos
+                           ? absl::string_view("")
+                           : path.substr(0, last_slash_pos));
+    if (stat(folder.c_str(), &st) == -1) {
+      PCHECK(errno == ENOENT);
+      CHECK_NE(folder, "") << ": Base path doesn't exist";
+      MkdirP(folder);
+      VLOG(1) << "Creating " << folder;
+      PCHECK(mkdir(folder.c_str(), FLAGS_permissions) == 0);
+    }
+  }
+
+  ipc_lib::LocklessQueueConfiguration config_;
+
+  int fd_;
+
+  size_t size_;
+  void *data_;
+};
+
+// Returns the portion of the path after the last /.
+absl::string_view Filename(absl::string_view path) {
+  auto last_slash_pos = path.find_last_of("/");
+
+  return last_slash_pos == absl::string_view::npos
+             ? path
+             : path.substr(last_slash_pos + 1, path.size());
+}
+
+ShmEventLoop::ShmEventLoop(const Configuration *configuration)
+    : EventLoop(configuration), name_(Filename(program_invocation_name)) {}
+
+namespace {
+
+namespace chrono = ::std::chrono;
+
+class ShmFetcher : public RawFetcher {
+ public:
+  explicit ShmFetcher(const Channel *channel)
+      : lockless_queue_memory_(channel),
+        lockless_queue_(lockless_queue_memory_.memory(),
+                        lockless_queue_memory_.config()),
+        data_storage_(static_cast<AlignedChar *>(aligned_alloc(
+                          alignof(AlignedChar), channel->max_size())),
+                      &free) {
+    context_.data = nullptr;
+    // Point the queue index at the next index to read starting now.  This
+    // makes it such that FetchNext will read the next message sent after
+    // the fetcher is created.
+    PointAtNextQueueIndex();
+  }
+
+  ~ShmFetcher() { data_ = nullptr; }
+
+  // Points the next message to fetch at the queue index which will be
+  // populated next.
+  void PointAtNextQueueIndex() {
+    actual_queue_index_ = lockless_queue_.LatestQueueIndex();
+    if (!actual_queue_index_.valid()) {
+      // Nothing in the queue.  The next element will show up at the 0th
+      // index in the queue.
+      actual_queue_index_ =
+          ipc_lib::QueueIndex::Zero(lockless_queue_.queue_size());
+    } else {
+      actual_queue_index_ = actual_queue_index_.Increment();
+    }
+  }
+
+  bool FetchNext() override {
+    // TODO(austin): Write a test which starts with nothing in the queue,
+    // and then calls FetchNext() after something is sent.
+    // TODO(austin): Get behind and make sure it dies both here and with
+    // Fetch.
+    ipc_lib::LocklessQueue::ReadResult read_result = lockless_queue_.Read(
+        actual_queue_index_.index(), &context_.monotonic_sent_time,
+        &context_.realtime_sent_time, &context_.size,
+        reinterpret_cast<char *>(data_storage_.get()));
+    if (read_result == ipc_lib::LocklessQueue::ReadResult::GOOD) {
+      context_.queue_index = actual_queue_index_.index();
+      data_ = reinterpret_cast<char *>(data_storage_.get()) +
+              lockless_queue_.message_data_size() - context_.size;
+      context_.data = data_;
+      actual_queue_index_ = actual_queue_index_.Increment();
+    }
+
+    // Make sure the data wasn't modified while we were reading it.  This
+    // can only happen if you are reading the last message *while* it is
+    // being written to, which means you are pretty far behind.
+    CHECK(read_result != ipc_lib::LocklessQueue::ReadResult::OVERWROTE)
+        << ": Got behind while reading and the last message was modified "
+           "out "
+           "from under us while we were reading it.  Don't get so far "
+           "behind.";
+
+    CHECK(read_result != ipc_lib::LocklessQueue::ReadResult::TOO_OLD)
+        << ": The next message is no longer available.";
+    return read_result == ipc_lib::LocklessQueue::ReadResult::GOOD;
+  }
+
+  bool Fetch() override {
+    const ipc_lib::QueueIndex queue_index = lockless_queue_.LatestQueueIndex();
+    // actual_queue_index_ is only meaningful if it was set by Fetch or
+    // FetchNext.  This happens when valid_data_ has been set.  So, only
+    // skip checking if valid_data_ is true.
+    //
+    // Also, if the latest queue index is invalid, we are empty.  So there
+    // is nothing to fetch.
+    if ((data_ != nullptr &&
+         queue_index == actual_queue_index_.DecrementBy(1u)) ||
+        !queue_index.valid()) {
+      return false;
+    }
+
+    ipc_lib::LocklessQueue::ReadResult read_result =
+        lockless_queue_.Read(queue_index.index(), &context_.monotonic_sent_time,
+                             &context_.realtime_sent_time, &context_.size,
+                             reinterpret_cast<char *>(data_storage_.get()));
+    if (read_result == ipc_lib::LocklessQueue::ReadResult::GOOD) {
+      context_.queue_index = queue_index.index();
+      data_ = reinterpret_cast<char *>(data_storage_.get()) +
+              lockless_queue_.message_data_size() - context_.size;
+      context_.data = data_;
+      actual_queue_index_ = queue_index.Increment();
+    }
+
+    // Make sure the data wasn't modified while we were reading it.  This
+    // can only happen if you are reading the last message *while* it is
+    // being written to, which means you are pretty far behind.
+    CHECK(read_result != ipc_lib::LocklessQueue::ReadResult::OVERWROTE)
+        << ": Got behind while reading and the last message was modified "
+           "out "
+           "from under us while we were reading it.  Don't get so far "
+           "behind.";
+
+    CHECK(read_result != ipc_lib::LocklessQueue::ReadResult::NOTHING_NEW)
+        << ": Queue index went backwards.  This should never happen.";
+
+    // We fell behind between when we read the index and read the value.
+    // This isn't worth recovering from since this means we went to sleep
+    // for a long time in the middle of this function.
+    CHECK(read_result != ipc_lib::LocklessQueue::ReadResult::TOO_OLD)
+        << ": The next message is no longer available.";
+    return read_result == ipc_lib::LocklessQueue::ReadResult::GOOD;
+  }
+
+  bool RegisterWakeup(int priority) {
+    return lockless_queue_.RegisterWakeup(priority);
+  }
+
+  void UnregisterWakeup() { lockless_queue_.UnregisterWakeup(); }
+
+ private:
+  MMapedQueue lockless_queue_memory_;
+  ipc_lib::LocklessQueue lockless_queue_;
+
+  ipc_lib::QueueIndex actual_queue_index_ =
+      ipc_lib::LocklessQueue::empty_queue_index();
+
+  struct AlignedChar {
+    alignas(32) char data;
+  };
+
+  std::unique_ptr<AlignedChar, decltype(&free)> data_storage_;
+};
+
+class ShmSender : public RawSender {
+ public:
+  explicit ShmSender(const Channel *channel, const ShmEventLoop *shm_event_loop)
+      : RawSender(),
+        shm_event_loop_(shm_event_loop),
+        name_(channel->name()->str()),
+        lockless_queue_memory_(channel),
+        lockless_queue_(lockless_queue_memory_.memory(),
+                        lockless_queue_memory_.config()),
+        lockless_queue_sender_(lockless_queue_.MakeSender()) {}
+
+  void *data() override { return lockless_queue_sender_.Data(); }
+  size_t size() override { return lockless_queue_sender_.size(); }
+  bool Send(size_t size) override {
+    lockless_queue_sender_.Send(size);
+    lockless_queue_.Wakeup(shm_event_loop_->priority());
+    return true;
+  }
+
+  bool Send(void *msg, size_t length) override {
+    lockless_queue_sender_.Send(reinterpret_cast<char *>(msg), length);
+    lockless_queue_.Wakeup(shm_event_loop_->priority());
+    // TODO(austin): Return an error if we send too fast.
+    return true;
+  }
+
+  const absl::string_view name() const override { return name_; }
+
+ private:
+  const ShmEventLoop *shm_event_loop_;
+  std::string name_;
+  MMapedQueue lockless_queue_memory_;
+  ipc_lib::LocklessQueue lockless_queue_;
+  ipc_lib::LocklessQueue::Sender lockless_queue_sender_;
+};
+
+}  // namespace
+
+namespace internal {
+
+// Class to manage the state for a Watcher.
+class WatcherState {
+ public:
+  WatcherState(
+      const Channel *channel,
+      std::function<void(const Context &context, const void *message)> watcher)
+      : shm_fetcher_(channel), watcher_(watcher) {}
+
+  ~WatcherState() {}
+
+  // Points the next message to fetch at the queue index which will be populated
+  // next.
+  void PointAtNextQueueIndex() { shm_fetcher_.PointAtNextQueueIndex(); }
+
+  // Returns true if there is new data available.
+  bool HasNewData() {
+    if (!has_new_data_) {
+      has_new_data_ = shm_fetcher_.FetchNext();
+    }
+
+    return has_new_data_;
+  }
+
+  // Returns the time of the current data sample.
+  aos::monotonic_clock::time_point event_time() const {
+    return shm_fetcher_.context().monotonic_sent_time;
+  }
+
+  // Consumes the data by calling the callback.
+  void CallCallback() {
+    CHECK(has_new_data_);
+    watcher_(shm_fetcher_.context(), shm_fetcher_.most_recent_data());
+    has_new_data_ = false;
+  }
+
+  // Starts the thread and waits until it is running.
+  bool RegisterWakeup(int priority) {
+    return shm_fetcher_.RegisterWakeup(priority);
+  }
+
+  void UnregisterWakeup() { return shm_fetcher_.UnregisterWakeup(); }
+
+ private:
+  bool has_new_data_ = false;
+
+  ShmFetcher shm_fetcher_;
+
+  std::function<void(const Context &context, const void *message)> watcher_;
+};
+
+// Adapter class to adapt a timerfd to a TimerHandler.
+// The part of the API which is accessed by the TimerHandler interface needs to
+// be threadsafe.  This means Setup and Disable.
+class TimerHandlerState : public TimerHandler {
+ public:
+  TimerHandlerState(ShmEventLoop *shm_event_loop, ::std::function<void()> fn)
+      : shm_event_loop_(shm_event_loop), fn_(::std::move(fn)) {
+    shm_event_loop_->epoll_.OnReadable(timerfd_.fd(), [this]() {
+      timerfd_.Read();
+      fn_();
+    });
+  }
+
+  ~TimerHandlerState() { shm_event_loop_->epoll_.DeleteFd(timerfd_.fd()); }
+
+  void Setup(monotonic_clock::time_point base,
+             monotonic_clock::duration repeat_offset) override {
+    // SetTime is threadsafe already.
+    timerfd_.SetTime(base, repeat_offset);
+  }
+
+  void Disable() override {
+    // Disable is also threadsafe already.
+    timerfd_.Disable();
+  }
+
+ private:
+  ShmEventLoop *shm_event_loop_;
+
+  TimerFd timerfd_;
+
+  // Function to be run on the thread
+  ::std::function<void()> fn_;
+};
+
+// Adapter class to the timerfd and PhasedLoop.
+// The part of the API which is accessed by the PhasedLoopHandler interface
+// needs to be threadsafe.  This means set_interval_and_offset
+class PhasedLoopHandler : public ::aos::PhasedLoopHandler {
+ public:
+  PhasedLoopHandler(ShmEventLoop *shm_event_loop, ::std::function<void(int)> fn,
+                    const monotonic_clock::duration interval,
+                    const monotonic_clock::duration offset)
+      : shm_event_loop_(shm_event_loop),
+        phased_loop_(interval, shm_event_loop_->monotonic_now(), offset),
+        fn_(::std::move(fn)) {
+    shm_event_loop_->epoll_.OnReadable(timerfd_.fd(), [this]() {
+      timerfd_.Read();
+      // Call the function.  To avoid needing a recursive mutex, drop the lock
+      // before running the function.
+      fn_(cycles_elapsed_);
+      Reschedule();
+    });
+  }
+
+  ~PhasedLoopHandler() { shm_event_loop_->epoll_.DeleteFd(timerfd_.fd()); }
+
+  void set_interval_and_offset(
+      const monotonic_clock::duration interval,
+      const monotonic_clock::duration offset) override {
+    phased_loop_.set_interval_and_offset(interval, offset);
+  }
+
+  void Startup() {
+    phased_loop_.Reset(shm_event_loop_->monotonic_now());
+    Reschedule();
+  }
+
+ private:
+  // Reschedules the timer.  Must be called with the mutex held.
+  void Reschedule() {
+    cycles_elapsed_ = phased_loop_.Iterate(shm_event_loop_->monotonic_now());
+    timerfd_.SetTime(phased_loop_.sleep_time(), ::aos::monotonic_clock::zero());
+  }
+
+  ShmEventLoop *shm_event_loop_;
+
+  TimerFd timerfd_;
+  time::PhasedLoop phased_loop_;
+
+  int cycles_elapsed_ = 1;
+
+  // Function to be run
+  const ::std::function<void(int)> fn_;
+};
+}  // namespace internal
+
+::std::unique_ptr<RawFetcher> ShmEventLoop::MakeRawFetcher(
+    const Channel *channel) {
+  return ::std::unique_ptr<RawFetcher>(new ShmFetcher(channel));
+}
+
+::std::unique_ptr<RawSender> ShmEventLoop::MakeRawSender(
+    const Channel *channel) {
+  Take(channel);
+  return ::std::unique_ptr<RawSender>(new ShmSender(channel, this));
+}
+
+void ShmEventLoop::MakeRawWatcher(
+    const Channel *channel,
+    std::function<void(const Context &context, const void *message)> watcher) {
+  Take(channel);
+
+  ::std::unique_ptr<internal::WatcherState> state(
+      new internal::WatcherState(
+      channel, std::move(watcher)));
+  watchers_.push_back(::std::move(state));
+}
+
+TimerHandler *ShmEventLoop::AddTimer(::std::function<void()> callback) {
+  ::std::unique_ptr<internal::TimerHandlerState> timer(
+      new internal::TimerHandlerState(this, ::std::move(callback)));
+
+  timers_.push_back(::std::move(timer));
+
+  return timers_.back().get();
+}
+
+PhasedLoopHandler *ShmEventLoop::AddPhasedLoop(
+    ::std::function<void(int)> callback,
+    const monotonic_clock::duration interval,
+    const monotonic_clock::duration offset) {
+  ::std::unique_ptr<internal::PhasedLoopHandler> phased_loop(
+      new internal::PhasedLoopHandler(this, ::std::move(callback), interval,
+                                      offset));
+
+  phased_loops_.push_back(::std::move(phased_loop));
+
+  return phased_loops_.back().get();
+}
+
+void ShmEventLoop::OnRun(::std::function<void()> on_run) {
+  on_run_.push_back(::std::move(on_run));
+}
+
+void ShmEventLoop::Run() {
+  std::unique_ptr<ipc_lib::SignalFd> signalfd;
+
+  if (watchers_.size() > 0) {
+    signalfd.reset(new ipc_lib::SignalFd({ipc_lib::kWakeupSignal}));
+
+    epoll_.OnReadable(signalfd->fd(), [signalfd_ptr = signalfd.get(), this]() {
+      signalfd_siginfo result = signalfd_ptr->Read();
+      CHECK_EQ(result.ssi_signo, ipc_lib::kWakeupSignal);
+
+      // TODO(austin): We should really be checking *everything*, not just
+      // watchers, and calling the oldest thing first.  That will improve
+      // determinism a lot.
+
+      while (true) {
+        // Call the handlers in time order of their messages.
+        aos::monotonic_clock::time_point min_event_time =
+            aos::monotonic_clock::max_time;
+        size_t min_watcher_index = -1;
+        size_t watcher_index = 0;
+        for (::std::unique_ptr<internal::WatcherState> &watcher : watchers_) {
+          if (watcher->HasNewData()) {
+            if (watcher->event_time() < min_event_time) {
+              min_watcher_index = watcher_index;
+              min_event_time = watcher->event_time();
+            }
+          }
+          ++watcher_index;
+        }
+
+        if (min_event_time == aos::monotonic_clock::max_time) {
+          break;
+        }
+
+        watchers_[min_watcher_index]->CallCallback();
+      }
+    });
+  }
+
+  // Now, all the threads are up.  Lock everything into memory and go RT.
+  if (priority_ != 0) {
+    ::aos::InitRT();
+
+    LOG(INFO) << "Setting priority to " << priority_;
+    ::aos::SetCurrentThreadRealtimePriority(priority_);
+  }
+
+  set_is_running(true);
+
+  // Now that we are realtime (but before the OnRun handlers run), snap the
+  // queue index.
+  for (::std::unique_ptr<internal::WatcherState> &watcher : watchers_) {
+    watcher->PointAtNextQueueIndex();
+    CHECK(watcher->RegisterWakeup(priority_));
+  }
+
+  // Now that we are RT, run all the OnRun handlers.
+  for (const auto &run : on_run_) {
+    run();
+  }
+
+  // Start up all the phased loops.
+  for (::std::unique_ptr<internal::PhasedLoopHandler> &phased_loop :
+       phased_loops_) {
+    phased_loop->Startup();
+  }
+
+  // And start our main event loop which runs all the timers and handles Quit.
+  epoll_.Run();
+
+  // Once epoll exits, there is no useful nonrt work left to do.
+  set_is_running(false);
+
+  // Nothing time or synchronization critical needs to happen after this point.
+  // Drop RT priority.
+  ::aos::UnsetCurrentThreadRealtimePriority();
+
+  for (::std::unique_ptr<internal::WatcherState> &watcher : watchers_) {
+    watcher->UnregisterWakeup();
+  }
+
+  if (watchers_.size() > 0) {
+    epoll_.DeleteFd(signalfd->fd());
+    signalfd.reset();
+  }
+}
+
+void ShmEventLoop::Exit() { epoll_.Quit(); }
+
+ShmEventLoop::~ShmEventLoop() {
+  CHECK(!is_running()) << ": ShmEventLoop destroyed while running";
+}
+
+void ShmEventLoop::Take(const Channel *channel) {
+  CHECK(!is_running()) << ": Cannot add new objects while running.";
+
+  // Cheat aggresively.  Use the shared memory path as a proxy for a unique
+  // identifier for the channel.
+  const std::string path = ShmPath(channel);
+
+  const auto prior = ::std::find(taken_.begin(), taken_.end(), path);
+  CHECK(prior == taken_.end()) << ": " << path << " is already being used.";
+
+  taken_.emplace_back(path);
+}
+
+void ShmEventLoop::SetRuntimeRealtimePriority(int priority) {
+  if (is_running()) {
+    LOG(FATAL) << "Cannot set realtime priority while running.";
+  }
+  priority_ = priority;
+}
+
+}  // namespace aos
diff --git a/aos/events/shm_event_loop.h b/aos/events/shm_event_loop.h
new file mode 100644
index 0000000..e859201
--- /dev/null
+++ b/aos/events/shm_event_loop.h
@@ -0,0 +1,92 @@
+#ifndef AOS_EVENTS_SHM_EVENT_LOOP_H_
+#define AOS_EVENTS_SHM_EVENT_LOOP_H_
+
+#include <unordered_set>
+#include <vector>
+
+#include "aos/events/epoll.h"
+#include "aos/events/event_loop.h"
+#include "aos/ipc_lib/signalfd.h"
+#include "aos/mutex/mutex.h"
+
+namespace aos {
+namespace internal {
+
+class WatcherState;
+class TimerHandlerState;
+class PhasedLoopHandler;
+
+}  // namespace internal
+
+// Specialization of EventLoop that is built from queues running out of shared
+// memory. See more details at aos/queue.h
+//
+// This object must be interacted with from one thread, but the Senders and
+// Fetchers may be used from multiple threads afterwords (as long as their
+// destructors are called back in one thread again)
+class ShmEventLoop : public EventLoop {
+ public:
+  ShmEventLoop(const Configuration *configuration);
+  ~ShmEventLoop() override;
+
+  aos::monotonic_clock::time_point monotonic_now() override {
+    return aos::monotonic_clock::now();
+  }
+  aos::realtime_clock::time_point realtime_now() override {
+    return aos::realtime_clock::now();
+  }
+
+  std::unique_ptr<RawSender> MakeRawSender(const Channel *channel) override;
+  std::unique_ptr<RawFetcher> MakeRawFetcher(const Channel *channel) override;
+
+  void MakeRawWatcher(
+      const Channel *channel,
+      std::function<void(const Context &context, const void *message)> watcher)
+      override;
+
+  TimerHandler *AddTimer(std::function<void()> callback) override;
+  aos::PhasedLoopHandler *AddPhasedLoop(
+      std::function<void(int)> callback,
+      const monotonic_clock::duration interval,
+      const monotonic_clock::duration offset =
+          std::chrono::seconds(0)) override;
+
+  void OnRun(std::function<void()> on_run) override;
+  void Run();
+  void Exit();
+
+  // TODO(austin): Add a function to register control-C call.
+
+  void SetRuntimeRealtimePriority(int priority) override;
+
+  void set_name(const absl::string_view name) override {
+    name_ = std::string(name);
+  }
+  const absl::string_view name() const override { return name_; }
+
+  int priority() const { return priority_; }
+
+ private:
+  friend class internal::WatcherState;
+  friend class internal::TimerHandlerState;
+  friend class internal::PhasedLoopHandler;
+
+  // Tracks that we can't have multiple watchers or a sender and a watcher (or
+  // multiple senders) on a single queue (path).
+  void Take(const Channel *channel);
+
+  std::vector<std::function<void()>> on_run_;
+  int priority_ = 0;
+  std::string name_;
+  std::vector<std::string> taken_;
+
+  internal::EPoll epoll_;
+
+  std::vector<std::unique_ptr<internal::TimerHandlerState>> timers_;
+  std::vector<std::unique_ptr<internal::PhasedLoopHandler>> phased_loops_;
+  std::vector<std::unique_ptr<internal::WatcherState>> watchers_;
+};
+
+}  // namespace aos
+
+#endif  // AOS_EVENTS_SHM_EVENT_LOOP_H_
diff --git a/aos/events/shm-event-loop_test.cc b/aos/events/shm_event_loop_test.cc
similarity index 72%
rename from aos/events/shm-event-loop_test.cc
rename to aos/events/shm_event_loop_test.cc
index e0d0b49..4406e01 100644
--- a/aos/events/shm-event-loop_test.cc
+++ b/aos/events/shm_event_loop_test.cc
@@ -1,9 +1,13 @@
-#include "aos/events/shm-event-loop.h"
+#include "aos/events/shm_event_loop.h"
 
-#include "aos/events/event-loop_param_test.h"
-#include "aos/testing/test_shm.h"
+#include "aos/events/event_loop_param_test.h"
+#include "glog/logging.h"
 #include "gtest/gtest.h"
 
+#include "aos/events/test_message_generated.h"
+
+DECLARE_string(shm_base);
+
 namespace aos {
 namespace testing {
 namespace {
@@ -11,28 +15,40 @@
 
 class ShmEventLoopTestFactory : public EventLoopTestFactory {
  public:
+  ShmEventLoopTestFactory() {
+    // Put all the queue files in ${TEST_TMPDIR} if it is set, otherwise
+    // everything will be reusing /dev/shm when sharded.
+    char *test_tmpdir = getenv("TEST_TMPDIR");
+    if (test_tmpdir != nullptr) {
+      FLAGS_shm_base = std::string(test_tmpdir) + "/aos";
+    }
+
+    // Clean up anything left there before.
+    unlink((FLAGS_shm_base + "test/aos.TestMessage.v0").c_str());
+    unlink((FLAGS_shm_base + "test1/aos.TestMessage.v0").c_str());
+    unlink((FLAGS_shm_base + "test2/aos.TestMessage.v0").c_str());
+  }
+
   ::std::unique_ptr<EventLoop> Make() override {
-    return ::std::unique_ptr<EventLoop>(new ShmEventLoop());
+    return ::std::unique_ptr<EventLoop>(new ShmEventLoop(configuration()));
   }
 
   ::std::unique_ptr<EventLoop> MakePrimary() override {
     ::std::unique_ptr<ShmEventLoop> loop =
-        ::std::unique_ptr<ShmEventLoop>(new ShmEventLoop());
+        ::std::unique_ptr<ShmEventLoop>(new ShmEventLoop(configuration()));
     primary_event_loop_ = loop.get();
     return ::std::move(loop);
   }
 
-  void Run() override { AOS_CHECK_NOTNULL(primary_event_loop_)->Run(); }
+  void Run() override { CHECK_NOTNULL(primary_event_loop_)->Run(); }
 
-  void Exit() override { AOS_CHECK_NOTNULL(primary_event_loop_)->Exit(); }
+  void Exit() override { CHECK_NOTNULL(primary_event_loop_)->Exit(); }
 
   void SleepFor(::std::chrono::nanoseconds duration) override {
     ::std::this_thread::sleep_for(duration);
   }
 
  private:
-  ::aos::testing::TestSharedMemory my_shm_;
-
   ::aos::ShmEventLoop *primary_event_loop_;
 };
 
@@ -46,24 +62,13 @@
                           return new ShmEventLoopTestFactory();
                         }));
 
-struct TestMessage : public ::aos::Message {
-  enum { kQueueLength = 100, kHash = 0x696c0cdc };
-  int msg_value;
-
-  void Zero() { msg_value = 0; }
-  static size_t Size() { return 1 + ::aos::Message::Size(); }
-  size_t Print(char *buffer, size_t length) const;
-  TestMessage() { Zero(); }
-};
-
 }  // namespace
 
 bool IsRealtime() {
   int scheduler;
-  if ((scheduler = sched_getscheduler(0)) == -1) {
-    AOS_PLOG(FATAL, "sched_getscheduler(0) failed\n");
-  }
-  AOS_LOG(INFO, "scheduler is %d\n", scheduler);
+  PCHECK((scheduler = sched_getscheduler(0)) != -1);
+
+  LOG(INFO) << "scheduler is " << scheduler;
   return scheduler == SCHED_FIFO || scheduler == SCHED_RR;
 }
 
@@ -82,7 +87,7 @@
   bool did_timer = false;
   bool did_watcher = false;
 
-  auto timer = loop->AddTimer([&did_timer, &loop, &factory]() {
+  auto timer = loop->AddTimer([&did_timer, &factory]() {
     EXPECT_TRUE(IsRealtime());
     did_timer = true;
     factory.Exit();
@@ -97,9 +102,11 @@
     EXPECT_TRUE(IsRealtime());
     did_onrun = true;
     timer->Setup(loop->monotonic_now() + chrono::milliseconds(100));
-    auto msg = sender.MakeMessage();
-    msg->msg_value = 200;
-    msg.Send();
+
+    aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
+    TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
+    builder.add_value(200);
+    msg.Send(builder.Finish());
   });
 
   factory.Run();
diff --git a/aos/events/simulated-event-loop.cc b/aos/events/simulated-event-loop.cc
deleted file mode 100644
index 85ea21b..0000000
--- a/aos/events/simulated-event-loop.cc
+++ /dev/null
@@ -1,402 +0,0 @@
-#include "aos/events/simulated-event-loop.h"
-
-#include <algorithm>
-#include <deque>
-
-#include "aos/logging/logging.h"
-#include "aos/queue.h"
-#include "aos/testing/test_logging.h"
-#include "aos/util/phased_loop.h"
-
-namespace aos {
-namespace {
-
-class SimulatedSender : public RawSender {
- public:
-  SimulatedSender(SimulatedQueue *queue, EventLoop *event_loop)
-      : queue_(queue), event_loop_(event_loop) {
-    testing::EnableTestLogging();
-  }
-  ~SimulatedSender() {}
-
-  aos::Message *GetMessage() override {
-    return RefCountedBuffer(queue_->size()).release();
-  }
-
-  void Free(aos::Message *msg) override { RefCountedBuffer tmp(msg); }
-
-  bool Send(aos::Message *msg) override {
-    {
-      if (msg->sent_time == monotonic_clock::min_time) {
-        msg->sent_time = event_loop_->monotonic_now();
-      }
-    }
-    queue_->Send(RefCountedBuffer(msg));
-    return true;
-  }
-
-  const char *name() const override { return queue_->name(); }
-
- private:
-  SimulatedQueue *queue_;
-  EventLoop *event_loop_;
-};
-}  // namespace
-
-class SimulatedFetcher : public RawFetcher {
- public:
-  explicit SimulatedFetcher(SimulatedQueue *queue) : queue_(queue) {}
-  ~SimulatedFetcher() { queue_->UnregisterFetcher(this); }
-
-  bool FetchNext() override {
-    if (msgs_.size() == 0) return false;
-
-    msg_ = msgs_.front();
-    msgs_.pop_front();
-    set_most_recent(msg_.get());
-    return true;
-  }
-
-  bool Fetch() override {
-    if (msgs_.size() == 0) {
-      if (!msg_ && queue_->latest_message()) {
-        msg_ = queue_->latest_message();
-        set_most_recent(msg_.get());
-        return true;
-      } else {
-        return false;
-      }
-    }
-
-    // We've had a message enqueued, so we don't need to go looking for the
-    // latest message from before we started.
-    msg_ = msgs_.back();
-    msgs_.clear();
-    set_most_recent(msg_.get());
-    return true;
-  }
-
- private:
-  friend class SimulatedQueue;
-
-  // Internal method for Simulation to add a message to the buffer.
-  void Enqueue(RefCountedBuffer buffer) {
-    msgs_.emplace_back(buffer);
-  }
-
-  SimulatedQueue *queue_;
-  RefCountedBuffer msg_;
-
-  // Messages queued up but not in use.
-  ::std::deque<RefCountedBuffer> msgs_;
-};
-
-class SimulatedTimerHandler : public TimerHandler {
- public:
-  explicit SimulatedTimerHandler(EventScheduler *scheduler,
-                                 ::std::function<void()> fn)
-      : scheduler_(scheduler), fn_(fn) {}
-  ~SimulatedTimerHandler() {}
-
-  void Setup(monotonic_clock::time_point base,
-             monotonic_clock::duration repeat_offset) override {
-    Disable();
-    const ::aos::monotonic_clock::time_point monotonic_now =
-        scheduler_->monotonic_now();
-    base_ = base;
-    repeat_offset_ = repeat_offset;
-    if (base < monotonic_now) {
-      token_ = scheduler_->Schedule(monotonic_now, [this]() { HandleEvent(); });
-    } else {
-      token_ = scheduler_->Schedule(base, [this]() { HandleEvent(); });
-    }
-  }
-
-  void HandleEvent() {
-    const ::aos::monotonic_clock::time_point monotonic_now =
-        scheduler_->monotonic_now();
-    if (repeat_offset_ != ::aos::monotonic_clock::zero()) {
-      // Reschedule.
-      while (base_ <= monotonic_now) base_ += repeat_offset_;
-      token_ = scheduler_->Schedule(base_, [this]() { HandleEvent(); });
-    } else {
-      token_ = EventScheduler::Token();
-    }
-    fn_();
-  }
-
-  void Disable() override {
-    if (token_ != EventScheduler::Token()) {
-      scheduler_->Deschedule(token_);
-      token_ = EventScheduler::Token();
-    }
-  }
-
-  ::aos::monotonic_clock::time_point monotonic_now() const {
-    return scheduler_->monotonic_now();
-  }
-
- private:
-  EventScheduler *scheduler_;
-  EventScheduler::Token token_;
-  // Function to be run on the thread
-  ::std::function<void()> fn_;
-  monotonic_clock::time_point base_;
-  monotonic_clock::duration repeat_offset_;
-};
-
-class SimulatedPhasedLoopHandler : public PhasedLoopHandler {
- public:
-  SimulatedPhasedLoopHandler(EventScheduler *scheduler,
-                             ::std::function<void(int)> fn,
-                             const monotonic_clock::duration interval,
-                             const monotonic_clock::duration offset)
-      : simulated_timer_handler_(scheduler, [this]() { HandleTimerWakeup(); }),
-        phased_loop_(interval, simulated_timer_handler_.monotonic_now(),
-                     offset),
-        fn_(fn) {
-    // TODO(austin): This assumes time doesn't change between when the
-    // constructor is called and when we start running.  It's probably a safe
-    // assumption.
-    Reschedule();
-  }
-
-  void HandleTimerWakeup() {
-    fn_(cycles_elapsed_);
-    Reschedule();
-  }
-
-  void set_interval_and_offset(
-      const monotonic_clock::duration interval,
-      const monotonic_clock::duration offset) override {
-    phased_loop_.set_interval_and_offset(interval, offset);
-  }
-
-  void Reschedule() {
-    cycles_elapsed_ =
-        phased_loop_.Iterate(simulated_timer_handler_.monotonic_now());
-    simulated_timer_handler_.Setup(phased_loop_.sleep_time(),
-                                   ::aos::monotonic_clock::zero());
-  }
-
- private:
-  SimulatedTimerHandler simulated_timer_handler_;
-
-  time::PhasedLoop phased_loop_;
-
-  int cycles_elapsed_ = 1;
-
-  ::std::function<void(int)> fn_;
-};
-
-class SimulatedEventLoop : public EventLoop {
- public:
-  explicit SimulatedEventLoop(
-      EventScheduler *scheduler,
-      ::std::map<::std::pair<::std::string, QueueTypeInfo>, SimulatedQueue>
-          *queues)
-      : scheduler_(scheduler), queues_(queues) {
-    scheduler_->AddRawEventLoop(this);
-  }
-  ~SimulatedEventLoop() override { scheduler_->RemoveRawEventLoop(this); };
-
-  ::aos::monotonic_clock::time_point monotonic_now() override {
-    return scheduler_->monotonic_now();
-  }
-
-  ::std::unique_ptr<RawSender> MakeRawSender(
-      const ::std::string &path, const QueueTypeInfo &type) override;
-
-  ::std::unique_ptr<RawFetcher> MakeRawFetcher(
-      const ::std::string &path, const QueueTypeInfo &type) override;
-
-  void MakeRawWatcher(
-      const ::std::string &path, const QueueTypeInfo &type,
-      ::std::function<void(const ::aos::Message *message)> watcher) override;
-
-  TimerHandler *AddTimer(::std::function<void()> callback) override {
-    timers_.emplace_back(new SimulatedTimerHandler(scheduler_, callback));
-    return timers_.back().get();
-  }
-
-  PhasedLoopHandler *AddPhasedLoop(::std::function<void(int)> callback,
-                                   const monotonic_clock::duration interval,
-                                   const monotonic_clock::duration offset =
-                                       ::std::chrono::seconds(0)) override {
-    phased_loops_.emplace_back(
-        new SimulatedPhasedLoopHandler(scheduler_, callback, interval, offset));
-    return phased_loops_.back().get();
-  }
-
-  void OnRun(::std::function<void()> on_run) override {
-    scheduler_->Schedule(scheduler_->monotonic_now(), on_run);
-  }
-
-  void set_name(const char *name) override { name_ = name; }
-
-  SimulatedQueue *GetSimulatedQueue(
-      const ::std::pair<::std::string, QueueTypeInfo> &);
-
-  void Take(const ::std::string &path);
-
-  void SetRuntimeRealtimePriority(int /*priority*/) override {
-    if (is_running()) {
-      ::aos::Die("Cannot set realtime priority while running.");
-    }
-  }
-
- private:
-  EventScheduler *scheduler_;
-  ::std::map<::std::pair<::std::string, QueueTypeInfo>, SimulatedQueue>
-      *queues_;
-  ::std::vector<std::string> taken_;
-  ::std::vector<std::unique_ptr<TimerHandler>> timers_;
-  ::std::vector<std::unique_ptr<PhasedLoopHandler>> phased_loops_;
-
-  ::std::string name_;
-};
-
-EventScheduler::Token EventScheduler::Schedule(
-    ::aos::monotonic_clock::time_point time, ::std::function<void()> callback) {
-  return events_list_.emplace(time, callback);
-}
-
-void EventScheduler::Deschedule(EventScheduler::Token token) {
-  events_list_.erase(token);
-}
-
-void EventScheduler::RunFor(monotonic_clock::duration duration) {
-  const ::aos::monotonic_clock::time_point end_time =
-      monotonic_now() + duration;
-  testing::MockTime(monotonic_now());
-  for (RawEventLoop *event_loop : raw_event_loops_) {
-    event_loop->set_is_running(true);
-  }
-  is_running_ = true;
-  while (!events_list_.empty() && is_running_) {
-    auto iter = events_list_.begin();
-    ::aos::monotonic_clock::time_point next_time = iter->first;
-    if (next_time > end_time) {
-      break;
-    }
-    now_ = iter->first;
-    testing::MockTime(now_);
-    ::std::function<void()> callback = ::std::move(iter->second);
-    events_list_.erase(iter);
-    callback();
-  }
-  now_ = end_time;
-  if (!is_running_) {
-    for (RawEventLoop *event_loop : raw_event_loops_) {
-      event_loop->set_is_running(false);
-    }
-  }
-  testing::UnMockTime();
-}
-
-void EventScheduler::Run() {
-  testing::MockTime(monotonic_now());
-  for (RawEventLoop *event_loop : raw_event_loops_) {
-    event_loop->set_is_running(true);
-  }
-  is_running_ = true;
-  while (!events_list_.empty() && is_running_) {
-    auto iter = events_list_.begin();
-    now_ = iter->first;
-    testing::MockTime(now_);
-    ::std::function<void()> callback = ::std::move(iter->second);
-    events_list_.erase(iter);
-    callback();
-  }
-  if (!is_running_) {
-    for (RawEventLoop *event_loop : raw_event_loops_) {
-      event_loop->set_is_running(false);
-    }
-  }
-  testing::UnMockTime();
-}
-
-void SimulatedEventLoop::MakeRawWatcher(
-    const std::string &path, const QueueTypeInfo &type,
-    std::function<void(const aos::Message *message)> watcher) {
-  Take(path);
-  ::std::pair<::std::string, QueueTypeInfo> key(path, type);
-  GetSimulatedQueue(key)->MakeRawWatcher(watcher);
-}
-
-std::unique_ptr<RawSender> SimulatedEventLoop::MakeRawSender(
-    const std::string &path, const QueueTypeInfo &type) {
-  Take(path);
-  ::std::pair<::std::string, QueueTypeInfo> key(path, type);
-  return GetSimulatedQueue(key)->MakeRawSender(this);
-}
-
-std::unique_ptr<RawFetcher> SimulatedEventLoop::MakeRawFetcher(
-    const std::string &path, const QueueTypeInfo &type) {
-  ::std::pair<::std::string, QueueTypeInfo> key(path, type);
-  return GetSimulatedQueue(key)->MakeRawFetcher();
-}
-
-SimulatedQueue *SimulatedEventLoop::GetSimulatedQueue(
-    const ::std::pair<::std::string, QueueTypeInfo> &type) {
-  auto it = queues_->find(type);
-  if (it == queues_->end()) {
-    it =
-        queues_
-            ->emplace(type, SimulatedQueue(type.second, type.first, scheduler_))
-            .first;
-  }
-  return &it->second;
-}
-
-void SimulatedQueue::MakeRawWatcher(
-    ::std::function<void(const aos::Message *message)> watcher) {
-  watchers_.push_back(watcher);
-}
-
-::std::unique_ptr<RawSender> SimulatedQueue::MakeRawSender(
-    EventLoop *event_loop) {
-  return ::std::unique_ptr<RawSender>(new SimulatedSender(this, event_loop));
-}
-
-::std::unique_ptr<RawFetcher> SimulatedQueue::MakeRawFetcher() {
-  ::std::unique_ptr<SimulatedFetcher> fetcher(new SimulatedFetcher(this));
-  fetchers_.push_back(fetcher.get());
-  return ::std::move(fetcher);
-}
-
-void SimulatedQueue::Send(RefCountedBuffer message) {
-  latest_message_ = message;
-  if (scheduler_->is_running()) {
-    for (auto &watcher : watchers_) {
-      scheduler_->Schedule(scheduler_->monotonic_now(),
-                           [watcher, message]() { watcher(message.get()); });
-    }
-  }
-  for (auto &fetcher : fetchers_) {
-    fetcher->Enqueue(message);
-  }
-}
-
-void SimulatedQueue::UnregisterFetcher(SimulatedFetcher *fetcher) {
-  fetchers_.erase(::std::find(fetchers_.begin(), fetchers_.end(), fetcher));
-}
-
-void SimulatedEventLoop::Take(const ::std::string &path) {
-  if (is_running()) {
-    ::aos::Die("Cannot add new objects while running.\n");
-  }
-  const auto prior = ::std::find(taken_.begin(), taken_.end(), path);
-  if (prior != taken_.end()) {
-    ::aos::Die("%s is already being used.", path.c_str());
-  } else {
-    taken_.emplace_back(path);
-  }
-}
-
-::std::unique_ptr<EventLoop> SimulatedEventLoopFactory::MakeEventLoop() {
-  return ::std::unique_ptr<EventLoop>(
-      new SimulatedEventLoop(&scheduler_, &queues_));
-}
-
-}  // namespace aos
diff --git a/aos/events/simulated-event-loop.h b/aos/events/simulated-event-loop.h
deleted file mode 100644
index 2fcc9d1..0000000
--- a/aos/events/simulated-event-loop.h
+++ /dev/null
@@ -1,214 +0,0 @@
-#ifndef _AOS_EVENTS_SIMULATED_EVENT_LOOP_H_
-#define _AOS_EVENTS_SIMULATED_EVENT_LOOP_H_
-
-#include <algorithm>
-#include <map>
-#include <memory>
-#include <unordered_set>
-#include <utility>
-#include <vector>
-
-#include "aos/events/event-loop.h"
-
-namespace aos {
-
-// This class manages allocation of queue messages for simulation.
-// Unfortunately, because the current interfaces all assume that we pass around
-// raw pointers to messages we can't use a std::shared_ptr or the such, and
-// because aos::Message's themselves to not have any sort of built-in support
-// for this, we need to manage memory for the Messages in some custom fashion.
-// In this case, we do so by allocating a ref-counter in the bytes immediately
-// preceding the aos::Message. We then provide a constructor that takes just a
-// pointer to an existing message and we assume that it was allocated using this
-// class, and can decrement the counter if the RefCountedBuffer we constructed
-// goes out of scope. There are currently no checks to ensure that pointers
-// passed into this class were actually allocated using this class.
-class RefCountedBuffer {
- public:
-  RefCountedBuffer() {}
-  ~RefCountedBuffer() { clear(); }
-
-  // Create a RefCountedBuffer for some Message that was already allocated using
-  // a RefCountedBuffer class. This, or some function like it, is required to
-  // allow us to let users of the simulated event loops work with raw pointers
-  // to messages.
-  explicit RefCountedBuffer(aos::Message *data) : data_(data) {}
-
-  // Allocates memory for a new message of a given size. Does not initialize the
-  // memory or call any constructors.
-  explicit RefCountedBuffer(size_t size) {
-    data_ = reinterpret_cast<uint8_t *>(malloc(kRefCountSize + size)) +
-            kRefCountSize;
-    // Initialize the allocated memory with an integer
-    *GetRefCount() = 1;
-  }
-
-  RefCountedBuffer(const RefCountedBuffer &other) {
-    data_ = other.data_;
-    if (data_ != nullptr) {
-      ++*GetRefCount();
-    }
-  }
-
-  RefCountedBuffer(RefCountedBuffer &&other) { std::swap(data_, other.data_); }
-
-  RefCountedBuffer &operator=(const RefCountedBuffer &other) {
-    if (this == &other) return *this;
-    clear();
-    data_ = other.data_;
-    ++*GetRefCount();
-    return *this;
-  }
-
-  RefCountedBuffer &operator=(RefCountedBuffer &&other) {
-    if (this == &other) return *this;
-    std::swap(data_, other.data_);
-    return *this;
-  }
-
-  operator bool() const { return data_ != nullptr; }
-
-  aos::Message *get() const { return static_cast<aos::Message *>(data_); }
-
-  aos::Message *release() {
-    auto tmp = get();
-    data_ = nullptr;
-    return tmp;
-  }
-
-  void clear() {
-    if (data_ != nullptr) {
-      if (--*GetRefCount() == 0) {
-        // Free memory block from the start of the allocated block
-        free(GetRefCount());
-      }
-      data_ = nullptr;
-    }
-  }
-
- private:
-  void *data_ = nullptr;
-  // Qty. memory to be allocated to the ref counter
-  static constexpr size_t kRefCountSize = sizeof(int64_t);
-
-  int64_t *GetRefCount() {
-    // Need to cast the void* to an 8 bit long object (size of void* is
-    // technically 0)
-    return reinterpret_cast<int64_t *>(static_cast<void *>(
-        reinterpret_cast<uint8_t *>(data_) - kRefCountSize));
-  }
-};
-
-class EventScheduler {
- public:
-  using QueueType = ::std::multimap<::aos::monotonic_clock::time_point,
-                                    ::std::function<void()>>;
-  using Token = QueueType::iterator;
-
-  // Schedule an event with a callback function
-  // Returns an iterator to the event
-  Token Schedule(::aos::monotonic_clock::time_point time,
-                 ::std::function<void()> callback);
-
-  // Deschedule an event by its iterator
-  void Deschedule(Token token);
-
-  void Run();
-  void RunFor(::aos::monotonic_clock::duration duration);
-
-  void Exit() {
-    is_running_ = false;
-  }
-
-  bool is_running() const { return is_running_; }
-
-  void AddRawEventLoop(RawEventLoop *event_loop) {
-    raw_event_loops_.push_back(event_loop);
-  }
-  void RemoveRawEventLoop(RawEventLoop *event_loop) {
-    raw_event_loops_.erase(::std::find(raw_event_loops_.begin(),
-                                       raw_event_loops_.end(), event_loop));
-  }
-
-  ::aos::monotonic_clock::time_point monotonic_now() const { return now_; }
-
- private:
-  ::aos::monotonic_clock::time_point now_ = ::aos::monotonic_clock::epoch();
-  QueueType events_list_;
-  bool is_running_ = false;
-  ::std::vector<RawEventLoop *> raw_event_loops_;
-};
-
-// Class for simulated fetchers.
-class SimulatedFetcher;
-
-class SimulatedQueue {
- public:
-  explicit SimulatedQueue(const QueueTypeInfo &type, const ::std::string &name,
-                          EventScheduler *scheduler)
-      : type_(type), name_(name), scheduler_(scheduler){};
-
-  ~SimulatedQueue() { AOS_CHECK_EQ(0u, fetchers_.size()); }
-
-  // Makes a connected raw sender which calls Send below.
-  ::std::unique_ptr<RawSender> MakeRawSender(EventLoop *event_loop);
-
-  // Makes a connected raw fetcher.
-  ::std::unique_ptr<RawFetcher> MakeRawFetcher();
-
-  // Registers a watcher for the queue.
-  void MakeRawWatcher(
-      ::std::function<void(const ::aos::Message *message)> watcher);
-
-  // Sends the message to all the connected receivers and fetchers.
-  void Send(RefCountedBuffer message);
-
-  // Unregisters a fetcher.
-  void UnregisterFetcher(SimulatedFetcher *fetcher);
-
-  const RefCountedBuffer &latest_message() { return latest_message_; }
-
-  size_t size() const { return type_.size; }
-
-  const char *name() const { return name_.c_str(); }
-
- private:
-  const QueueTypeInfo type_;
-  const ::std::string name_;
-
-  // List of all watchers.
-  ::std::vector<std::function<void(const aos::Message *message)>> watchers_;
-
-  // List of all fetchers.
-  ::std::vector<SimulatedFetcher *> fetchers_;
-  RefCountedBuffer latest_message_;
-  EventScheduler *scheduler_;
-};
-
-class SimulatedEventLoopFactory {
- public:
-  ::std::unique_ptr<EventLoop> MakeEventLoop();
-
-  // Starts executing the event loops unconditionally.
-  void Run() { scheduler_.Run(); }
-  // Executes the event loops for a duration.
-  void RunFor(monotonic_clock::duration duration) {
-    scheduler_.RunFor(duration);
-  }
-
-  // Stops executing all event loops.  Meant to be called from within an event
-  // loop handler.
-  void Exit() { scheduler_.Exit(); }
-
-  monotonic_clock::time_point monotonic_now() const {
-    return scheduler_.monotonic_now();
-  }
-
- private:
-  EventScheduler scheduler_;
-  ::std::map<::std::pair<::std::string, QueueTypeInfo>, SimulatedQueue> queues_;
-};
-
-}  // namespace aos
-
-#endif  //_AOS_EVENTS_TEST_EVENT_LOOP_H_
diff --git a/aos/events/simulated_event_loop.cc b/aos/events/simulated_event_loop.cc
new file mode 100644
index 0000000..9bc74d5
--- /dev/null
+++ b/aos/events/simulated_event_loop.cc
@@ -0,0 +1,514 @@
+#include "aos/events/simulated_event_loop.h"
+
+#include <algorithm>
+#include <deque>
+
+#include "absl/container/btree_map.h"
+#include "absl/container/btree_set.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/util/phased_loop.h"
+
+namespace aos {
+
+// Container for both a message, and the context for it for simulation.  This
+// makes tracking the timestamps associated with the data easy.
+struct SimulatedMessage {
+  // Struct to let us force data to be well aligned.
+  struct OveralignedChar {
+    char data alignas(32);
+  };
+
+  // Context for the data.
+  Context context;
+
+  // The data.
+  char *data() { return reinterpret_cast<char *>(&actual_data[0]); }
+
+  // Then the data.
+  OveralignedChar actual_data[];
+};
+
+class SimulatedFetcher;
+
+class SimulatedChannel {
+ public:
+  explicit SimulatedChannel(const Channel *channel, EventScheduler *scheduler)
+      : channel_(CopyFlatBuffer(channel)),
+        scheduler_(scheduler),
+        next_queue_index_(ipc_lib::QueueIndex::Zero(channel->max_size())) {}
+
+  ~SimulatedChannel() { CHECK_EQ(0u, fetchers_.size()); }
+
+  // Makes a connected raw sender which calls Send below.
+  ::std::unique_ptr<RawSender> MakeRawSender(EventLoop *event_loop);
+
+  // Makes a connected raw fetcher.
+  ::std::unique_ptr<RawFetcher> MakeRawFetcher();
+
+  // Registers a watcher for the queue.
+  void MakeRawWatcher(
+      ::std::function<void(const Context &context, const void *message)>
+          watcher);
+
+  // Sends the message to all the connected receivers and fetchers.
+  void Send(std::shared_ptr<SimulatedMessage> message);
+
+  // Unregisters a fetcher.
+  void UnregisterFetcher(SimulatedFetcher *fetcher);
+
+  std::shared_ptr<SimulatedMessage> latest_message() { return latest_message_; }
+
+  size_t max_size() const { return channel_.message().max_size(); }
+
+  const absl::string_view name() const {
+    return channel_.message().name()->string_view();
+  }
+
+  const Channel *channel() const { return &channel_.message(); }
+
+ private:
+  const FlatbufferDetachedBuffer<Channel> channel_;
+
+  // List of all watchers.
+  ::std::vector<
+      std::function<void(const Context &context, const void *message)>>
+      watchers_;
+
+  // List of all fetchers.
+  ::std::vector<SimulatedFetcher *> fetchers_;
+  std::shared_ptr<SimulatedMessage> latest_message_;
+  EventScheduler *scheduler_;
+
+  ipc_lib::QueueIndex next_queue_index_;
+};
+
+namespace {
+
+// Creates a SimulatedMessage with size bytes of storage.
+// This is a shared_ptr so we don't have to implement refcounting or copying.
+std::shared_ptr<SimulatedMessage> MakeSimulatedMessage(size_t size) {
+  SimulatedMessage *message = reinterpret_cast<SimulatedMessage *>(
+      malloc(sizeof(SimulatedMessage) + size));
+  message->context.size = size;
+  message->context.data = message->data();
+
+  return std::shared_ptr<SimulatedMessage>(message, free);
+}
+
+class SimulatedSender : public RawSender {
+ public:
+  SimulatedSender(SimulatedChannel *simulated_channel, EventLoop *event_loop)
+      : simulated_channel_(simulated_channel), event_loop_(event_loop) {}
+  ~SimulatedSender() {}
+
+  void *data() override {
+    if (!message_) {
+      message_ = MakeSimulatedMessage(simulated_channel_->max_size());
+    }
+    return message_->data();
+  }
+
+  size_t size() override { return simulated_channel_->max_size(); }
+
+  bool Send(size_t length) override {
+    CHECK_LE(length, size()) << ": Attempting to send too big a message.";
+    message_->context.monotonic_sent_time = event_loop_->monotonic_now();
+    message_->context.realtime_sent_time = event_loop_->realtime_now();
+    CHECK_LE(length, message_->context.size);
+    message_->context.size = length;
+
+    // TODO(austin): Track sending too fast.
+    simulated_channel_->Send(message_);
+
+    // Drop the reference to the message so that we allocate a new message for
+    // next time.  Otherwise we will continue to reuse the same memory for all
+    // messages and corrupt it.
+    message_.reset();
+    return true;
+  }
+
+  bool Send(void *msg, size_t size) override {
+    CHECK_LE(size, this->size()) << ": Attempting to send too big a message.";
+
+    // This is wasteful, but since flatbuffers fill from the back end of the
+    // queue, we need it to be full sized.
+    message_ = MakeSimulatedMessage(simulated_channel_->max_size());
+
+    // Now fill in the message.  size is already populated above, and
+    // queue_index will be populated in queue_.  Put this at the back of the
+    // data segment.
+    memcpy(message_->data() + simulated_channel_->max_size() - size, msg, size);
+
+    return Send(size);
+  }
+
+  const absl::string_view name() const override {
+    return simulated_channel_->name();
+  }
+
+ private:
+  SimulatedChannel *simulated_channel_;
+  EventLoop *event_loop_;
+
+  std::shared_ptr<SimulatedMessage> message_;
+};
+}  // namespace
+
+class SimulatedFetcher : public RawFetcher {
+ public:
+  explicit SimulatedFetcher(SimulatedChannel *queue) : queue_(queue) {}
+  ~SimulatedFetcher() { queue_->UnregisterFetcher(this); }
+
+  bool FetchNext() override {
+    if (msgs_.size() == 0) return false;
+
+    SetMsg(msgs_.front());
+    msgs_.pop_front();
+    return true;
+  }
+
+  bool Fetch() override {
+    if (msgs_.size() == 0) {
+      if (!msg_ && queue_->latest_message()) {
+        SetMsg(queue_->latest_message());
+        return true;
+      } else {
+        return false;
+      }
+    }
+
+    // We've had a message enqueued, so we don't need to go looking for the
+    // latest message from before we started.
+    SetMsg(msgs_.back());
+    msgs_.clear();
+    return true;
+  }
+
+ private:
+  friend class SimulatedChannel;
+
+  // Updates the state inside RawFetcher to point to the data in msg_.
+  void SetMsg(std::shared_ptr<SimulatedMessage> msg) {
+    msg_ = msg;
+    data_ = msg_->context.data;
+    context_ = msg_->context;
+  }
+
+  // Internal method for Simulation to add a message to the buffer.
+  void Enqueue(std::shared_ptr<SimulatedMessage> buffer) {
+    msgs_.emplace_back(buffer);
+  }
+
+  SimulatedChannel *queue_;
+  std::shared_ptr<SimulatedMessage> msg_;
+
+  // Messages queued up but not in use.
+  ::std::deque<std::shared_ptr<SimulatedMessage>> msgs_;
+};
+
+class SimulatedTimerHandler : public TimerHandler {
+ public:
+  explicit SimulatedTimerHandler(EventScheduler *scheduler,
+                                 ::std::function<void()> fn)
+      : scheduler_(scheduler), token_(scheduler_->InvalidToken()), fn_(fn) {}
+  ~SimulatedTimerHandler() {}
+
+  void Setup(monotonic_clock::time_point base,
+             monotonic_clock::duration repeat_offset) override {
+    Disable();
+    const ::aos::monotonic_clock::time_point monotonic_now =
+        scheduler_->monotonic_now();
+    base_ = base;
+    repeat_offset_ = repeat_offset;
+    if (base < monotonic_now) {
+      token_ = scheduler_->Schedule(monotonic_now, [this]() { HandleEvent(); });
+    } else {
+      token_ = scheduler_->Schedule(base, [this]() { HandleEvent(); });
+    }
+  }
+
+  void HandleEvent() {
+    const ::aos::monotonic_clock::time_point monotonic_now =
+        scheduler_->monotonic_now();
+    if (repeat_offset_ != ::aos::monotonic_clock::zero()) {
+      // Reschedule.
+      while (base_ <= monotonic_now) base_ += repeat_offset_;
+      token_ = scheduler_->Schedule(base_, [this]() { HandleEvent(); });
+    } else {
+      token_ = scheduler_->InvalidToken();
+    }
+    fn_();
+  }
+
+  void Disable() override {
+    if (token_ != scheduler_->InvalidToken()) {
+      scheduler_->Deschedule(token_);
+      token_ = scheduler_->InvalidToken();
+    }
+  }
+
+  ::aos::monotonic_clock::time_point monotonic_now() const {
+    return scheduler_->monotonic_now();
+  }
+
+ private:
+  EventScheduler *scheduler_;
+  EventScheduler::Token token_;
+  // Function to be run on the thread
+  ::std::function<void()> fn_;
+  monotonic_clock::time_point base_;
+  monotonic_clock::duration repeat_offset_;
+};
+
+class SimulatedPhasedLoopHandler : public PhasedLoopHandler {
+ public:
+  SimulatedPhasedLoopHandler(EventScheduler *scheduler,
+                             ::std::function<void(int)> fn,
+                             const monotonic_clock::duration interval,
+                             const monotonic_clock::duration offset)
+      : simulated_timer_handler_(scheduler, [this]() { HandleTimerWakeup(); }),
+        phased_loop_(interval, simulated_timer_handler_.monotonic_now(),
+                     offset),
+        fn_(fn) {
+    // TODO(austin): This assumes time doesn't change between when the
+    // constructor is called and when we start running.  It's probably a safe
+    // assumption.
+    Reschedule();
+  }
+
+  void HandleTimerWakeup() {
+    fn_(cycles_elapsed_);
+    Reschedule();
+  }
+
+  void set_interval_and_offset(
+      const monotonic_clock::duration interval,
+      const monotonic_clock::duration offset) override {
+    phased_loop_.set_interval_and_offset(interval, offset);
+  }
+
+  void Reschedule() {
+    cycles_elapsed_ =
+        phased_loop_.Iterate(simulated_timer_handler_.monotonic_now());
+    simulated_timer_handler_.Setup(phased_loop_.sleep_time(),
+                                   ::aos::monotonic_clock::zero());
+  }
+
+ private:
+  SimulatedTimerHandler simulated_timer_handler_;
+
+  time::PhasedLoop phased_loop_;
+
+  int cycles_elapsed_ = 1;
+
+  ::std::function<void(int)> fn_;
+};
+
+class SimulatedEventLoop : public EventLoop {
+ public:
+  explicit SimulatedEventLoop(
+      EventScheduler *scheduler,
+      absl::btree_map<SimpleChannel, std::unique_ptr<SimulatedChannel>>
+          *channels,
+      const Configuration *configuration,
+      std::vector<std::pair<EventLoop *, std::function<void(bool)>>>
+          *raw_event_loops)
+      : EventLoop(configuration),
+        scheduler_(scheduler),
+        channels_(channels),
+        raw_event_loops_(raw_event_loops) {
+    raw_event_loops_->push_back(
+        std::make_pair(this, [this](bool value) { set_is_running(value); }));
+  }
+  ~SimulatedEventLoop() override {
+    for (auto it = raw_event_loops_->begin(); it != raw_event_loops_->end();
+         ++it) {
+      if (it->first == this) {
+        raw_event_loops_->erase(it);
+        break;
+      }
+    }
+  }
+
+  ::aos::monotonic_clock::time_point monotonic_now() override {
+    return scheduler_->monotonic_now();
+  }
+
+  ::aos::realtime_clock::time_point realtime_now() override {
+    return scheduler_->realtime_now();
+  }
+
+  ::std::unique_ptr<RawSender> MakeRawSender(const Channel *channel) override;
+
+  ::std::unique_ptr<RawFetcher> MakeRawFetcher(const Channel *channel) override;
+
+  void MakeRawWatcher(
+      const Channel *channel,
+      ::std::function<void(const Context &context, const void *message)>
+          watcher) override;
+
+  TimerHandler *AddTimer(::std::function<void()> callback) override {
+    timers_.emplace_back(new SimulatedTimerHandler(scheduler_, callback));
+    return timers_.back().get();
+  }
+
+  PhasedLoopHandler *AddPhasedLoop(::std::function<void(int)> callback,
+                                   const monotonic_clock::duration interval,
+                                   const monotonic_clock::duration offset =
+                                       ::std::chrono::seconds(0)) override {
+    phased_loops_.emplace_back(
+        new SimulatedPhasedLoopHandler(scheduler_, callback, interval, offset));
+    return phased_loops_.back().get();
+  }
+
+  void OnRun(::std::function<void()> on_run) override {
+    scheduler_->Schedule(scheduler_->monotonic_now(), on_run);
+  }
+
+  void set_name(const absl::string_view name) override {
+    name_ = std::string(name);
+  }
+  const absl::string_view name() const override { return name_; }
+
+  SimulatedChannel *GetSimulatedChannel(const Channel *channel);
+
+  void Take(const Channel *channel);
+
+  void SetRuntimeRealtimePriority(int /*priority*/) override {
+    CHECK(!is_running()) << ": Cannot set realtime priority while running.";
+  }
+
+ private:
+  EventScheduler *scheduler_;
+  absl::btree_map<SimpleChannel, std::unique_ptr<SimulatedChannel>> *channels_;
+  std::vector<std::pair<EventLoop *, std::function<void(bool)>>>
+      *raw_event_loops_;
+  absl::btree_set<SimpleChannel> taken_;
+  ::std::vector<std::unique_ptr<TimerHandler>> timers_;
+  ::std::vector<std::unique_ptr<PhasedLoopHandler>> phased_loops_;
+
+  ::std::string name_;
+};
+
+void SimulatedEventLoop::MakeRawWatcher(
+    const Channel *channel,
+    std::function<void(const Context &channel, const void *message)> watcher) {
+  Take(channel);
+  GetSimulatedChannel(channel)->MakeRawWatcher(watcher);
+}
+
+std::unique_ptr<RawSender> SimulatedEventLoop::MakeRawSender(
+    const Channel *channel) {
+  Take(channel);
+  return GetSimulatedChannel(channel)->MakeRawSender(this);
+}
+
+std::unique_ptr<RawFetcher> SimulatedEventLoop::MakeRawFetcher(
+    const Channel *channel) {
+  return GetSimulatedChannel(channel)->MakeRawFetcher();
+}
+
+SimulatedChannel *SimulatedEventLoop::GetSimulatedChannel(
+    const Channel *channel) {
+  auto it = channels_->find(SimpleChannel(channel));
+  if (it == channels_->end()) {
+    it = channels_
+             ->emplace(SimpleChannel(channel),
+                       std::unique_ptr<SimulatedChannel>(
+                           new SimulatedChannel(channel, scheduler_)))
+             .first;
+  }
+  return it->second.get();
+}
+
+void SimulatedChannel::MakeRawWatcher(
+    ::std::function<void(const Context &context, const void *message)>
+        watcher) {
+  watchers_.push_back(watcher);
+}
+
+::std::unique_ptr<RawSender> SimulatedChannel::MakeRawSender(
+    EventLoop *event_loop) {
+  return ::std::unique_ptr<RawSender>(new SimulatedSender(this, event_loop));
+}
+
+::std::unique_ptr<RawFetcher> SimulatedChannel::MakeRawFetcher() {
+  ::std::unique_ptr<SimulatedFetcher> fetcher(new SimulatedFetcher(this));
+  fetchers_.push_back(fetcher.get());
+  return ::std::move(fetcher);
+}
+
+void SimulatedChannel::Send(std::shared_ptr<SimulatedMessage> message) {
+  message->context.queue_index = next_queue_index_.index();
+  message->context.data =
+      message->data() + channel()->max_size() - message->context.size;
+  next_queue_index_ = next_queue_index_.Increment();
+
+  latest_message_ = message;
+  if (scheduler_->is_running()) {
+    for (auto &watcher : watchers_) {
+      scheduler_->Schedule(scheduler_->monotonic_now(), [watcher, message]() {
+        watcher(message->context, message->context.data);
+      });
+    }
+  }
+  for (auto &fetcher : fetchers_) {
+    fetcher->Enqueue(message);
+  }
+}
+
+void SimulatedChannel::UnregisterFetcher(SimulatedFetcher *fetcher) {
+  fetchers_.erase(::std::find(fetchers_.begin(), fetchers_.end(), fetcher));
+}
+
+SimpleChannel::SimpleChannel(const Channel *channel)
+    : name(CHECK_NOTNULL(CHECK_NOTNULL(channel)->name())->str()),
+      type(CHECK_NOTNULL(CHECK_NOTNULL(channel)->type())->str()) {}
+
+void SimulatedEventLoop::Take(const Channel *channel) {
+  CHECK(!is_running()) << ": Cannot add new objects while running.";
+
+  auto result = taken_.insert(SimpleChannel(channel));
+  CHECK(result.second) << ": " << FlatbufferToJson(channel)
+                       << " is already being used.";
+}
+
+SimulatedEventLoopFactory::SimulatedEventLoopFactory(
+    const Configuration *configuration)
+    : configuration_(configuration) {}
+SimulatedEventLoopFactory::~SimulatedEventLoopFactory() {}
+
+::std::unique_ptr<EventLoop> SimulatedEventLoopFactory::MakeEventLoop() {
+  return ::std::unique_ptr<EventLoop>(new SimulatedEventLoop(
+      &scheduler_, &channels_, configuration_, &raw_event_loops_));
+}
+
+void SimulatedEventLoopFactory::RunFor(monotonic_clock::duration duration) {
+  for (const std::pair<EventLoop *, std::function<void(bool)>> &event_loop :
+       raw_event_loops_) {
+    event_loop.second(true);
+  }
+  scheduler_.RunFor(duration);
+  if (!scheduler_.is_running()) {
+    for (const std::pair<EventLoop *, std::function<void(bool)>> &event_loop :
+         raw_event_loops_) {
+      event_loop.second(false);
+    }
+  }
+}
+
+void SimulatedEventLoopFactory::Run() {
+  for (const std::pair<EventLoop *, std::function<void(bool)>> &event_loop :
+       raw_event_loops_) {
+    event_loop.second(true);
+  }
+  scheduler_.Run();
+  if (!scheduler_.is_running()) {
+    for (const std::pair<EventLoop *, std::function<void(bool)>> &event_loop :
+         raw_event_loops_) {
+      event_loop.second(false);
+    }
+  }
+}
+
+}  // namespace aos
diff --git a/aos/events/simulated_event_loop.h b/aos/events/simulated_event_loop.h
new file mode 100644
index 0000000..485ab68
--- /dev/null
+++ b/aos/events/simulated_event_loop.h
@@ -0,0 +1,86 @@
+#ifndef AOS_EVENTS_SIMULATED_EVENT_LOOP_H_
+#define AOS_EVENTS_SIMULATED_EVENT_LOOP_H_
+
+#include <algorithm>
+#include <map>
+#include <memory>
+#include <unordered_set>
+#include <utility>
+#include <vector>
+
+#include "absl/container/btree_map.h"
+#include "aos/events/event_loop.h"
+#include "aos/events/event_scheduler.h"
+#include "aos/flatbuffer_merge.h"
+#include "aos/flatbuffers.h"
+#include "aos/ipc_lib/index.h"
+#include "glog/logging.h"
+
+namespace aos {
+
+// Class for simulated fetchers.
+class SimulatedChannel;
+
+struct SimpleChannel {
+  SimpleChannel(const Channel *channel);
+  std::string name;
+  std::string type;
+
+  std::string DebugString() const {
+    return std::string("{ ") + name + ", " + type + "}";
+  }
+
+  bool operator==(const SimpleChannel &other) const {
+    return name == other.name && type == other.type;
+  }
+  bool operator<(const SimpleChannel &other) const {
+    int name_compare = other.name.compare(name);
+    if (name_compare == 0) {
+      return other.type < type;
+    } else if (name_compare < 0) {
+      return true;
+    } else {
+      return false;
+    }
+  }
+};
+
+class SimulatedEventLoopFactory {
+ public:
+  // Constructs a SimulatedEventLoopFactory with the provided configuration.
+  // This configuration must remain in scope for the lifetime of the factory and
+  // all sub-objects.
+  SimulatedEventLoopFactory(const Configuration *configuration);
+  ~SimulatedEventLoopFactory();
+
+  ::std::unique_ptr<EventLoop> MakeEventLoop();
+
+  // Starts executing the event loops unconditionally.
+  void Run();
+  // Executes the event loops for a duration.
+  void RunFor(monotonic_clock::duration duration);
+
+  // Stops executing all event loops.  Meant to be called from within an event
+  // loop handler.
+  void Exit() { scheduler_.Exit(); }
+
+  monotonic_clock::time_point monotonic_now() const {
+    return scheduler_.monotonic_now();
+  }
+  realtime_clock::time_point realtime_now() const {
+    return scheduler_.realtime_now();
+  }
+
+ private:
+  const Configuration *configuration_;
+  EventScheduler scheduler_;
+  // Map from name, type to queue.
+  absl::btree_map<SimpleChannel, std::unique_ptr<SimulatedChannel>> channels_;
+  // List of event loops to manage running and not running for.
+  std::vector<std::pair<EventLoop *, std::function<void(bool)>>>
+      raw_event_loops_;
+};
+
+}  // namespace aos
+
+#endif  // AOS_EVENTS_SIMULATED_EVENT_LOOP_H_
diff --git a/aos/events/simulated-event-loop_test.cc b/aos/events/simulated_event_loop_test.cc
similarity index 90%
rename from aos/events/simulated-event-loop_test.cc
rename to aos/events/simulated_event_loop_test.cc
index e987a11..356c25b 100644
--- a/aos/events/simulated-event-loop_test.cc
+++ b/aos/events/simulated_event_loop_test.cc
@@ -1,5 +1,6 @@
-#include "aos/events/simulated-event-loop.h"
-#include "aos/events/event-loop_param_test.h"
+#include "aos/events/simulated_event_loop.h"
+
+#include "aos/events/event_loop_param_test.h"
 #include "gtest/gtest.h"
 
 namespace aos {
@@ -9,6 +10,8 @@
 
 class SimulatedEventLoopTestFactory : public EventLoopTestFactory {
  public:
+  SimulatedEventLoopTestFactory() : event_loop_factory_(configuration()) {}
+
   ::std::unique_ptr<EventLoop> Make() override {
     return event_loop_factory_.MakeEventLoop();
   }
@@ -68,7 +71,7 @@
 // Test that running for a time period with no handlers causes time to progress
 // correctly.
 TEST(SimulatedEventLoopTest, RunForNoHandlers) {
-  SimulatedEventLoopFactory simulated_event_loop_factory;
+  SimulatedEventLoopFactory simulated_event_loop_factory(nullptr);
   ::std::unique_ptr<EventLoop> event_loop =
       simulated_event_loop_factory.MakeEventLoop();
 
@@ -83,12 +86,12 @@
 // Test that running for a time with a periodic handler causes time to end
 // correctly.
 TEST(SimulatedEventLoopTest, RunForTimerHandler) {
-  SimulatedEventLoopFactory simulated_event_loop_factory;
+  SimulatedEventLoopFactory simulated_event_loop_factory(nullptr);
   ::std::unique_ptr<EventLoop> event_loop =
       simulated_event_loop_factory.MakeEventLoop();
 
   int counter = 0;
-  auto timer = event_loop->AddTimer([&counter, &event_loop]() { ++counter; });
+  auto timer = event_loop->AddTimer([&counter]() { ++counter; });
   event_loop->OnRun([&event_loop, &timer] {
     timer->Setup(event_loop->monotonic_now() + chrono::milliseconds(50),
                  chrono::milliseconds(100));
diff --git a/aos/events/test_message.fbs b/aos/events/test_message.fbs
new file mode 100644
index 0000000..1d26c2e
--- /dev/null
+++ b/aos/events/test_message.fbs
@@ -0,0 +1,7 @@
+namespace aos;
+
+table TestMessage {
+  value:int;
+}
+
+root_type TestMessage;
diff --git a/aos/flatbuffers.h b/aos/flatbuffers.h
index 448f34b..fc91cf9 100644
--- a/aos/flatbuffers.h
+++ b/aos/flatbuffers.h
@@ -1,6 +1,9 @@
 #ifndef AOS_FLATBUFFERS_H_
 #define AOS_FLATBUFFERS_H_
 
+#include <array>
+
+#include "absl/strings/string_view.h"
 #include "flatbuffers/flatbuffers.h"
 
 namespace aos {
@@ -20,6 +23,8 @@
   virtual uint8_t *data() = 0;
   virtual size_t size() const = 0;
 
+  void Reset() { is_allocated_ = false; }
+
  private:
   bool is_allocated_ = false;
 };
@@ -37,11 +42,27 @@
   std::array<uint8_t, S> buffer_;
 };
 
+// This class adapts a preallocated memory region to an Allocator.
+class PreallocatedAllocator : public FixedAllocatorBase {
+ public:
+  PreallocatedAllocator(void *data, size_t size) : data_(data), size_(size) {}
+  uint8_t *data() override { return reinterpret_cast<uint8_t *>(data_); }
+  const uint8_t *data() const override {
+    return reinterpret_cast<const uint8_t *>(data_);
+  }
+  size_t size() const override { return size_; }
+
+ private:
+  void* data_;
+  size_t size_;
+};
+
 // Base class representing an object which holds the memory representing a root
 // flatbuffer.
 template <typename T>
 class Flatbuffer {
  public:
+  virtual ~Flatbuffer() {}
   // Returns the MiniReflectTypeTable for T.
   static const flatbuffers::TypeTable *MiniReflectTypeTable() {
     return T::MiniReflectTypeTable();
@@ -82,6 +103,8 @@
     return *this;
   }
 
+  virtual ~FlatbufferArray() override {}
+
   // Creates a builder wrapping the underlying data.
   flatbuffers::FlatBufferBuilder FlatBufferBuilder() {
     data_.deallocate(data_.data(), data_.size());
@@ -99,6 +122,39 @@
   size_t size_ = data_.size();
 };
 
+// String backed flatbuffer.
+template <typename T>
+class FlatbufferString : public Flatbuffer<T> {
+ public:
+  // Builds a flatbuffer using the contents of the string.
+  FlatbufferString(const absl::string_view data) : data_(data) {}
+  // Builds a Flatbuffer by copying the data from the other flatbuffer.
+  FlatbufferString(const Flatbuffer<T> &other) {
+    data_ = std::string(other.data(), other.size());
+  }
+
+  // Coppies the data from the other flatbuffer.
+  FlatbufferString &operator=(const Flatbuffer<T> &other) {
+    data_ = std::string(other.data(), other.size());
+    return *this;
+  }
+
+  virtual ~FlatbufferString() override {}
+
+  const uint8_t *data() const override {
+    return reinterpret_cast<const uint8_t *>(data_.data());
+  }
+  uint8_t *data() override {
+    // TODO(james): when we get c++17, can we drop the second cast?
+    return const_cast<uint8_t *>(
+        reinterpret_cast<const uint8_t *>(data_.data()));
+  }
+  size_t size() const override { return data_.size(); }
+
+ private:
+  std::string data_;
+};
+
 // This object associates the message type with the memory storing the
 // flatbuffer.  This only stores root tables.
 //
@@ -120,6 +176,8 @@
     return *this;
   }
 
+  virtual ~FlatbufferDetachedBuffer() override {}
+
   // Constructs an empty flatbuffer of type T.
   static FlatbufferDetachedBuffer<T> Empty() {
     flatbuffers::FlatBufferBuilder fbb;
diff --git a/aos/init.cc b/aos/init.cc
index fdb1800..ac18413 100644
--- a/aos/init.cc
+++ b/aos/init.cc
@@ -14,8 +14,9 @@
 #include <malloc.h>
 
 #include "aos/die.h"
-#include "aos/logging/implementations.h"
 #include "aos/ipc_lib/shared_mem.h"
+#include "aos/logging/implementations.h"
+#include "aos/realtime.h"
 
 namespace FLAG__namespace_do_not_use_directly_use_DECLARE_double_instead {
 extern double FLAGS_tcmalloc_release_rate __attribute__((weak));
@@ -34,25 +35,6 @@
 }  // namespace logging
 namespace {
 
-void SetSoftRLimit(int resource, rlim64_t soft, bool set_for_root) {
-  bool am_root = getuid() == 0;
-  if (set_for_root || !am_root) {
-    struct rlimit64 rlim;
-    if (getrlimit64(resource, &rlim) == -1) {
-      PDie("%s-init: getrlimit64(%d) failed",
-           program_invocation_short_name, resource);
-    }
-    rlim.rlim_cur = soft;
-    rlim.rlim_max = ::std::max(rlim.rlim_max, soft);
-
-    if (setrlimit64(resource, &rlim) == -1) {
-      PDie("%s-init: setrlimit64(%d, {cur=%ju,max=%ju}) failed",
-           program_invocation_short_name, resource, (uintmax_t)rlim.rlim_cur,
-           (uintmax_t)rlim.rlim_max);
-    }
-  }
-}
-
 // Common stuff that needs to happen at the beginning of both the realtime and
 // non-realtime initialization sequences. May be called twice.
 void InitStart() {
@@ -68,35 +50,11 @@
 
 }  // namespace
 
-void LockAllMemory() {
-  // Allow locking as much as we want into RAM.
-  SetSoftRLimit(RLIMIT_MEMLOCK, RLIM_INFINITY, false);
-
-  InitStart();
-  if (mlockall(MCL_CURRENT | MCL_FUTURE) == -1) {
-    PDie("%s-init: mlockall failed", program_invocation_short_name);
-  }
-
-  // Don't give freed memory back to the OS.
-  AOS_CHECK_EQ(1, mallopt(M_TRIM_THRESHOLD, -1));
-  // Don't use mmap for large malloc chunks.
-  AOS_CHECK_EQ(1, mallopt(M_MMAP_MAX, 0));
-
-  if (&FLAGS_tcmalloc_release_rate) {
-    // Tell tcmalloc not to return memory.
-    FLAGS_tcmalloc_release_rate = 0.0;
-  }
-
-  // Forces the memory pages for all the stack space that we're ever going to
-  // use to be loaded into memory (so it can be locked there).
-  uint8_t data[4096 * 8];
-  // Not 0 because linux might optimize that to a 0-filled page.
-  memset(data, 1, sizeof(data));
-
-  static const size_t kHeapPreallocSize = 512 * 1024;
-  char *const heap_data = static_cast<char *>(malloc(kHeapPreallocSize));
-  memset(heap_data, 1, kHeapPreallocSize);
-  free(heap_data);
+void InitGoogle(int *argc, char ***argv) {
+  FLAGS_logtostderr = true;
+  google::InitGoogleLogging((*argv)[0]);
+  gflags::ParseCommandLineFlags(argc, argv, true);
+  google::InstallFailureSignalHandler();
 }
 
 void InitNRT(bool for_realtime) {
@@ -120,16 +78,6 @@
   GoRT(relative_priority);
 }
 
-void InitRT() {
-  LockAllMemory();
-
-  // Only let rt processes run for 3 seconds straight.
-  SetSoftRLimit(RLIMIT_RTTIME, 3000000, true);
-
-  // Allow rt processes up to priority 40.
-  SetSoftRLimit(RLIMIT_RTPRIO, 40, false);
-}
-
 void GoRT(int relative_priority) {
   if (ShouldBeRealtime()) {
     InitRT();
@@ -155,30 +103,6 @@
   aos_core_free_shared_mem();
 }
 
-void WriteCoreDumps() {
-  // Do create core files of unlimited size.
-  SetSoftRLimit(RLIMIT_CORE, RLIM_INFINITY, true);
-}
-
-void SetCurrentThreadRealtimePriority(int priority) {
-  // Make sure we will only be allowed to run for 3 seconds straight.
-  SetSoftRLimit(RLIMIT_RTTIME, 3000000, true);
-
-  struct sched_param param;
-  param.sched_priority = priority;
-  if (sched_setscheduler(0, SCHED_FIFO, &param) == -1) {
-    AOS_PLOG(FATAL, "sched_setscheduler(0, SCHED_FIFO, %d) failed\n", priority);
-  }
-}
-
-void UnsetCurrentThreadRealtimePriority() {
-  struct sched_param param;
-  param.sched_priority = 0;
-  if (sched_setscheduler(0, SCHED_OTHER, &param) == -1) {
-    AOS_PLOG(FATAL, "sched_setscheduler(0, SCHED_OTHER, 0) failed\n");
-  }
-}
-
 void PinCurrentThreadToCPU(int number) {
   cpu_set_t cpuset;
   CPU_ZERO(&cpuset);
@@ -186,13 +110,4 @@
   AOS_PRCHECK(pthread_setaffinity_np(pthread_self(), sizeof(cpuset), &cpuset));
 }
 
-void SetCurrentThreadName(const ::std::string &name) {
-  if (name.size() > 16) {
-    AOS_LOG(FATAL, "thread name '%s' too long\n", name.c_str());
-  }
-  AOS_LOG(INFO, "this thread is changing to '%s'\n", name.c_str());
-  AOS_PCHECK(prctl(PR_SET_NAME, name.c_str()));
-  logging::internal::ReloadThreadName();
-}
-
 }  // namespace aos
diff --git a/aos/init.h b/aos/init.h
index be99a24..85d5da7 100644
--- a/aos/init.h
+++ b/aos/init.h
@@ -5,6 +5,9 @@
 
 namespace aos {
 
+// Initializes glog and gflags.
+void InitGoogle(int *argc, char ***argv);
+
 // In order to use shared memory, one of the Init* functions must be called in
 // exactly 1 thread per process. It is OK to keep going without calling one of
 // them again after fork(2)ing.
@@ -23,35 +26,12 @@
 // exit gracefully).
 void Cleanup();
 
-// Locks everything into memory and sets the limits.  This plus InitNRT are
-// everything you need to do before SetCurrentThreadRealtimePriority will make
-// your thread RT.  Called as part of ShmEventLoop::Run()
-void InitRT();
-
 // Performs the realtime parts of initialization after InitNRT(true) has been called.
 void GoRT(int relative_priority = 0);
 
-// Sets up this process to write core dump files.
-// This is called by Init*, but it's here for other files that want this
-// behavior without calling Init*.
-void WriteCoreDumps();
-
-// Sets the current thread's realtime priority.
-void SetCurrentThreadRealtimePriority(int priority);
-
-// Sets the current thread back down to non-realtime priority.
-void UnsetCurrentThreadRealtimePriority();
-
 // Pins the current thread to CPU #number.
 void PinCurrentThreadToCPU(int number);
 
-// Sets the name of the current thread.
-// This will displayed by `top -H`, dump_rtprio, and show up in logs.
-// name can have a maximum of 16 characters.
-void SetCurrentThreadName(const ::std::string &name);
-
-void LockAllMemory();
-
 }  // namespace aos
 
 #endif  // AOS_INIT_H_
diff --git a/aos/input/BUILD b/aos/input/BUILD
index 0da8d01..b4ceea6 100644
--- a/aos/input/BUILD
+++ b/aos/input/BUILD
@@ -9,11 +9,10 @@
         "joystick_input.h",
     ],
     deps = [
-        "//aos/events:event-loop",
+        "//aos/events:event_loop",
         "//aos/input:driver_station_data",
         "//aos/logging",
-        "//aos/logging:queue_logging",
-        "//aos/robot_state",
+        "//aos/robot_state:robot_state_fbs",
     ],
 )
 
@@ -29,10 +28,11 @@
         "//aos:math",
         "//aos/input:driver_station_data",
         "//aos/logging",
-        "//aos/logging:queue_logging",
-        "//aos/robot_state",
+        "//aos/robot_state:robot_state_fbs",
+        "//frc971/control_loops:control_loops_fbs",
         "//frc971/control_loops/drivetrain:drivetrain_config",
-        "//frc971/control_loops/drivetrain:drivetrain_queue",
+        "//frc971/control_loops/drivetrain:drivetrain_goal_fbs",
+        "//frc971/control_loops/drivetrain:drivetrain_status_fbs",
     ],
 )
 
@@ -45,7 +45,8 @@
         "driver_station_data.h",
     ],
     deps = [
-        "//aos/robot_state",
+        "//aos/robot_state:joystick_state_fbs",
+        "@com_github_google_glog//:glog",
     ],
 )
 
@@ -54,12 +55,12 @@
     srcs = ["action_joystick_input.cc"],
     hdrs = ["action_joystick_input.h"],
     deps = [
+        ":drivetrain_input",
         "//aos:init",
         "//aos/actions:action_lib",
-        "//aos/input:drivetrain_input",
         "//aos/input:joystick_input",
         "//aos/logging",
-        "//frc971/autonomous:auto_queue",
+        "//frc971/autonomous:auto_fbs",
         "//frc971/autonomous:base_autonomous_actor",
     ],
 )
diff --git a/aos/input/action_joystick_input.cc b/aos/input/action_joystick_input.cc
index 509f4c5..376009b 100644
--- a/aos/input/action_joystick_input.cc
+++ b/aos/input/action_joystick_input.cc
@@ -1,7 +1,7 @@
 #include "aos/input/action_joystick_input.h"
 
 #include "aos/input/driver_station_data.h"
-#include "frc971/autonomous/auto.q.h"
+#include "frc971/autonomous/auto_generated.h"
 #include "frc971/autonomous/base_autonomous_actor.h"
 
 using ::aos::input::driver_station::ControlBit;
@@ -49,8 +49,10 @@
 
 void ActionJoystickInput::StartAuto() {
   AOS_LOG(INFO, "Starting auto mode\n");
-  action_queue_.EnqueueAction(
-      autonomous_action_factory_.Make(GetAutonomousMode()));
+  frc971::autonomous::AutonomousActionParamsT params;
+  params.mode = GetAutonomousMode();
+
+  action_queue_.EnqueueAction(autonomous_action_factory_.Make(params));
   auto_action_running_ = true;
 }
 
diff --git a/aos/input/action_joystick_input.h b/aos/input/action_joystick_input.h
index 3057ace..781e224 100644
--- a/aos/input/action_joystick_input.h
+++ b/aos/input/action_joystick_input.h
@@ -4,7 +4,7 @@
 #include "aos/input/driver_station_data.h"
 #include "aos/input/drivetrain_input.h"
 #include "aos/input/joystick_input.h"
-#include "frc971/autonomous/auto.q.h"
+#include "frc971/autonomous/auto_generated.h"
 #include "frc971/autonomous/base_autonomous_actor.h"
 
 namespace aos {
@@ -99,7 +99,7 @@
       AOS_LOG(WARNING, "no auto mode values\n");
       return 0;
     }
-    return autonomous_mode_fetcher_->mode;
+    return autonomous_mode_fetcher_->mode();
   }
 
   // True if the internal state machine thinks auto is running right now.
diff --git a/aos/input/driver_station_data.cc b/aos/input/driver_station_data.cc
index 8898ca1..9e3bc52 100644
--- a/aos/input/driver_station_data.cc
+++ b/aos/input/driver_station_data.cc
@@ -1,20 +1,39 @@
 #include "aos/input/driver_station_data.h"
 
+#include "glog/logging.h"
+
 namespace aos {
 namespace input {
 namespace driver_station {
 
 Data::Data() : current_values_(), old_values_() {}
 
-void Data::Update(const JoystickState &new_values) {
+void Data::Update(const JoystickState *new_values) {
   old_values_ = current_values_;
-  current_values_ = new_values;
+  CHECK(new_values->has_joysticks());
+  CHECK_EQ(new_values->joysticks()->size(), current_values_.joysticks.size());
+  for (size_t i = 0; i < current_values_.joysticks.size(); ++i) {
+    const Joystick *joystick = new_values->joysticks()->Get(i);
+    current_values_.joysticks[i].buttons =
+        joystick->buttons();
+    current_values_.joysticks[i].pov = joystick->pov();
+    for (size_t j = 0; j < joystick->axis()->size(); ++j) {
+      current_values_.joysticks[i].axis[j] = joystick->axis()->Get(j);
+    }
+
+    current_values_.joysticks[i].pov = joystick->pov();
+  }
+  current_values_.test_mode = new_values->test_mode();
+  current_values_.fms_attached = new_values->fms_attached();
+  current_values_.enabled = new_values->enabled();
+  current_values_.autonomous = new_values->autonomous();
+  current_values_.team_id = new_values->team_id();
+  current_values_.switch_left = new_values->switch_left();
+  current_values_.scale_left = new_values->scale_left();
 }
 
-namespace {
-
-bool GetButton(const ButtonLocation location,
-               const JoystickState &values) {
+bool Data::GetButton(const ButtonLocation location,
+                     const Data::SavedJoystickState &values) {
   if (location.joystick() < 0 ||
       location.joystick() > static_cast<int>(values.joysticks.size())) {
     return false;
@@ -23,15 +42,16 @@
     return false;
   }
   return values.joysticks[location.joystick() - 1].buttons &
-      (1 << (location.number() - 1));
+         (1 << (location.number() - 1));
 }
 
-bool DoGetPOV(const POVLocation location, const JoystickState &values) {
+bool Data::DoGetPOV(const POVLocation location,
+                    const Data::SavedJoystickState &values) {
   return values.joysticks[location.joystick() - 1].pov == location.number();
 }
 
-bool GetControlBitValue(const ControlBit bit,
-                        const JoystickState &values) {
+bool Data::GetControlBitValue(const ControlBit bit,
+                              const Data::SavedJoystickState &values) {
   switch (bit) {
     case ControlBit::kTestMode:
       return values.test_mode;
@@ -46,8 +66,6 @@
   }
 }
 
-}  // namespace
-
 bool Data::IsPressed(const ButtonLocation location) const {
   return GetButton(location, current_values_);
 }
diff --git a/aos/input/driver_station_data.h b/aos/input/driver_station_data.h
index 6a52248..18eb579 100644
--- a/aos/input/driver_station_data.h
+++ b/aos/input/driver_station_data.h
@@ -4,9 +4,10 @@
 // This file defines several types to support nicely looking at the data
 // received from the driver's station.
 
+#include <array>
 #include <memory>
 
-#include "aos/robot_state/robot_state.q.h"
+#include "aos/robot_state/joystick_state_generated.h"
 
 namespace aos {
 namespace input {
@@ -20,8 +21,7 @@
       : joystick_(joystick), number_(number) {}
 
   // How many joysticks there are.
-  static const int kJoysticks = sizeof(JoystickState::joysticks) /
-                                sizeof(JoystickState::joysticks[0]);
+  static const int kJoysticks = 6;
 
   // Which joystick number this is (1-based).
   int joystick() const { return joystick_; }
@@ -68,8 +68,7 @@
       : JoystickFeature(joystick, number) {}
 
   // How many axes there are available on each joystick.
-  static const int kAxes = sizeof(Joystick::axis) /
-                           sizeof(Joystick::axis[0]);
+  static const int kAxes = 6;
 };
 
 class Data {
@@ -79,7 +78,7 @@
   Data();
 
   // Updates the current information with a new set of values.
-  void Update(const JoystickState &new_values);
+  void Update(const JoystickState *new_values);
 
   bool IsPressed(POVLocation location) const;
   bool PosEdge(POVLocation location) const;
@@ -101,7 +100,34 @@
   float GetAxis(JoystickAxis axis) const;
 
  private:
-  JoystickState current_values_, old_values_;
+  struct SavedJoystickState {
+    struct SavedJoystick {
+      uint16_t buttons = 0;
+      std::array<double, JoystickAxis::kAxes> axis;
+      int pov = 0;
+    };
+
+    std::array<SavedJoystick, JoystickFeature::kJoysticks> joysticks;
+    bool test_mode = false;
+    bool fms_attached = false;
+    bool enabled = false;
+    bool autonomous = false;
+    uint16_t team_id = 0;
+
+    // 2018 scale and switch positions.
+    bool switch_left = false;
+    bool scale_left = false;
+  };
+
+  static bool GetButton(const ButtonLocation location,
+                        const Data::SavedJoystickState &values);
+  static bool DoGetPOV(const POVLocation location,
+                       const Data::SavedJoystickState &values);
+
+  static bool GetControlBitValue(const ControlBit bit,
+                                 const Data::SavedJoystickState &values);
+
+  SavedJoystickState current_values_, old_values_;
 };
 
 }  // namespace driver_station
diff --git a/aos/input/drivetrain_input.cc b/aos/input/drivetrain_input.cc
index a0bbf2c..687c8bb 100644
--- a/aos/input/drivetrain_input.cc
+++ b/aos/input/drivetrain_input.cc
@@ -8,13 +8,17 @@
 #include "aos/commonmath.h"
 #include "aos/input/driver_station_data.h"
 #include "aos/logging/logging.h"
-#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+#include "frc971/control_loops/control_loops_generated.h"
+#include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
+#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
 
 using ::aos::input::driver_station::ButtonLocation;
 using ::aos::input::driver_station::ControlBit;
 using ::aos::input::driver_station::JoystickAxis;
 using ::aos::input::driver_station::POVLocation;
 
+namespace drivetrain = frc971::control_loops::drivetrain;
+
 namespace aos {
 namespace input {
 
@@ -33,7 +37,7 @@
 
   drivetrain_status_fetcher_.Fetch();
   if (drivetrain_status_fetcher_.get()) {
-    robot_velocity_ = drivetrain_status_fetcher_->robot_speed;
+    robot_velocity_ = drivetrain_status_fetcher_->robot_speed();
   }
 
   // If we have a vision align function, and it is in control, don't run the
@@ -71,9 +75,9 @@
 
   if (drivetrain_status_fetcher_.get()) {
     if (is_control_loop_driving && !last_is_control_loop_driving_) {
-      left_goal_ = drivetrain_status_fetcher_->estimated_left_position +
+      left_goal_ = drivetrain_status_fetcher_->estimated_left_position() +
                    wheel * wheel_multiplier_;
-      right_goal_ = drivetrain_status_fetcher_->estimated_right_position -
+      right_goal_ = drivetrain_status_fetcher_->estimated_right_position() -
                     wheel * wheel_multiplier_;
     }
   }
@@ -82,24 +86,36 @@
       left_goal_ - wheel * wheel_multiplier_ + throttle * 0.3;
   const double current_right_goal =
       right_goal_ + wheel * wheel_multiplier_ + throttle * 0.3;
-  auto new_drivetrain_goal = drivetrain_goal_sender_.MakeMessage();
-  new_drivetrain_goal->wheel = wheel;
-  new_drivetrain_goal->wheel_velocity = wheel_velocity;
-  new_drivetrain_goal->wheel_torque = wheel_torque;
-  new_drivetrain_goal->throttle = throttle;
-  new_drivetrain_goal->throttle_velocity = throttle_velocity;
-  new_drivetrain_goal->throttle_torque = throttle_torque;
-  new_drivetrain_goal->highgear = high_gear;
-  new_drivetrain_goal->quickturn = data.IsPressed(quick_turn_);
-  new_drivetrain_goal->controller_type =
-      is_line_following ? 3 : (is_control_loop_driving ? 1 : 0);
-  new_drivetrain_goal->left_goal = current_left_goal;
-  new_drivetrain_goal->right_goal = current_right_goal;
+  auto builder = drivetrain_goal_sender_.MakeBuilder();
 
-  new_drivetrain_goal->linear.max_velocity = 3.0;
-  new_drivetrain_goal->linear.max_acceleration = 20.0;
+  frc971::ProfileParameters::Builder linear_builder =
+      builder.MakeBuilder<frc971::ProfileParameters>();
 
-  if (!new_drivetrain_goal.Send()) {
+  linear_builder.add_max_velocity(3.0);
+  linear_builder.add_max_acceleration(20.0);
+
+  flatbuffers::Offset<frc971::ProfileParameters> linear_offset =
+      linear_builder.Finish();
+
+  auto goal_builder = builder.MakeBuilder<drivetrain::Goal>();
+  goal_builder.add_wheel(wheel);
+  goal_builder.add_wheel_velocity(wheel_velocity);
+  goal_builder.add_wheel_torque(wheel_torque);
+  goal_builder.add_throttle(throttle);
+  goal_builder.add_throttle_velocity(throttle_velocity);
+  goal_builder.add_throttle_torque(throttle_torque);
+  goal_builder.add_highgear(high_gear);
+  goal_builder.add_quickturn(data.IsPressed(quick_turn_));
+  goal_builder.add_controller_type(
+      is_line_following
+          ? drivetrain::ControllerType_LINE_FOLLOWER
+          : (is_control_loop_driving ? drivetrain::ControllerType_MOTION_PROFILE
+                                     : drivetrain::ControllerType_POLYDRIVE));
+  goal_builder.add_left_goal(current_left_goal);
+  goal_builder.add_right_goal(current_right_goal);
+  goal_builder.add_linear(linear_offset);
+
+  if (!builder.Send(goal_builder.Finish())) {
     AOS_LOG(WARNING, "sending stick values failed\n");
   }
 
@@ -304,8 +320,7 @@
 }
 ::std::unique_ptr<DrivetrainInputReader> DrivetrainInputReader::Make(
     ::aos::EventLoop *event_loop, InputType type,
-    const ::frc971::control_loops::drivetrain::DrivetrainConfig<double>
-        &dt_config) {
+    const drivetrain::DrivetrainConfig<double> &dt_config) {
   std::unique_ptr<DrivetrainInputReader> drivetrain_input_reader;
 
   using InputType = DrivetrainInputReader::InputType;
diff --git a/aos/input/drivetrain_input.h b/aos/input/drivetrain_input.h
index 26dfe95..0c43d99 100644
--- a/aos/input/drivetrain_input.h
+++ b/aos/input/drivetrain_input.h
@@ -9,8 +9,10 @@
 
 #include "aos/input/driver_station_data.h"
 #include "aos/logging/logging.h"
-#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+#include "frc971/control_loops/control_loops_generated.h"
 #include "frc971/control_loops/drivetrain/drivetrain_config.h"
+#include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
+#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
 
 namespace aos {
 namespace input {
@@ -60,12 +62,11 @@
         turn2_use_(turn2_use),
         drivetrain_status_fetcher_(
             event_loop
-                ->MakeFetcher<::frc971::control_loops::DrivetrainQueue::Status>(
-                    ".frc971.control_loops.drivetrain_queue.status")),
+                ->MakeFetcher<::frc971::control_loops::drivetrain::Status>(
+                    "/drivetrain")),
         drivetrain_goal_sender_(
-            event_loop
-                ->MakeSender<::frc971::control_loops::DrivetrainQueue::Goal>(
-                    ".frc971.control_loops.drivetrain_queue.goal")) {}
+            event_loop->MakeSender<::frc971::control_loops::drivetrain::Goal>(
+                "/drivetrain")) {}
 
   virtual ~DrivetrainInputReader() = default;
 
@@ -130,9 +131,9 @@
   virtual WheelAndThrottle GetWheelAndThrottle(
       const ::aos::input::driver_station::Data &data) = 0;
 
-  ::aos::Fetcher<::frc971::control_loops::DrivetrainQueue::Status>
+  ::aos::Fetcher<::frc971::control_loops::drivetrain::Status>
       drivetrain_status_fetcher_;
-  ::aos::Sender<::frc971::control_loops::DrivetrainQueue::Goal>
+  ::aos::Sender<::frc971::control_loops::drivetrain::Goal>
       drivetrain_goal_sender_;
 
   double robot_velocity_ = 0.0;
diff --git a/aos/input/joystick_input.cc b/aos/input/joystick_input.cc
index d1bd302..743e138 100644
--- a/aos/input/joystick_input.cc
+++ b/aos/input/joystick_input.cc
@@ -3,18 +3,17 @@
 #include <string.h>
 #include <atomic>
 
-#include "aos/robot_state/robot_state.q.h"
 #include "aos/logging/logging.h"
-#include "aos/logging/queue_logging.h"
+#include "aos/robot_state/robot_state_generated.h"
 
 namespace aos {
 namespace input {
 
-void JoystickInput::HandleData(const ::aos::JoystickState &joystick_state) {
+void JoystickInput::HandleData(const ::aos::JoystickState *joystick_state) {
   data_.Update(joystick_state);
 
-  mode_ = static_cast<int>(joystick_state.switch_left) |
-          (static_cast<int>(joystick_state.scale_left) << 1);
+  mode_ = static_cast<int>(joystick_state->switch_left()) |
+          (static_cast<int>(joystick_state->scale_left()) << 1);
 
   {
     using driver_station::JoystickFeature;
diff --git a/aos/input/joystick_input.h b/aos/input/joystick_input.h
index ed72e78..5e8bf5a 100644
--- a/aos/input/joystick_input.h
+++ b/aos/input/joystick_input.h
@@ -3,7 +3,7 @@
 
 #include <atomic>
 
-#include "aos/events/event-loop.h"
+#include "aos/events/event_loop.h"
 #include "aos/input/driver_station_data.h"
 
 namespace aos {
@@ -21,7 +21,7 @@
     event_loop_->MakeWatcher(
         ".aos.joystick_state",
         [this](const ::aos::JoystickState &joystick_state) {
-          this->HandleData(joystick_state);
+          this->HandleData(&joystick_state);
         });
     event_loop->SetRuntimeRealtimePriority(29);
   }
@@ -30,7 +30,7 @@
   int mode() const { return mode_; }
 
  private:
-  void HandleData(const ::aos::JoystickState &joystick_state);
+  void HandleData(const ::aos::JoystickState *joystick_state);
 
   // Subclasses should do whatever they want with data here.
   virtual void RunIteration(const driver_station::Data &data) = 0;
@@ -41,12 +41,6 @@
   int mode_;
 };
 
-// Class which will proxy joystick information from UDP packets to the queues.
-class JoystickProxy {
- public:
-  void Run();
-};
-
 }  // namespace input
 }  // namespace aos
 
diff --git a/aos/ipc_lib/BUILD b/aos/ipc_lib/BUILD
index 684620a..908cb80 100644
--- a/aos/ipc_lib/BUILD
+++ b/aos/ipc_lib/BUILD
@@ -1,5 +1,3 @@
-package(default_visibility = ["//visibility:public"])
-
 cc_library(
     name = "aos_sync",
     srcs = [
@@ -11,11 +9,12 @@
     linkopts = [
         "-lpthread",
     ],
+    visibility = ["//visibility:public"],
     deps = [
         "//aos:macros",
-        "@com_google_absl//absl/base",
-        "//aos/logging",
         "//aos/util:compiler_memory_barrier",
+        "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/base",
     ],
 )
 
@@ -27,6 +26,7 @@
     hdrs = [
         "core_lib.h",
     ],
+    visibility = ["//visibility:public"],
     deps = [
         ":aos_sync",
         ":shared_mem_types",
@@ -36,7 +36,7 @@
 cc_library(
     name = "shared_mem",
     srcs = [
-        "shared_mem.c",
+        "shared_mem.cc",
     ],
     hdrs = [
         "shared_mem.h",
@@ -44,11 +44,12 @@
     linkopts = [
         "-lrt",
     ],
+    visibility = ["//visibility:public"],
     deps = [
         ":aos_sync",
         ":core_lib",
         ":shared_mem_types",
-        "//aos/logging",
+        "@com_github_google_glog//:glog",
     ],
 )
 
@@ -75,11 +76,11 @@
     linkopts = [
         "-lrt",
     ],
+    visibility = ["//visibility:public"],
     deps = [
         ":core_lib",
         ":shared_mem",
         "//aos:condition",
-        "//aos/logging",
         "//aos/mutex",
         "//aos/util:options",
     ],
@@ -157,8 +158,9 @@
     hdrs = [
         "signalfd.h",
     ],
+    visibility = ["//visibility:public"],
     deps = [
-        "//aos/logging",
+        "@com_github_google_glog//:glog",
     ],
 )
 
@@ -166,6 +168,7 @@
     name = "index",
     srcs = ["index.cc"],
     hdrs = ["index.h"],
+    visibility = ["//visibility:public"],
 )
 
 cc_test(
@@ -174,7 +177,7 @@
     deps = [
         ":index",
         "//aos/testing:googletest",
-        "//aos/testing:test_logging",
+        "@com_github_google_glog//:glog",
     ],
 )
 
@@ -185,11 +188,11 @@
         "lockless_queue_memory.h",
     ],
     hdrs = ["lockless_queue.h"],
+    visibility = ["//visibility:public"],
     deps = [
         ":aos_sync",
         ":index",
-        "//aos:init",
-        "//aos/logging",
+        "//aos:realtime",
         "//aos/time",
         "//aos/util:compiler_memory_barrier",
         "@com_github_google_glog//:glog",
@@ -208,7 +211,7 @@
     deps = [
         ":lockless_queue",
         "//aos:event",
-        "//third_party/googletest:gtest",
+        "//aos/testing:googletest",
     ],
 )
 
@@ -225,7 +228,6 @@
         "//aos/libc:aos_strsignal",
         "//aos/testing:googletest",
         "//aos/testing:prevent_exit",
-        "//aos/testing:test_logging",
     ],
 )
 
diff --git a/aos/ipc_lib/aos_sync.cc b/aos/ipc_lib/aos_sync.cc
index 3bdba21..efb1fb1 100644
--- a/aos/ipc_lib/aos_sync.cc
+++ b/aos/ipc_lib/aos_sync.cc
@@ -26,10 +26,10 @@
 #include <algorithm>
 #include <type_traits>
 
-#include "aos/logging/logging.h"
+#include "absl/base/call_once.h"
 #include "aos/macros.h"
 #include "aos/util/compiler_memory_barrier.h"
-#include "absl/base/call_once.h"
+#include "glog/logging.h"
 
 using ::aos::linux_code::ipc_lib::FutexAccessorObserver;
 
@@ -354,16 +354,16 @@
   return r;
 }
 
-// This gets called by functions before AOS_LOG(FATAL)ing with error messages
+// This gets called by functions before LOG(FATAL)ing with error messages
 // that would be incorrect if the error was caused by a process forking without
 // initialize_in_new_thread getting called in the fork.
 void check_cached_tid(pid_t tid) {
   pid_t actual = do_get_tid();
   if (tid != actual) {
-    AOS_LOG(FATAL,
-            "task %jd forked into %jd without letting aos_sync know"
-            " so we're not really sure what's going on\n",
-            static_cast<intmax_t>(tid), static_cast<intmax_t>(actual));
+    LOG(FATAL) << "task " << static_cast<intmax_t>(tid) << " forked into "
+               << static_cast<intmax_t>(actual)
+               << " without letting aos_sync know so we're not really sure "
+                  "what's going on";
   }
 }
 
@@ -378,9 +378,9 @@
 }
 
 void InstallAtforkHook() {
-  if (pthread_atfork(NULL, NULL, atfork_child) != 0) {
-    AOS_PLOG(FATAL, "pthread_atfork(NULL, NULL, %p) failed", atfork_child);
-  }
+  PCHECK(pthread_atfork(NULL, NULL, &atfork_child) == 0)
+      << ": pthread_atfork(NULL, NULL, "
+      << reinterpret_cast<void *>(&atfork_child) << ") failed";
 }
 
 // This gets called to set everything up in a new thread by get_tid().
@@ -472,11 +472,10 @@
   robust_head.futex_offset = static_cast<ssize_t>(offsetof(aos_mutex, futex)) -
                              static_cast<ssize_t>(offsetof(aos_mutex, next));
   robust_head.pending_next = 0;
-  if (syscall(SYS_set_robust_list, robust_head_next_value(), sizeof(robust_head)) !=
-      0) {
-    AOS_PLOG(FATAL, "set_robust_list(%p, %zd) failed",
-             reinterpret_cast<void *>(robust_head.next), sizeof(robust_head));
-  }
+  PCHECK(syscall(SYS_set_robust_list, robust_head_next_value(),
+                 sizeof(robust_head)) == 0)
+      << ": set_robust_list(" << reinterpret_cast<void *>(robust_head.next)
+      << ", " << sizeof(robust_head) << ") failed";
   if (kRobustListDebug) {
     printf("%" PRId32 ": init done\n", get_tid());
   }
@@ -675,12 +674,12 @@
           }
         }
         my_robust_list::robust_head.pending_next = 0;
-        if (ret == -EDEADLK) {
-          AOS_LOG(FATAL, "multiple lock of %p by %" PRId32 "\n", m, tid);
-        }
-        AOS_PELOG(FATAL, -ret, "FUTEX_LOCK_PI(%p(=%" PRIu32 "), 1, %p) failed",
-                  &m->futex, __atomic_load_n(&m->futex, __ATOMIC_SEQ_CST),
-                  timeout);
+        CHECK_NE(ret, -EDEADLK) << ": multiple lock of " << m << " by " << tid;
+
+        errno = -ret;
+        PLOG(FATAL) << "FUTEX_LOCK_PI(" << &m->futex
+                    << "(=" << __atomic_load_n(&m->futex, __ATOMIC_SEQ_CST)
+                    << "), 1, " << timeout << ") failed";
       } else {
         if (kLockDebug) {
           printf("%" PRId32 ": %p kernel lock done\n", tid, m);
@@ -746,8 +745,9 @@
         continue;
       }
       my_robust_list::robust_head.pending_next = 0;
-      AOS_PELOG(FATAL, -ret, "FUTEX_CMP_REQUEUE_PI(%p, 1, %d, %p, *%p) failed",
-                c, number_requeue, &m->futex, c);
+      errno = -ret;
+      PLOG(FATAL) << "FUTEX_CMP_REQUEUE_PI(" << c << ", 1, " << number_requeue
+                  << ", " << &m->futex << ", *" << c << ") failed";
     } else {
       return;
     }
@@ -778,11 +778,10 @@
     my_robust_list::robust_head.pending_next = 0;
     check_cached_tid(tid);
     if ((value & FUTEX_TID_MASK) == 0) {
-      AOS_LOG(FATAL, "multiple unlock of aos_mutex %p by %" PRId32 "\n", m,
-              tid);
+      LOG(FATAL) << "multiple unlock of aos_mutex " << m << " by " << tid;
     } else {
-      AOS_LOG(FATAL, "aos_mutex %p is locked by %" PRId32 ", not %" PRId32 "\n",
-              m, value & FUTEX_TID_MASK, tid);
+      LOG(FATAL) << "aos_mutex " << m << " is locked by "
+                 << (value & FUTEX_TID_MASK) << ", not " << tid;
     }
   }
 
@@ -795,7 +794,8 @@
     const int ret = sys_futex_unlock_pi(&m->futex);
     if (ret != 0) {
       my_robust_list::robust_head.pending_next = 0;
-      AOS_PELOG(FATAL, -ret, "FUTEX_UNLOCK_PI(%p) failed", &m->futex);
+      errno = -ret;
+      PLOG(FATAL) << "FUTEX_UNLOCK_PI(" << (&m->futex) << ") failed";
     }
   } else {
     // There aren't any waiters, so no need to call into the kernel.
@@ -832,8 +832,9 @@
           return 4;
         }
         my_robust_list::robust_head.pending_next = 0;
-        AOS_PELOG(FATAL, -ret, "FUTEX_TRYLOCK_PI(%p, 0, NULL) failed",
-                  &m->futex);
+        errno = -ret;
+        PLOG(FATAL) << "FUTEX_TRYLOCK_PI(" << (&m->futex)
+                    << ", 0, NULL) failed";
       }
     }
   }
@@ -898,9 +899,9 @@
         continue;
       }
       my_robust_list::robust_head.pending_next = 0;
-      AOS_PELOG(FATAL, -ret,
-                "FUTEX_WAIT_REQUEUE_PI(%p, %" PRIu32 ", %p) failed", c,
-                wait_start, &m->futex);
+      errno = -ret;
+      PLOG(FATAL) << "FUTEX_WAIT_REQUEUE_PI(" << c << ", " << wait_start << ", "
+                  << (&m->futex) << ") failed";
     } else {
       // Record that the kernel relocked it for us.
       lock_pthread_mutex(m);
diff --git a/aos/ipc_lib/index_test.cc b/aos/ipc_lib/index_test.cc
index 689ed24..2e9a37b 100644
--- a/aos/ipc_lib/index_test.cc
+++ b/aos/ipc_lib/index_test.cc
@@ -1,7 +1,7 @@
 #include "aos/ipc_lib/index.h"
 
-#include "aos/testing/test_logging.h"
 #include "gtest/gtest.h"
+#include "glog/logging.h"
 
 namespace aos {
 namespace ipc_lib {
@@ -10,7 +10,8 @@
 class QueueIndexTest : public ::testing::Test {
  protected:
   uint32_t GetIndex(const QueueIndex &index) {
-    printf("Index, count: %x, %x\n", index.index_, index.count_);
+    LOG(INFO) << "Index, count: " << std::hex << index.index_ << ", "
+              << index.count_;
     return index.index();
   }
 
diff --git a/aos/ipc_lib/ipc_comparison.cc b/aos/ipc_lib/ipc_comparison.cc
index 5ea1c8b..1553159 100644
--- a/aos/ipc_lib/ipc_comparison.cc
+++ b/aos/ipc_lib/ipc_comparison.cc
@@ -28,6 +28,7 @@
 #include "aos/logging/implementations.h"
 #include "aos/logging/logging.h"
 #include "aos/mutex/mutex.h"
+#include "aos/realtime.h"
 #include "aos/time/time.h"
 
 DEFINE_string(method, "", "Which IPC method to use");
diff --git a/aos/ipc_lib/lockless_queue.cc b/aos/ipc_lib/lockless_queue.cc
index cd0e2ae..c2b0254 100644
--- a/aos/ipc_lib/lockless_queue.cc
+++ b/aos/ipc_lib/lockless_queue.cc
@@ -9,9 +9,8 @@
 #include <iostream>
 #include <sstream>
 
-#include "aos/init.h"
 #include "aos/ipc_lib/lockless_queue_memory.h"
-#include "aos/logging/logging.h"
+#include "aos/realtime.h"
 #include "aos/util/compiler_memory_barrier.h"
 #include "glog/logging.h"
 
@@ -20,8 +19,6 @@
 
 namespace {
 
-constexpr bool kDebug = false;
-
 void GrabQueueSetupLockOrDie(LocklessQueueMemory *memory) {
   const int result = mutex_grab(&(memory->queue_setup_lock));
   CHECK(result == 0 || result == 1);
@@ -59,9 +56,7 @@
     const uint32_t tid =
         __atomic_load_n(&(sender->tid.futex), __ATOMIC_RELAXED);
     if (tid & FUTEX_OWNER_DIED) {
-      if (kDebug) {
-        printf("Found an easy death for sender %zu\n", i);
-      }
+      VLOG(3) << "Found an easy death for sender " << i;
       const Index to_replace = sender->to_replace.RelaxedLoad();
       const Index scratch_index = sender->scratch_index.Load();
 
@@ -119,9 +114,7 @@
     return;
   }
 
-  if (kDebug) {
-    printf("Starting hard cleanup\n");
-  }
+  VLOG(3) << "Starting hard cleanup";
 
   size_t num_accounted_for = 0;
   size_t num_missing = 0;
@@ -166,9 +159,8 @@
         // Candidate.
         CHECK_LE(to_replace.message_index(), accounted_for.size());
         if (accounted_for[to_replace.message_index()]) {
-          if (kDebug) {
-            printf("Sender %zu died, to_replace is already accounted for\n", i);
-          }
+          VLOG(3) << "Sender " << i
+                  << " died, to_replace is already accounted for";
           // If both are accounted for, we are corrupt...
           CHECK(!accounted_for[scratch_index.message_index()]);
 
@@ -185,9 +177,8 @@
           --num_missing;
           ++num_accounted_for;
         } else if (accounted_for[scratch_index.message_index()]) {
-          if (kDebug) {
-            printf("Sender %zu died, scratch_index is already accounted for\n", i);
-          }
+          VLOG(3) << "Sender " << i
+                  << " died, scratch_index is already accounted for";
           // scratch_index is accounted for.  That means we did the insert,
           // but didn't record it.
           CHECK(to_replace.valid());
@@ -204,9 +195,7 @@
           --num_missing;
           ++num_accounted_for;
         } else {
-          if (kDebug) {
-            printf("Sender %zu died, neither is accounted for\n", i);
-          }
+          VLOG(3) << "Sender " << i << " died, neither is accounted for";
           // Ambiguous.  There will be an unambiguous one somewhere that we
           // can do first.
         }
@@ -406,7 +395,8 @@
   // creating a pidfd is likely not RT.
   for (size_t i = 0; i < num_watchers; ++i) {
     Watcher *w = memory_->GetWatcher(i);
-    // Start by reading the tid.  This needs to be atomic to force it to come first.
+    // Start by reading the tid.  This needs to be atomic to force it to come
+    // first.
     watcher_copy_[i].tid = __atomic_load_n(&(w->tid.futex), __ATOMIC_SEQ_CST);
     watcher_copy_[i].pid = w->pid;
     watcher_copy_[i].priority = w->priority;
@@ -521,18 +511,32 @@
   return index;
 }
 
+size_t LocklessQueue::Sender::size() { return memory_->message_data_size(); }
+
+void *LocklessQueue::Sender::Data() {
+  ::aos::ipc_lib::Sender *sender = memory_->GetSender(sender_index_);
+  Index scratch_index = sender->scratch_index.RelaxedLoad();
+  Message *message = memory_->GetMessage(scratch_index);
+  message->header.queue_index.Invalidate();
+
+  return &message->data[0];
+}
+
 void LocklessQueue::Sender::Send(const char *data, size_t length) {
+  CHECK_LE(length, size());
+  memcpy(Data(), data, length);
+  Send(length);
+}
+
+void LocklessQueue::Sender::Send(size_t length) {
   const size_t queue_size = memory_->queue_size();
-  CHECK_LE(length, memory_->message_data_size());
+  CHECK_LE(length, size());
 
   ::aos::ipc_lib::Sender *sender = memory_->GetSender(sender_index_);
   Index scratch_index = sender->scratch_index.RelaxedLoad();
   Message *message = memory_->GetMessage(scratch_index);
 
-  message->header.queue_index.Invalidate();
-
   message->header.length = length;
-  memcpy(&message->data[0], data, length);
 
   while (true) {
     const QueueIndex actual_next_queue_index =
@@ -564,10 +568,8 @@
       memory_->next_queue_index.CompareAndExchangeStrong(
           actual_next_queue_index, incremented_queue_index);
 
-      if (kDebug) {
-        printf("We were beat.  Try again.  Was %x, is %x\n", to_replace.get(),
-               decremented_queue_index.index());
-      }
+      VLOG(3) << "We were beat.  Try again.  Was " << std::hex
+              << to_replace.get() << ", is " << decremented_queue_index.index();
       continue;
     }
 
@@ -581,12 +583,10 @@
               ->header.queue_index.RelaxedLoad(queue_size);
       if (previous_index != decremented_queue_index && previous_index.valid()) {
         // Retry.
-        if (kDebug) {
-          printf(
-              "Something fishy happened, queue index doesn't match.  Retrying. "
-              " Previous index was %x, should be %x\n",
-              previous_index.index(), decremented_queue_index.index());
-        }
+        VLOG(3) << "Something fishy happened, queue index doesn't match.  "
+                   "Retrying.  Previous index was "
+                << std::hex << previous_index.index() << ", should be "
+                << decremented_queue_index.index();
         continue;
       }
     }
@@ -597,8 +597,7 @@
     // Before we are fully done filling out the message, update the Sender state
     // with the new index to write.  This re-uses the barrier for the
     // queue_index store.
-    const Index index_to_write(next_queue_index,
-                               scratch_index.message_index());
+    const Index index_to_write(next_queue_index, scratch_index.message_index());
 
     sender->scratch_index.RelaxedStore(index_to_write);
 
@@ -616,9 +615,7 @@
              ->CompareAndExchangeStrong(to_replace, index_to_write)) {
       // Aw, didn't succeed.  Retry.
       sender->to_replace.RelaxedInvalidate();
-      if (kDebug) {
-        printf("Failed to wrap into queue\n");
-      }
+      VLOG(3) << "Failed to wrap into queue";
       continue;
     }
 
@@ -661,10 +658,8 @@
     if (starting_queue_index != queue_index) {
       // If we found a message that is exactly 1 loop old, we just wrapped.
       if (starting_queue_index == queue_index.DecrementBy(queue_size)) {
-        if (kDebug) {
-          printf("Matches: %x, %x\n", starting_queue_index.index(),
-                 queue_index.DecrementBy(queue_size).index());
-        }
+        VLOG(3) << "Matches: " << std::hex << starting_queue_index.index()
+                << ", " << queue_index.DecrementBy(queue_size).index();
         return ReadResult::NOTHING_NEW;
       } else {
         // Someone has re-used this message between when we pulled it out of the
@@ -673,9 +668,7 @@
         Message *new_m = memory_->GetMessage(queue_index);
         if (m != new_m) {
           m = new_m;
-          if (kDebug) {
-            printf("Retrying, m doesn't match\n");
-          }
+          VLOG(3) << "Retrying, m doesn't match";
           continue;
         }
 
@@ -686,17 +679,14 @@
         // Either we got too far behind (signaled by this being a valid
         // message), or this is one of the initial messages which are invalid.
         if (starting_queue_index.valid()) {
-          if (kDebug) {
-            printf("Too old.  Tried for %x, got %x, behind by %d\n",
-                   queue_index.index(), starting_queue_index.index(),
-                   starting_queue_index.index() - queue_index.index());
-          }
+          VLOG(3) << "Too old.  Tried for " << std::hex << queue_index.index()
+                  << ", got " << starting_queue_index.index() << ", behind by "
+                  << std::dec
+                  << (starting_queue_index.index() - queue_index.index());
           return ReadResult::TOO_OLD;
         }
 
-        if (kDebug) {
-          printf("Initial\n");
-        }
+        VLOG(3) << "Initial";
 
         // There isn't a valid message at this location.
         //
@@ -705,28 +695,24 @@
         // asking for something crazy, like something before the beginning of
         // the queue.  Tell them that they are behind.
         if (uint32_queue_index < memory_->queue_size()) {
-          if (kDebug) {
-            printf("Near zero, %x\n", uint32_queue_index);
-          }
+          VLOG(3) << "Near zero, " << std::hex << uint32_queue_index;
           return ReadResult::NOTHING_NEW;
         } else {
-          if (kDebug) {
-            printf("not near zero, %x\n", uint32_queue_index);
-          }
+          VLOG(3) << "not near zero, " << std::hex << uint32_queue_index;
           return ReadResult::TOO_OLD;
         }
       }
     }
-    if (kDebug) {
-      printf("Eq: %x, %x\n", starting_queue_index.index(), queue_index.index());
-    }
+    VLOG(3) << "Eq: " << std::hex << starting_queue_index.index() << ", "
+            << queue_index.index();
     break;
   }
 
-  // Then read the data out.
+  // Then read the data out.  Copy it all out to be deterministic and so we can
+  // make length be from either end.
   *monotonic_sent_time = m->header.monotonic_sent_time;
   *realtime_sent_time = m->header.realtime_sent_time;
-  memcpy(data, &m->data[0], m->header.length);
+  memcpy(data, &m->data[0], message_data_size());
   *length = m->header.length;
 
   // And finally, confirm that the message *still* points to the queue index we
@@ -735,20 +721,22 @@
   // it's lifetime.
   const QueueIndex final_queue_index = m->header.queue_index.Load(queue_size);
   if (final_queue_index != queue_index) {
-    if (kDebug) {
-      printf(
-          "Changed out from under us.  Reading %x, finished with %x, delta: "
-          "%d\n",
-          queue_index.index(), final_queue_index.index(),
-          final_queue_index.index() - queue_index.index());
-    }
-    return ReadResult::TOO_OLD;
+    VLOG(3) << "Changed out from under us.  Reading " << std::hex
+            << queue_index.index() << ", finished with "
+            << final_queue_index.index() << ", delta: " << std::dec
+            << (final_queue_index.index() - queue_index.index());
+    return ReadResult::OVERWROTE;
   }
 
   return ReadResult::GOOD;
 }
 
-uint32_t LocklessQueue::LatestQueueIndex() {
+size_t LocklessQueue::queue_size() const { return memory_->queue_size(); }
+size_t LocklessQueue::message_data_size() const {
+  return memory_->message_data_size();
+}
+
+QueueIndex LocklessQueue::LatestQueueIndex() {
   const size_t queue_size = memory_->queue_size();
 
   // There is only one interesting case.  We need to know if the queue is empty.
@@ -757,7 +745,7 @@
       memory_->next_queue_index.Load(queue_size);
   if (next_queue_index.valid()) {
     const QueueIndex current_queue_index = next_queue_index.DecrementBy(1u);
-    return current_queue_index.index();
+    return current_queue_index;
   } else {
     return empty_queue_index();
   }
@@ -845,7 +833,8 @@
   }
   ::std::cout << "  }" << ::std::endl;
 
-  ::std::cout << "  Sender senders[" << memory->num_senders() << "] {" << ::std::endl;
+  ::std::cout << "  Sender senders[" << memory->num_senders() << "] {"
+              << ::std::endl;
   for (size_t i = 0; i < memory->num_senders(); ++i) {
     Sender *s = memory->GetSender(i);
     ::std::cout << "    [" << i << "] -> Sender {" << ::std::endl;
diff --git a/aos/ipc_lib/lockless_queue.h b/aos/ipc_lib/lockless_queue.h
index dafc157..fcc5d79 100644
--- a/aos/ipc_lib/lockless_queue.h
+++ b/aos/ipc_lib/lockless_queue.h
@@ -106,7 +106,7 @@
 // Prints to stdout the data inside the queue for debugging.
 void PrintLocklessQueueMemory(LocklessQueueMemory *memory);
 
-const static int kWakeupSignal = SIGRTMIN + 2;
+const static unsigned int kWakeupSignal = SIGRTMIN + 2;
 
 // Class to manage sending and receiving data in the lockless queue.  This is
 // separate from the actual memory backing the queue so that memory can be
@@ -122,6 +122,8 @@
   // Returns the number of messages in the queue.
   size_t QueueSize() const;
 
+  size_t message_data_size() const;
+
   // Registers this thread to receive the kWakeupSignal signal when Wakeup is
   // called. Returns false if there was an error in registration.
   bool RegisterWakeup(int priority);
@@ -137,8 +139,9 @@
   // If you ask for a queue index 2 past the newest, you will still get
   // NOTHING_NEW until that gets overwritten with new data.  If you ask for an
   // element newer than QueueSize() from the current message, we consider it
-  // behind by a large amount and return TOO_OLD.
-  enum class ReadResult { TOO_OLD, GOOD, NOTHING_NEW };
+  // behind by a large amount and return TOO_OLD.  If the message is modified
+  // out from underneath us as we read it, return OVERWROTE.
+  enum class ReadResult { TOO_OLD, GOOD, NOTHING_NEW, OVERWROTE };
   ReadResult Read(uint32_t queue_index,
                   ::aos::monotonic_clock::time_point *monotonic_sent_time,
                   ::aos::realtime_clock::time_point *realtime_sent_time,
@@ -147,8 +150,12 @@
   // Returns the index to the latest queue message.  Returns empty_queue_index()
   // if there are no messages in the queue.  Do note that this index wraps if
   // more than 2^32 messages are sent.
-  uint32_t LatestQueueIndex();
-  static constexpr uint32_t empty_queue_index() { return 0xffffffff; }
+  QueueIndex LatestQueueIndex();
+  static QueueIndex empty_queue_index() { return QueueIndex::Invalid(); }
+
+  // Returns the size of the queue.  This is mostly useful for manipulating
+  // QueueIndex.
+  size_t queue_size() const;
 
   // TODO(austin): Return the oldest queue index.  This lets us catch up nicely
   // if we got behind.
@@ -181,6 +188,14 @@
 
     ~Sender();
 
+    // Sends a message without copying the data.
+    // Copy at most size() bytes of data into the memory pointed to by Data(),
+    // and then call Send().
+    // Note: calls to Data() are expensive enough that you should cache it.
+    size_t size();
+    void *Data();
+    void Send(size_t length);
+
     // Sends up to length data.  Does not wakeup the target.
     void Send(const char *data, size_t length);
 
diff --git a/aos/ipc_lib/lockless_queue_death_test.cc b/aos/ipc_lib/lockless_queue_death_test.cc
index 7a68273..4f1d7e4 100644
--- a/aos/ipc_lib/lockless_queue_death_test.cc
+++ b/aos/ipc_lib/lockless_queue_death_test.cc
@@ -11,10 +11,10 @@
 #include <memory>
 #include <thread>
 
-#include "aos/init.h"
 #include "aos/ipc_lib/aos_sync.h"
 #include "aos/ipc_lib/lockless_queue_memory.h"
 #include "aos/libc/aos_strsignal.h"
+#include "aos/realtime.h"
 #include "aos/testing/prevent_exit.h"
 #include "aos/testing/test_logging.h"
 #include "gflags/gflags.h"
@@ -507,14 +507,14 @@
 
   TestShmRobustness(
       config,
-      [this, config, tid](void *memory) {
+      [config, tid](void *memory) {
         // Initialize the queue and grab the tid.
         LocklessQueue queue(
             reinterpret_cast<aos::ipc_lib::LocklessQueueMemory *>(memory),
             config);
         *tid = gettid();
       },
-      [this, config](void *memory) {
+      [config](void *memory) {
         // Now try to write 2 messages.  We will get killed a bunch as this
         // tries to happen.
         LocklessQueue queue(
@@ -527,7 +527,7 @@
           sender.Send(data, s + 1);
         }
       },
-      [this, config, tid](void *raw_memory) {
+      [config, tid](void *raw_memory) {
         // Confirm that we can create 2 senders (the number in the queue), and
         // send a message.  And that all the messages in the queue are valid.
         ::aos::ipc_lib::LocklessQueueMemory *memory =
diff --git a/aos/ipc_lib/lockless_queue_test.cc b/aos/ipc_lib/lockless_queue_test.cc
index f3b49b6..b9cb54d 100644
--- a/aos/ipc_lib/lockless_queue_test.cc
+++ b/aos/ipc_lib/lockless_queue_test.cc
@@ -11,11 +11,10 @@
 
 #include "aos/event.h"
 #include "aos/events/epoll.h"
-#include "aos/init.h"
 #include "aos/ipc_lib/aos_sync.h"
 #include "aos/ipc_lib/queue_racer.h"
 #include "aos/ipc_lib/signalfd.h"
-#include "aos/testing/test_logging.h"
+#include "aos/realtime.h"
 #include "gflags/gflags.h"
 #include "gtest/gtest.h"
 
@@ -43,7 +42,6 @@
 class LocklessQueueTest : public ::testing::Test {
  public:
   LocklessQueueTest() {
-    ::aos::testing::EnableTestLogging();
     config_.num_watchers = 10;
     config_.num_senders = 100;
     config_.queue_size = 10000;
@@ -247,8 +245,8 @@
   // Send enough messages to wrap.
   for (int i = 0; i < 20000; ++i) {
     // Confirm that the queue index makes sense given the number of sends.
-    EXPECT_EQ(queue.LatestQueueIndex(),
-              i == 0 ? LocklessQueue::empty_queue_index() : i - 1);
+    EXPECT_EQ(queue.LatestQueueIndex().index(),
+              i == 0 ? LocklessQueue::empty_queue_index().index() : i - 1);
 
     // Send a trivial piece of data.
     char data[100];
@@ -257,7 +255,7 @@
 
     // Confirm that the queue index still makes sense.  This is easier since the
     // empty case has been handled.
-    EXPECT_EQ(queue.LatestQueueIndex(), i);
+    EXPECT_EQ(queue.LatestQueueIndex().index(), i);
 
     // Read a result from 5 in the past.
     ::aos::monotonic_clock::time_point monotonic_sent_time;
diff --git a/aos/ipc_lib/queue.cc b/aos/ipc_lib/queue.cc
index 5b6a0fa..3b6e5a1 100644
--- a/aos/ipc_lib/queue.cc
+++ b/aos/ipc_lib/queue.cc
@@ -172,7 +172,7 @@
   MessageHeader *header = __atomic_load_n(&free_messages_, __ATOMIC_RELAXED);
   do {
     if (__builtin_expect(header == nullptr, 0)) {
-      AOS_LOG(FATAL, "overused pool of queue %p (%s)\n", this, name_);
+      LOG(FATAL) << "overused pool of queue " << this << " (" << name_ << ")";
     }
   } while (__builtin_expect(
       !__atomic_compare_exchange_n(&free_messages_, &header, header->next, true,
@@ -195,10 +195,8 @@
   static_assert((sizeof(RawQueue::MessageHeader) % 8) == 0,
                 "need to revalidate size/alignent assumptions");
 
-  if (queue_length < 1) {
-    AOS_LOG(FATAL, "queue length %d of %s needs to be at least 1\n",
-            queue_length, name);
-  }
+  CHECK_GE(queue_length, 1) << ": queue length " << queue_length << " of "
+                            << name << " needs to be at least 1";
 
   const size_t name_size = strlen(name) + 1;
   char *temp = static_cast<char *>(shm_malloc(name_size));
@@ -249,8 +247,8 @@
     printf("fetching queue %s\n", name);
   }
   if (mutex_lock(&global_core->mem_struct->queues.lock) != 0) {
-    AOS_LOG(FATAL, "mutex_lock(%p) failed\n",
-            &global_core->mem_struct->queues.lock);
+    LOG(FATAL) << "mutex_lock(" << &global_core->mem_struct->queues.lock
+               << ") failed";
   }
   RawQueue *current =
       static_cast<RawQueue *>(global_core->mem_struct->queues.pointer);
@@ -302,14 +300,14 @@
 
 bool RawQueue::DoWriteMessage(void *msg, Options<RawQueue> options) {
   if (kWriteDebug) {
-    printf("queue: %p->WriteMessage(%p, %x)\n", this, msg, options.printable());
+    printf("queue: %p->WriteMessage(%p, %x), len :%zu\n", this, msg, options.printable(), msg_length_);
   }
 
   bool signal_readable;
 
   {
     IPCMutexLocker locker(&data_lock_);
-    AOS_CHECK(!locker.owner_died());
+    CHECK(!locker.owner_died());
 
     int new_end;
     while (true) {
@@ -334,7 +332,7 @@
         if (kWriteDebug) {
           printf("queue: going to wait for writable_ of %p\n", this);
         }
-        AOS_CHECK(!writable_.Wait());
+        CHECK(!writable_.Wait());
       }
     }
     data_[data_end_] = msg;
@@ -390,7 +388,7 @@
         if (wait_result == Condition::WaitResult::kOk) {
           break;
         }
-        AOS_CHECK(wait_result != Condition::WaitResult::kOwnerDied);
+        CHECK(wait_result != Condition::WaitResult::kOwnerDied);
         if (wait_result == Condition::WaitResult::kTimeout) {
           return false;
         }
@@ -427,7 +425,7 @@
   void *msg = NULL;
 
   IPCMutexLocker locker(&data_lock_);
-  AOS_CHECK(!locker.owner_died());
+  CHECK(!locker.owner_died());
 
   if (!ReadCommonStart(options, nullptr, chrono::nanoseconds(0))) {
     if (kReadDebug) {
@@ -490,7 +488,7 @@
   void *msg = NULL;
 
   IPCMutexLocker locker(&data_lock_);
-  AOS_CHECK(!locker.owner_died());
+  CHECK(!locker.owner_died());
 
   if (!ReadCommonStart(options, index, timeout)) {
     if (kReadDebug) {
diff --git a/aos/ipc_lib/queue.h b/aos/ipc_lib/queue.h
index 5b68f2e..6e07993 100644
--- a/aos/ipc_lib/queue.h
+++ b/aos/ipc_lib/queue.h
@@ -5,7 +5,7 @@
 #include "aos/mutex/mutex.h"
 #include "aos/condition.h"
 #include "aos/util/options.h"
-#include "aos/logging/logging.h"
+#include "glog/logging.h"
 
 // TODO(brians) add valgrind client requests to the queue and shared_mem_malloc
 // code to make checking for leaks work better
@@ -90,10 +90,11 @@
     static constexpr Options<RawQueue> kWriteFailureOptions =
         kNonBlock | kBlock | kOverride;
     if (!options.NoOthersSet(kWriteFailureOptions)) {
-      AOS_LOG(FATAL, "illegal write options in %x\n", options.printable());
+      LOG(FATAL) << "illegal write options in " << std::hex
+                 << options.printable();
     }
     if (!options.ExactlyOneSet(kWriteFailureOptions)) {
-      AOS_LOG(FATAL, "invalid write options %x\n", options.printable());
+      LOG(FATAL) << "invalid write options " << std::hex << options.printable();
     }
     return DoWriteMessage(msg, options);
   }
@@ -123,7 +124,7 @@
     CheckReadOptions(options);
     static constexpr Options<RawQueue> kFromEndAndPeek = kFromEnd | kPeek;
     if (options.AllSet(kFromEndAndPeek)) {
-      AOS_LOG(FATAL, "ReadMessageIndex(kFromEnd | kPeek) is not allowed\n");
+      LOG(FATAL) << "ReadMessageIndex(kFromEnd | kPeek) is not allowed";
     }
     return DoReadMessageIndex(options, index, timeout);
   }
@@ -161,11 +162,12 @@
     static constexpr Options<RawQueue> kValidOptions =
         kPeek | kFromEnd | kNonBlock | kBlock;
     if (!options.NoOthersSet(kValidOptions)) {
-      AOS_LOG(FATAL, "illegal read options in %x\n", options.printable());
+      LOG(FATAL) << "illegal read options in " << std::hex
+                 << options.printable();
     }
     static constexpr Options<RawQueue> kBlockChoices = kNonBlock | kBlock;
     if (!options.ExactlyOneSet(kBlockChoices)) {
-      AOS_LOG(FATAL, "invalid read options %x\n", options.printable());
+      LOG(FATAL) << "invalid read options " << std::hex << options.printable();
     }
   }
 
diff --git a/aos/ipc_lib/queue_racer.cc b/aos/ipc_lib/queue_racer.cc
index 53490a0..bb754d8 100644
--- a/aos/ipc_lib/queue_racer.cc
+++ b/aos/ipc_lib/queue_racer.cc
@@ -82,12 +82,15 @@
       //
       // So, grab them in order.
       const uint64_t finished_writes = finished_writes_.load();
-      const uint32_t latest_queue_index_uint32_t = queue.LatestQueueIndex();
+      const QueueIndex latest_queue_index_queue_index =
+          queue.LatestQueueIndex();
       const uint64_t started_writes = started_writes_.load();
 
+      const uint32_t latest_queue_index_uint32_t =
+          queue.LatestQueueIndex().index();
       uint64_t latest_queue_index = latest_queue_index_uint32_t;
 
-      if (latest_queue_index_uint32_t != LocklessQueue::empty_queue_index()) {
+      if (latest_queue_index_queue_index != LocklessQueue::empty_queue_index()) {
         // If we got smaller, we wrapped.
         if (latest_queue_index_uint32_t < last_queue_index) {
           ++wrap_count;
@@ -104,19 +107,19 @@
 
       // If we are at the beginning, the queue needs to always return empty.
       if (started_writes == 0) {
-        EXPECT_EQ(latest_queue_index_uint32_t,
+        EXPECT_EQ(latest_queue_index_queue_index,
                   LocklessQueue::empty_queue_index());
         EXPECT_EQ(finished_writes, 0);
       } else {
         if (finished_writes == 0) {
           // Plausible to be at the beginning.
-          if (latest_queue_index_uint32_t !=
+          if (latest_queue_index_queue_index !=
               LocklessQueue::empty_queue_index()) {
             // Otherwise, we have started.  The queue is always allowed to
             EXPECT_GE(started_writes, latest_queue_index + 1);
           }
         } else {
-          EXPECT_NE(latest_queue_index_uint32_t,
+          EXPECT_NE(latest_queue_index_queue_index,
                     LocklessQueue::empty_queue_index());
           // latest_queue_index is an index, not a count.  So it always reads 1
           // low.
diff --git a/aos/ipc_lib/queue_racer.h b/aos/ipc_lib/queue_racer.h
index 59435b1..eaeedd4 100644
--- a/aos/ipc_lib/queue_racer.h
+++ b/aos/ipc_lib/queue_racer.h
@@ -36,7 +36,7 @@
 
   size_t CurrentIndex() {
     LocklessQueue queue(memory_, config_);
-    return queue.LatestQueueIndex();
+    return queue.LatestQueueIndex().index();
   }
 
  private:
diff --git a/aos/ipc_lib/raw_queue_test.cc b/aos/ipc_lib/raw_queue_test.cc
index aa3b335..3048e1b 100644
--- a/aos/ipc_lib/raw_queue_test.cc
+++ b/aos/ipc_lib/raw_queue_test.cc
@@ -191,7 +191,8 @@
       case 0:  // child
         if (kForkSleep != chrono::milliseconds(0)) {
           AOS_LOG(INFO, "pid %jd sleeping for %" PRId64 "ns\n",
-                  static_cast<intmax_t>(getpid()), kForkSleep.count());
+                  static_cast<intmax_t>(getpid()),
+                  static_cast<int64_t>(kForkSleep.count()));
           this_thread::sleep_for(kForkSleep);
         }
         ::aos::testing::PreventExit();
diff --git a/aos/ipc_lib/shared_mem.c b/aos/ipc_lib/shared_mem.cc
similarity index 71%
rename from aos/ipc_lib/shared_mem.c
rename to aos/ipc_lib/shared_mem.cc
index da55ebc..93ced7d 100644
--- a/aos/ipc_lib/shared_mem.c
+++ b/aos/ipc_lib/shared_mem.cc
@@ -10,9 +10,9 @@
 #include <stdlib.h>
 #include <assert.h>
 
-#include "aos/ipc_lib/core_lib.h"
-#include "aos/logging/logging.h"
 #include "aos/ipc_lib/aos_sync.h"
+#include "aos/ipc_lib/core_lib.h"
+#include "glog/logging.h"
 
 // the path for the shared memory segment. see shm_open(3) for restrictions
 #define AOS_SHM_NAME "/aos_shared_mem"
@@ -61,7 +61,7 @@
       if (shm == -1 && errno == EEXIST) {
         printf("shared_mem: going to shm_unlink(%s)\n", global_core->shm_name);
         if (shm_unlink(global_core->shm_name) == -1) {
-          AOS_PLOG(WARNING, "shm_unlink(%s) failed", global_core->shm_name);
+          PLOG(WARNING) << "shm_unlink(" << global_core->shm_name << ") failed";
           break;
         }
       } else {
@@ -73,22 +73,22 @@
     global_core->owner = 0;
   }
   if (shm == -1) {
-    AOS_PLOG(FATAL, "shm_open(%s, O_RDWR [| O_CREAT | O_EXCL, 0|0666) failed",
-             global_core->shm_name);
+    PLOG(FATAL) << "shm_open(" << global_core->shm_name
+                << ", O_RDWR [| O_CREAT | O_EXCL, 0|0666) failed";
   }
   if (global_core->owner) {
-    if (ftruncate(shm, SIZEOFSHMSEG) == -1) {
-      AOS_PLOG(FATAL, "fruncate(%d, 0x%zx) failed", shm, (size_t)SIZEOFSHMSEG);
-    }
+    PCHECK(ftruncate(shm, SIZEOFSHMSEG) == 0)
+        << ": fruncate(" << shm << ", 0x" << std::hex << (size_t)SIZEOFSHMSEG
+        << ") failed";
   }
   int flags = MAP_SHARED | MAP_FIXED;
   if (lock) flags |= MAP_LOCKED | MAP_POPULATE;
   void *shm_address = mmap((void *)SHM_START, SIZEOFSHMSEG,
                            PROT_READ | PROT_WRITE, flags, shm, 0);
-  if (shm_address == MAP_FAILED) {
-    AOS_PLOG(FATAL, "shared_mem: mmap(%p, 0x%zx, stuff, %x, %d, 0) failed",
-             (void *)SHM_START, (size_t)SIZEOFSHMSEG, flags, shm);
-  }
+  PCHECK(shm_address != MAP_FAILED)
+      << std::hex << "shared_mem: mmap(" << (void *)SHM_START << ", 0x"
+      << (size_t)SIZEOFSHMSEG << ", stuff, " << flags << ", " << shm
+      << ", 0) failed";
   if (create) {
     printf("shared_mem: creating %s, shm at: %p\n", global_core->shm_name,
            shm_address);
@@ -96,19 +96,18 @@
     printf("shared_mem: not creating, shm at: %p\n", shm_address);
   }
   if (close(shm) == -1) {
-    AOS_PLOG(WARNING, "close(%d(=shm) failed", shm);
+    PLOG(WARNING) << "close(" << shm << "(=shm) failed";
   }
-  if (shm_address != (void *)SHM_START) {
-    AOS_LOG(FATAL, "shm isn't at hard-coded %p. at %p instead\n",
-            (void *)SHM_START, shm_address);
-  }
+  PCHECK(shm_address == (void *)SHM_START)
+      << "shm isn't at hard-coded " << (void *)SHM_START << ". at "
+      << shm_address << " instead";
   aos_core_use_address_as_shared_mem(shm_address, SIZEOFSHMSEG);
-  AOS_LOG(INFO, "shared_mem: end of create_shared_mem owner=%d\n",
-          global_core->owner);
+  LOG(INFO) << "shared_mem: end of create_shared_mem owner="
+            << global_core->owner;
 }
 
 void aos_core_use_address_as_shared_mem(void *address, size_t size) {
-  global_core->mem_struct = address;
+  global_core->mem_struct = reinterpret_cast<aos_shm_core_t *>(address);
   global_core->size = size;
   global_core->shared_mem =
       (uint8_t *)address + sizeof(*global_core->mem_struct);
@@ -118,22 +117,19 @@
     futex_set(&global_core->mem_struct->creation_condition);
   } else {
     if (futex_wait(&global_core->mem_struct->creation_condition) != 0) {
-      AOS_LOG(FATAL, "waiting on creation_condition failed\n");
+      LOG(FATAL) << "waiting on creation_condition failed";
     }
   }
 }
 
 void aos_core_free_shared_mem() {
   void *shm_address = global_core->shared_mem;
-  if (munmap((void *)SHM_START, SIZEOFSHMSEG) == -1) {
-    AOS_PLOG(FATAL, "munmap(%p, 0x%zx) failed", shm_address,
-             (size_t)SIZEOFSHMSEG);
-  }
+  PCHECK(munmap((void *)SHM_START, SIZEOFSHMSEG) != -1)
+      << ": munmap(" << shm_address << ", 0x" << std::hex
+      << (size_t)SIZEOFSHMSEG << ") failed";
   if (global_core->owner) {
-    if (shm_unlink(global_core->shm_name)) {
-      AOS_PLOG(FATAL, "shared_mem: shm_unlink(%s) failed",
-               global_core->shm_name);
-    }
+    PCHECK(shm_unlink(global_core->shm_name) == 0)
+        << ": shared_mem: shm_unlink(" << global_core->shm_name << ") failed";
   }
 }
 
diff --git a/aos/ipc_lib/signalfd.cc b/aos/ipc_lib/signalfd.cc
index 045444b..af95598 100644
--- a/aos/ipc_lib/signalfd.cc
+++ b/aos/ipc_lib/signalfd.cc
@@ -5,12 +5,12 @@
 #include <unistd.h>
 #include <initializer_list>
 
-#include "aos/logging/logging.h"
+#include "glog/logging.h"
 
 namespace aos {
 namespace ipc_lib {
 
-SignalFd::SignalFd(::std::initializer_list<int> signals) {
+SignalFd::SignalFd(::std::initializer_list<unsigned int> signals) {
   // Build up the mask with the provided signals.
   sigemptyset(&mask_);
   for (int signal : signals) {
@@ -18,7 +18,7 @@
   }
   // Then build a signalfd.  Make it nonblocking so it works well with an epoll
   // loop, and have it close on exec.
-  AOS_PCHECK(fd_ = signalfd(-1, &mask_, SFD_NONBLOCK | SFD_CLOEXEC));
+  PCHECK((fd_ = signalfd(-1, &mask_, SFD_NONBLOCK | SFD_CLOEXEC)) != 0);
   // Now that we have a consumer of the signal, block the signals so the
   // signalfd gets them.
   pthread_sigmask(SIG_BLOCK, &mask_, nullptr);
@@ -27,7 +27,7 @@
 SignalFd::~SignalFd() {
   // Unwind the constructor.  Unblock the signals and close the fd.
   pthread_sigmask(SIG_UNBLOCK, &mask_, nullptr);
-  AOS_PCHECK(close(fd_));
+  PCHECK(close(fd_) == 0);
 }
 
 signalfd_siginfo SignalFd::Read() {
diff --git a/aos/ipc_lib/signalfd.h b/aos/ipc_lib/signalfd.h
index a545a80..7d2021a 100644
--- a/aos/ipc_lib/signalfd.h
+++ b/aos/ipc_lib/signalfd.h
@@ -13,7 +13,7 @@
  public:
   // Constructs a SignalFd for the provided list of signals.
   // Blocks the signals at the same time in this thread.
-  SignalFd(::std::initializer_list<int> signals);
+  SignalFd(::std::initializer_list<unsigned int> signals);
 
   SignalFd(const SignalFd &) = delete;
   SignalFd &operator=(const SignalFd &) = delete;
diff --git a/aos/json_to_flatbuffer.cc b/aos/json_to_flatbuffer.cc
index 13a3a38..34cdffe 100644
--- a/aos/json_to_flatbuffer.cc
+++ b/aos/json_to_flatbuffer.cc
@@ -152,7 +152,7 @@
                const absl::string_view data, flatbuffers::uoffset_t *table_end);
 
   // Adds *_value for the provided field.  If we are in a vector, queues the
-  // data up in vector_elements_.  Returns true on success.
+  // data up in vector_elements.  Returns true on success.
   bool AddElement(int field_index, int64_t int_value);
   bool AddElement(int field_index, double double_value);
   bool AddElement(int field_index, const ::std::string &data);
@@ -184,19 +184,19 @@
 
     // Field elements that need to be inserted.
     ::std::vector<FieldElement> elements;
+
+    // For scalar types (not strings, and not nested tables), the vector ends
+    // up being implemented as a start and end, and a block of data.  So we
+    // can't just push offsets in as we go.  We either need to reproduce the
+    // logic inside flatbuffers, or build up vectors of the data.  Vectors will
+    // be a bit of extra stack space, but whatever.
+    //
+    // Strings and nested structures are vectors of offsets.
+    // into the vector. Once you get to the end, you build up a vector and
+    // push that into the field.
+    ::std::vector<Element> vector_elements;
   };
   ::std::vector<FlatBufferContext> stack_;
-
-  // For scalar types (not strings, and not nested tables), the vector ends
-  // up being implemented as a start and end, and a block of data.  So we
-  // can't just push offsets in as we go.  We either need to reproduce the
-  // logic inside flatbuffers, or build up vectors of the data.  Vectors will
-  // be a bit of extra stack space, but whatever.
-  //
-  // Strings and nested structures are vectors of offsets.
-  // into the vector. Once you get to the end, you build up a vector and
-  // push that into the field.
-  ::std::vector<Element> vector_elements_;
 };
 
 bool JsonParser::DoParse(const flatbuffers::TypeTable *typetable,
@@ -225,7 +225,7 @@
 
       case Tokenizer::TokenType::kStartObject:  // {
         if (stack_.size() == 0) {
-          stack_.push_back({typetable, false, -1, "", {}});
+          stack_.push_back({typetable, false, -1, "", {}, {}});
         } else {
           int field_index = stack_.back().field_index;
 
@@ -241,7 +241,7 @@
           flatbuffers::TypeFunction type_function =
               stack_.back().typetable->type_refs[type_code.sequence_ref];
 
-          stack_.push_back({type_function(), false, -1, "", {}});
+          stack_.push_back({type_function(), false, -1, "", {}, {}});
         }
         break;
       case Tokenizer::TokenType::kEndObject:  // }
@@ -267,7 +267,7 @@
 
             // Do the right thing if we are in a vector.
             if (in_vector()) {
-              vector_elements_.emplace_back(
+              stack_.back().vector_elements.emplace_back(
                   flatbuffers::Offset<flatbuffers::String>(end));
             } else {
               stack_.back().elements.emplace_back(
@@ -363,7 +363,7 @@
   }
 
   if (in_vector()) {
-    vector_elements_.emplace_back(int_value);
+    stack_.back().vector_elements.emplace_back(int_value);
   } else {
     stack_.back().elements.emplace_back(field_index, int_value);
   }
@@ -380,7 +380,7 @@
   }
 
   if (in_vector()) {
-    vector_elements_.emplace_back(double_value);
+    stack_.back().vector_elements.emplace_back(double_value);
   } else {
     stack_.back().elements.emplace_back(field_index, double_value);
   }
@@ -396,9 +396,61 @@
     return false;
   }
 
-  if (in_vector()) {
-    vector_elements_.emplace_back(fbb_.CreateString(data));
+  const flatbuffers::ElementaryType elementary_type =
+      static_cast<flatbuffers::ElementaryType>(type_code.base_type);
+  switch (elementary_type) {
+    case flatbuffers::ET_CHAR:
+    case flatbuffers::ET_UCHAR:
+    case flatbuffers::ET_SHORT:
+    case flatbuffers::ET_USHORT:
+    case flatbuffers::ET_INT:
+    case flatbuffers::ET_UINT:
+    case flatbuffers::ET_LONG:
+    case flatbuffers::ET_ULONG:
+      if (type_code.sequence_ref != -1) {
+        // We have an enum.
+        const flatbuffers::TypeTable *type_table = stack_.back().typetable;
+        flatbuffers::TypeFunction type_function =
+            type_table->type_refs[type_code.sequence_ref];
 
+        const flatbuffers::TypeTable *enum_type_table = type_function();
+
+        CHECK_EQ(enum_type_table->st, flatbuffers::ST_ENUM);
+
+        int64_t int_value = 0;
+        bool found = false;
+        for (size_t i = 0; i < enum_type_table->num_elems; ++i) {
+          if (data == enum_type_table->names[i]) {
+            int_value = i;
+            found = true;
+            break;
+          }
+        }
+
+        if (!found) {
+          printf("Enum value '%s' not found for field '%s'\n", data.c_str(),
+                 type_table->names[field_index]);
+          return false;
+        }
+
+        if (in_vector()) {
+          stack_.back().vector_elements.emplace_back(int_value);
+        } else {
+          stack_.back().elements.emplace_back(field_index, int_value);
+        }
+        return true;
+      }
+    case flatbuffers::ET_UTYPE:
+    case flatbuffers::ET_BOOL:
+    case flatbuffers::ET_FLOAT:
+    case flatbuffers::ET_DOUBLE:
+    case flatbuffers::ET_STRING:
+    case flatbuffers::ET_SEQUENCE:
+      break;
+  }
+
+  if (in_vector()) {
+    stack_.back().vector_elements.emplace_back(fbb_.CreateString(data));
   } else {
     stack_.back().elements.emplace_back(field_index, fbb_.CreateString(data));
   }
@@ -540,8 +592,6 @@
   const flatbuffers::ElementaryType elementary_type =
       static_cast<flatbuffers::ElementaryType>(type_code.base_type);
   switch (elementary_type) {
-    case flatbuffers::ET_UTYPE:
-    case flatbuffers::ET_BOOL:
     case flatbuffers::ET_CHAR:
     case flatbuffers::ET_UCHAR:
     case flatbuffers::ET_SHORT:
@@ -550,14 +600,20 @@
     case flatbuffers::ET_UINT:
     case flatbuffers::ET_LONG:
     case flatbuffers::ET_ULONG:
+    case flatbuffers::ET_UTYPE:
+    case flatbuffers::ET_BOOL:
     case flatbuffers::ET_FLOAT:
     case flatbuffers::ET_DOUBLE:
       printf("Mismatched type for field '%s'. Got: string, expected %s\n",
              typetable->names[field_index],
              ElementaryTypeName(elementary_type));
+      CHECK_EQ(type_code.sequence_ref, -1)
+          << ": Field name " << typetable->names[field_index]
+          << " Got string expected " << ElementaryTypeName(elementary_type);
       return false;
-    case flatbuffers::ET_SEQUENCE:
     case flatbuffers::ET_STRING:
+      CHECK_EQ(type_code.sequence_ref, -1);
+    case flatbuffers::ET_SEQUENCE:
       fbb->AddOffset(field_offset, offset_element);
       return true;
   }
@@ -573,17 +629,19 @@
 
   // Vectors have a start (unfortunately which needs to know the size)
   fbb_.StartVector(
-      vector_elements_.size(),
+      stack_.back().vector_elements.size(),
       flatbuffers::InlineSize(elementary_type, stack_.back().typetable));
 
   // Then the data (in reverse order for some reason...)
-  for (size_t i = vector_elements_.size(); i > 0;) {
-    const Element &element = vector_elements_[--i];
+  for (size_t i = stack_.back().vector_elements.size(); i > 0;) {
+    const Element &element = stack_.back().vector_elements[--i];
     switch (element.type) {
       case Element::ElementType::INT:
         if (!PushElement(elementary_type, element.int_element)) return false;
         break;
       case Element::ElementType::DOUBLE:
+        CHECK_EQ(type_code.sequence_ref, -1)
+            << ": Field index is " << field_index;
         if (!PushElement(elementary_type, element.double_element)) return false;
         break;
       case Element::ElementType::OFFSET:
@@ -595,8 +653,8 @@
   // Then an End which is placed into the buffer the same as any other offset.
   stack_.back().elements.emplace_back(
       field_index, flatbuffers::Offset<flatbuffers::String>(
-                       fbb_.EndVector(vector_elements_.size())));
-  vector_elements_.clear();
+                       fbb_.EndVector(stack_.back().vector_elements.size())));
+  stack_.back().vector_elements.clear();
   return true;
 }
 
diff --git a/aos/json_to_flatbuffer.fbs b/aos/json_to_flatbuffer.fbs
index 2e90a53..8942cc8 100644
--- a/aos/json_to_flatbuffer.fbs
+++ b/aos/json_to_flatbuffer.fbs
@@ -1,5 +1,26 @@
 namespace aos.testing;
 
+enum BaseType : byte {
+    None,
+    UType,
+    Bool,
+    Byte,
+    UByte,
+    Short,
+    UShort,
+    Int,
+    UInt,
+    Long,
+    ULong,
+    Float,
+    Double,
+    String,
+    Vector,
+    Obj,     // Used for tables & structs.
+    Union,
+    Array
+}
+
 table Location {
   name:string;
   type:string;
@@ -18,6 +39,14 @@
   maps:[Map];
 }
 
+table VectorOfStrings {
+  str:[string];
+}
+
+table VectorOfVectorOfString {
+  v:[VectorOfStrings];
+}
+
 table Configuration {
   locations:[Location] (id: 0);
   maps:[Map] (id: 1);
@@ -48,32 +77,37 @@
 
   foo_string:string (id: 15);
 
+  foo_enum:BaseType (id: 16);
+  foo_enum_default:BaseType = None (id: 17);
+
   // Test vectors now.
-  vector_foo_byte:[byte] (id: 16);
-  vector_foo_ubyte:[ubyte] (id: 17);
-  vector_foo_bool:[bool] (id: 18);
+  vector_foo_byte:[byte] (id: 18);
+  vector_foo_ubyte:[ubyte] (id: 19);
+  vector_foo_bool:[bool] (id: 20);
 
-  vector_foo_short:[short] (id: 19);
-  vector_foo_ushort:[ushort] (id: 20);
+  vector_foo_short:[short] (id: 21);
+  vector_foo_ushort:[ushort] (id: 22);
 
-  vector_foo_int:[int] (id: 21);
-  vector_foo_uint:[uint] (id: 22);
+  vector_foo_int:[int] (id: 23);
+  vector_foo_uint:[uint] (id: 24);
 
-  vector_foo_long:[long] (id: 23);
-  vector_foo_ulong:[ulong] (id: 24);
+  vector_foo_long:[long] (id: 25);
+  vector_foo_ulong:[ulong] (id: 26);
 
-  vector_foo_float:[float] (id: 25);
-  vector_foo_double:[double] (id: 26);
+  vector_foo_float:[float] (id: 27);
+  vector_foo_double:[double] (id: 28);
 
-  vector_foo_string:[string] (id: 27);
+  vector_foo_string:[string] (id: 29);
+
+  vector_foo_enum:[BaseType] (id: 30);
 
   // And a simple nested application.
-  single_application:Application (id: 28);
-
-  // TODO(austin): enum
+  single_application:Application (id: 31);
 
   // And nest this object to get some crazy coverage.
-  nested_config:Configuration (id: 29);
+  nested_config:Configuration (id: 32);
+
+  vov:VectorOfVectorOfString (id: 33);
 }
 
 root_type Configuration;
diff --git a/aos/json_to_flatbuffer_test.cc b/aos/json_to_flatbuffer_test.cc
index a048e0a..84ac0ed 100644
--- a/aos/json_to_flatbuffer_test.cc
+++ b/aos/json_to_flatbuffer_test.cc
@@ -57,6 +57,12 @@
   EXPECT_TRUE(JsonAndBack("{ \"foo_float\": 5.0 }"));
   EXPECT_TRUE(JsonAndBack("{ \"foo_double\": 5.0 }"));
 
+  EXPECT_TRUE(JsonAndBack("{ \"foo_enum\": \"None\" }"));
+  EXPECT_TRUE(JsonAndBack("{ \"foo_enum\": \"UType\" }"));
+
+  EXPECT_TRUE(JsonAndBack("{ \"foo_enum_default\": \"None\" }"));
+  EXPECT_TRUE(JsonAndBack("{ \"foo_enum_default\": \"UType\" }"));
+
   EXPECT_TRUE(JsonAndBack("{ \"foo_string\": \"baz\" }"));
 }
 
@@ -72,6 +78,13 @@
   EXPECT_FALSE(JsonAndBack("{ \"foo\": 5 }"));
 }
 
+// Tests that an invalid enum type is handled correctly.
+TEST_F(JsonToFlatbufferTest, InvalidEnumName) {
+  EXPECT_FALSE(JsonAndBack("{ \"foo_enum\": \"5ype\" }"));
+
+  EXPECT_FALSE(JsonAndBack("{ \"foo_enum_default\": \"7ype\" }"));
+}
+
 // Test that adding a duplicate field results in an error.
 TEST_F(JsonToFlatbufferTest, DuplicateField) {
   EXPECT_FALSE(
@@ -106,19 +119,29 @@
 // Test arrays of simple types.
 TEST_F(JsonToFlatbufferTest, Array) {
   EXPECT_TRUE(JsonAndBack("{ \"vector_foo_byte\": [ 9, 7, 1 ] }"));
+  EXPECT_TRUE(JsonAndBack("{ \"vector_foo_byte\": [  ] }"));
   EXPECT_TRUE(JsonAndBack("{ \"vector_foo_ubyte\": [ 9, 7, 1 ] }"));
+  EXPECT_TRUE(JsonAndBack("{ \"vector_foo_ubyte\": [  ] }"));
 
   EXPECT_TRUE(JsonAndBack("{ \"vector_foo_short\": [ 9, 7, 1 ] }"));
+  EXPECT_TRUE(JsonAndBack("{ \"vector_foo_short\": [  ] }"));
   EXPECT_TRUE(JsonAndBack("{ \"vector_foo_ushort\": [ 9, 7, 1 ] }"));
+  EXPECT_TRUE(JsonAndBack("{ \"vector_foo_ushort\": [  ] }"));
 
   EXPECT_TRUE(JsonAndBack("{ \"vector_foo_int\": [ 9, 7, 1 ] }"));
+  EXPECT_TRUE(JsonAndBack("{ \"vector_foo_int\": [  ] }"));
   EXPECT_TRUE(JsonAndBack("{ \"vector_foo_uint\": [ 9, 7, 1 ] }"));
+  EXPECT_TRUE(JsonAndBack("{ \"vector_foo_uint\": [  ] }"));
 
   EXPECT_TRUE(JsonAndBack("{ \"vector_foo_long\": [ 9, 7, 1 ] }"));
+  EXPECT_TRUE(JsonAndBack("{ \"vector_foo_long\": [  ] }"));
   EXPECT_TRUE(JsonAndBack("{ \"vector_foo_ulong\": [ 9, 7, 1 ] }"));
+  EXPECT_TRUE(JsonAndBack("{ \"vector_foo_ulong\": [  ] }"));
 
   EXPECT_TRUE(JsonAndBack("{ \"vector_foo_float\": [ 9.0, 7.0, 1.0 ] }"));
+  EXPECT_TRUE(JsonAndBack("{ \"vector_foo_float\": [  ] }"));
   EXPECT_TRUE(JsonAndBack("{ \"vector_foo_double\": [ 9.0, 7.0, 1.0 ] }"));
+  EXPECT_TRUE(JsonAndBack("{ \"vector_foo_double\": [  ] }"));
 
   EXPECT_TRUE(JsonAndBack("{ \"vector_foo_float\": [ 9, 7, 1 ] }",
                           "{ \"vector_foo_float\": [ 9.0, 7.0, 1.0 ] }"));
@@ -126,6 +149,9 @@
                           "{ \"vector_foo_double\": [ 9.0, 7.0, 1.0 ] }"));
 
   EXPECT_TRUE(JsonAndBack("{ \"vector_foo_string\": [ \"bar\", \"baz\" ] }"));
+  EXPECT_TRUE(JsonAndBack("{ \"vector_foo_string\": [  ] }"));
+  EXPECT_TRUE(JsonAndBack("{ \"vector_foo_enum\": [ \"None\", \"UType\", \"Bool\" ] }"));
+  EXPECT_TRUE(JsonAndBack("{ \"vector_foo_enum\": [  ] }"));
 }
 
 // Test nested messages, and arrays of nested messages.
@@ -133,8 +159,13 @@
   EXPECT_TRUE(
       JsonAndBack("{ \"single_application\": { \"name\": \"woot\" } }"));
 
+  EXPECT_TRUE(JsonAndBack("{ \"single_application\": {  } }"));
+
   EXPECT_TRUE(JsonAndBack(
       "{ \"apps\": [ { \"name\": \"woot\" }, { \"name\": \"wow\" } ] }"));
+
+  EXPECT_TRUE(JsonAndBack(
+      "{ \"apps\": [ {  }, {  } ] }"));
 }
 
 // Test that we can parse an empty message.
@@ -158,8 +189,13 @@
                   "\"vector_foo_double\": [ 9.0, 7.0, 1.0 ] }"));
 }
 
+// Tests that multiple arrays get properly handled.
+TEST_F(JsonToFlatbufferTest, NestedArrays) {
+  EXPECT_TRUE(
+      JsonAndBack("{ \"vov\": { \"v\": [ { \"str\": [ \"a\", \"b\" ] }, { \"str\": [ \"c\", \"d\" ] } ] } }"));
+}
+
 // TODO(austin): Missmatched values.
-// TODO(austin): enums
 //
 // TODO(austin): unions?
 
diff --git a/aos/json_tokenizer.cc b/aos/json_tokenizer.cc
index 78bf46e..e3aa7ea 100644
--- a/aos/json_tokenizer.cc
+++ b/aos/json_tokenizer.cc
@@ -1,5 +1,7 @@
 #include "aos/json_tokenizer.h"
 
+#include <cerrno>
+
 namespace aos {
 
 void Tokenizer::ConsumeWhitespace() {
@@ -267,7 +269,13 @@
 
         ConsumeWhitespace();
 
-        state_ = State::kExpectField;
+        // And then if we encounter the end again, go to the end state.
+        if (Consume("}")) {
+          ConsumeWhitespace();
+          state_ = State::kExpectObjectEnd;
+        } else {
+          state_ = State::kExpectField;
+        }
         return TokenType::kStartObject;
       } else if (Consume("[")) {
         // Values are in arrays.  Record and recurse.
@@ -293,6 +301,22 @@
         field_value_ = "false";
         result = TokenType::kFalseValue;
       } else {
+        switch (object_type_.back()) {
+          case ObjectType::kObject:
+            if (Consume("}")) {
+              ConsumeWhitespace();
+              state_ = State::kExpectObjectEnd;
+              return Next();
+            }
+            break;
+          case ObjectType::kArray:
+            if (Consume("]")) {
+              ConsumeWhitespace();
+              state_ = State::kExpectArrayEnd;
+              return Next();
+            }
+            break;
+        }
         // Couldn't parse, so we have a syntax error.
         fprintf(stderr, "Error line %d, invalid field value.\n", linenumber_);
       }
diff --git a/aos/libc/BUILD b/aos/libc/BUILD
index 48a9ffd..234c29a 100644
--- a/aos/libc/BUILD
+++ b/aos/libc/BUILD
@@ -9,7 +9,7 @@
         "aos_strsignal.h",
     ],
     deps = [
-        "//aos/logging",
+        "@com_github_google_glog//:glog",
     ],
 )
 
@@ -20,7 +20,6 @@
     ],
     deps = [
         ":aos_strsignal",
-        "//aos/logging",
         "//aos/testing:googletest",
     ],
 )
diff --git a/aos/libc/aos_strsignal.cc b/aos/libc/aos_strsignal.cc
index a3331f9..9262ac6 100644
--- a/aos/libc/aos_strsignal.cc
+++ b/aos/libc/aos_strsignal.cc
@@ -2,14 +2,15 @@
 
 #include <signal.h>
 
-#include "aos/logging/logging.h"
+#include "glog/logging.h"
 
 const char *aos_strsignal(int signal) {
   static thread_local char buffer[512];
 
   if (signal >= SIGRTMIN && signal <= SIGRTMAX) {
-    AOS_CHECK(snprintf(buffer, sizeof(buffer), "Real-time signal %d",
-                       signal - SIGRTMIN) > 0);
+    CHECK_GT(snprintf(buffer, sizeof(buffer), "Real-time signal %d",
+                      signal - SIGRTMIN),
+             0);
     return buffer;
   }
 
@@ -17,6 +18,6 @@
     return sys_siglist[signal];
   }
 
-  AOS_CHECK(snprintf(buffer, sizeof(buffer), "Unknown signal %d", signal) > 0);
+  CHECK_GT(snprintf(buffer, sizeof(buffer), "Unknown signal %d", signal), 0);
   return buffer;
 }
diff --git a/aos/logging/BUILD b/aos/logging/BUILD
index 60c561b..6157e52 100644
--- a/aos/logging/BUILD
+++ b/aos/logging/BUILD
@@ -20,25 +20,6 @@
     ],
 )
 
-cc_library(
-    name = "replay",
-    srcs = [
-        "replay.cc",
-    ],
-    hdrs = [
-        "replay.h",
-    ],
-    visibility = ["//visibility:public"],
-    deps = [
-        ":binary_log_file",
-        ":logging",
-        ":queue_logging",
-        "//aos:queues",
-        "//aos/events:event-loop",
-        "//aos/ipc_lib:queue",
-    ],
-)
-
 cc_binary(
     name = "binary_log_writer",
     srcs = [
@@ -52,7 +33,6 @@
         "//aos:configuration",
         "//aos:die",
         "//aos:init",
-        "//aos:queue_types",
         "//aos/ipc_lib:queue",
         "//aos/time",
     ],
@@ -85,7 +65,6 @@
         ":logging",
         "//aos:configuration",
         "//aos:init",
-        "//aos:queue_types",
         "//aos/util:string_to_num",
     ],
 )
@@ -123,42 +102,6 @@
 )
 
 cc_library(
-    name = "queue_logging",
-    srcs = [
-        "queue_logging.cc",
-    ],
-    hdrs = [
-        "queue_logging.h",
-    ],
-    visibility = ["//visibility:public"],
-    deps = [
-        ":logging",
-        ":sizes",
-        "//aos:die",
-        "//aos:queue_types",
-    ],
-)
-
-cc_library(
-    name = "matrix_logging",
-    srcs = [
-        "matrix_logging.cc",
-    ],
-    hdrs = [
-        "matrix_logging.h",
-    ],
-    visibility = ["//visibility:public"],
-    deps = [
-        ":logging",
-        ":sizes",
-        "//aos:die",
-        "//aos:generated_queue_headers",
-        "//aos:queue_types",
-        "//third_party/eigen",
-    ],
-)
-
-cc_library(
     name = "printf_formats",
     hdrs = [
         "printf_formats.h",
@@ -183,11 +126,11 @@
     visibility = ["//visibility:public"],
     deps = [
         ":logging",
+        ":printf_formats",
         ":sizes",
         "//aos:die",
         "//aos:macros",
         "//aos:once",
-        "//aos:queue_types",
         "//aos/ipc_lib:queue",
         "//aos/mutex",
         "//aos/time",
diff --git a/aos/logging/binary_log_writer.cc b/aos/logging/binary_log_writer.cc
index be19d45..5b1dc38 100644
--- a/aos/logging/binary_log_writer.cc
+++ b/aos/logging/binary_log_writer.cc
@@ -18,7 +18,6 @@
 #include "aos/die.h"
 #include "aos/logging/binary_log_file.h"
 #include "aos/logging/implementations.h"
-#include "aos/queue_types.h"
 #include "aos/time/time.h"
 #include "aos/configuration.h"
 #include "aos/init.h"
@@ -29,41 +28,6 @@
 namespace linux_code {
 namespace {
 
-void CheckTypeWritten(uint32_t type_id, LogFileWriter *writer,
-                      ::std::unordered_set<uint32_t> *written_type_ids) {
-  if (written_type_ids->count(type_id) > 0) return;
-  if (MessageType::IsPrimitive(type_id)) return;
-
-  const MessageType &type = type_cache::Get(type_id);
-  for (int i = 0; i < type.number_fields; ++i) {
-    CheckTypeWritten(type.fields[i]->type, writer, written_type_ids);
-  }
-
-  char buffer[1024];
-  ssize_t size = type.Serialize(buffer, sizeof(buffer));
-  if (size == -1) {
-    AOS_LOG(WARNING, "%zu-byte buffer is too small to serialize type %s\n",
-            sizeof(buffer), type.name.c_str());
-    return;
-  }
-  LogFileMessageHeader *const output =
-      writer->GetWritePosition(sizeof(LogFileMessageHeader) + size);
-
-  output->time_sec = output->time_nsec = 0;
-  output->source = getpid();
-  output->name_size = 0;
-  output->sequence = 0;
-  output->level = FATAL;
-
-  memcpy(output + 1, buffer, size);
-  output->message_size = size;
-
-  output->type = LogFileMessageHeader::MessageType::kStructType;
-  futex_set(&output->marker);
-
-  written_type_ids->insert(type_id);
-}
-
 void AllocateLogName(char **filename, const char *directory) {
   int fileindex = 0;
   DIR *const d = opendir(directory);
@@ -205,7 +169,6 @@
   RawQueue *queue = GetLoggingQueue();
 
   ::std::unordered_set<uint32_t> written_type_ids;
-  off_t clear_type_ids_cookie = 0;
 
   while (true) {
     const LogMessage *const msg =
@@ -222,21 +185,6 @@
     const size_t raw_output_length =
         sizeof(LogFileMessageHeader) + msg->name_length + msg->message_length;
     size_t output_length = raw_output_length;
-    if (msg->type == LogMessage::Type::kStruct) {
-      output_length += sizeof(msg->structure.type_id) + sizeof(uint32_t) +
-                       msg->structure.string_length;
-      if (writer.ShouldClearSeekableData(&clear_type_ids_cookie,
-                                         output_length)) {
-        writer.ForceNewPage();
-        written_type_ids.clear();
-      }
-      CheckTypeWritten(msg->structure.type_id, &writer, &written_type_ids);
-    } else if (msg->type == LogMessage::Type::kMatrix) {
-      output_length +=
-          sizeof(msg->matrix.type) + sizeof(uint32_t) + sizeof(uint16_t) +
-          sizeof(uint16_t) + msg->matrix.string_length;
-      AOS_CHECK(MessageType::IsPrimitive(msg->matrix.type));
-    }
     LogFileMessageHeader *const output = writer.GetWritePosition(output_length);
     char *output_strings = reinterpret_cast<char *>(output) + sizeof(*output);
     output->name_size = msg->name_length;
@@ -254,50 +202,6 @@
                msg->message_length);
         output->type = LogFileMessageHeader::MessageType::kString;
         break;
-      case LogMessage::Type::kStruct: {
-        char *position = output_strings + msg->name_length;
-
-        memcpy(position, &msg->structure.type_id,
-               sizeof(msg->structure.type_id));
-        position += sizeof(msg->structure.type_id);
-        output->message_size += sizeof(msg->structure.type_id);
-
-        const uint32_t length = msg->structure.string_length;
-        memcpy(position, &length, sizeof(length));
-        position += sizeof(length);
-        memcpy(position, msg->structure.serialized,
-               length + msg->message_length);
-        position += length + msg->message_length;
-        output->message_size += sizeof(length) + length;
-
-        output->type = LogFileMessageHeader::MessageType::kStruct;
-      } break;
-      case LogMessage::Type::kMatrix: {
-        char *position = output_strings + msg->name_length;
-
-        memcpy(position, &msg->matrix.type, sizeof(msg->matrix.type));
-        position += sizeof(msg->matrix.type);
-        output->message_size += sizeof(msg->matrix.type);
-
-        uint32_t length = msg->matrix.string_length;
-        memcpy(position, &length, sizeof(length));
-        position += sizeof(length);
-        output->message_size += sizeof(length);
-
-        uint16_t rows = msg->matrix.rows, cols = msg->matrix.cols;
-        memcpy(position, &rows, sizeof(rows));
-        position += sizeof(rows);
-        memcpy(position, &cols, sizeof(cols));
-        position += sizeof(cols);
-        output->message_size += sizeof(rows) + sizeof(cols);
-        AOS_CHECK_EQ(msg->message_length,
-                     MessageType::Sizeof(msg->matrix.type) * rows * cols);
-
-        memcpy(position, msg->matrix.data, msg->message_length + length);
-        output->message_size += length;
-
-        output->type = LogFileMessageHeader::MessageType::kMatrix;
-      } break;
     }
 
     if (output->message_size - msg->message_length !=
diff --git a/aos/logging/context.cc b/aos/logging/context.cc
index 2fcb301..72c1970 100644
--- a/aos/logging/context.cc
+++ b/aos/logging/context.cc
@@ -1,5 +1,9 @@
 #include "aos/logging/context.h"
 
+#ifndef _GNU_SOURCE
+#define _GNU_SOURCE /* See feature_test_macros(7) */
+#endif
+
 #include <string.h>
 #include <sys/prctl.h>
 #include <sys/types.h>
@@ -7,6 +11,11 @@
 
 #include <string>
 
+#include <errno.h>
+
+extern char *program_invocation_name;
+extern char *program_invocation_short_name;
+
 #include "aos/die.h"
 #include "aos/complex_thread_local.h"
 
diff --git a/aos/logging/implementations.cc b/aos/logging/implementations.cc
index 632d90b..2220e4e 100644
--- a/aos/logging/implementations.cc
+++ b/aos/logging/implementations.cc
@@ -8,7 +8,6 @@
 
 #include "aos/die.h"
 #include "aos/logging/printf_formats.h"
-#include "aos/queue_types.h"
 #include "aos/time/time.h"
 #include "aos/ipc_lib/queue.h"
 #include "aos/once.h"
@@ -23,10 +22,15 @@
 // Some of the things specified in the LogImplementation documentation doesn't
 // apply here (mostly the parts about being able to use AOS_LOG) because this is
 // the root one.
-class RootLogImplementation : public SimpleLogImplementation {
+class RootLogImplementation : public LogImplementation {
  public:
   void have_other_implementation() { only_implementation_ = false; }
 
+ protected:
+  virtual ::aos::monotonic_clock::time_point monotonic_now() const {
+    return ::aos::monotonic_clock::now();
+  }
+
  private:
   void set_next(LogImplementation *) override {
     AOS_LOG(FATAL, "can't have a next logger from here\n");
@@ -101,66 +105,6 @@
 
 }  // namespace
 
-void FillInMessageStructure(bool add_to_type_cache, log_level level,
-                            monotonic_clock::time_point monotonic_now,
-                            const ::std::string &message_string, size_t size,
-                            const MessageType *type,
-                            const ::std::function<size_t(char *)> &serialize,
-                            LogMessage *message) {
-  if (add_to_type_cache) {
-    type_cache::AddShm(type->id);
-  }
-  message->structure.type_id = type->id;
-
-  FillInMessageBase(level, monotonic_now, message);
-
-  if (message_string.size() + size > sizeof(message->structure.serialized)) {
-    AOS_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(),
-         message->structure.string_length);
-
-  message->message_length = serialize(
-      &message->structure.serialized[message->structure.string_length]);
-  message->type = LogMessage::Type::kStruct;
-}
-
-void FillInMessageMatrix(log_level level,
-                         monotonic_clock::time_point monotonic_now,
-                         const ::std::string &message_string, uint32_t type_id,
-                         int rows, int cols, const void *data,
-                         LogMessage *message) {
-  AOS_CHECK(MessageType::IsPrimitive(type_id));
-  message->matrix.type = type_id;
-
-  const auto element_size = MessageType::Sizeof(type_id);
-
-  FillInMessageBase(level, monotonic_now, message);
-
-  message->message_length = rows * cols * element_size;
-  if (message_string.size() + message->message_length >
-      sizeof(message->matrix.data)) {
-    AOS_LOG(FATAL,
-            "%dx%d matrix of type %" PRIu32
-            " (size %u) and message %s is too big\n",
-            rows, cols, type_id, element_size, message_string.c_str());
-  }
-  message->matrix.string_length = message_string.size();
-  memcpy(message->matrix.data, message_string.data(),
-         message->matrix.string_length);
-
-  message->matrix.rows = rows;
-  message->matrix.cols = cols;
-  SerializeMatrix(type_id, &message->matrix.data[message->matrix.string_length],
-                  data, rows, cols);
-  message->type = LogMessage::Type::kMatrix;
-}
-
 void FillInMessage(log_level level, monotonic_clock::time_point monotonic_now,
                    const char *format, va_list ap, LogMessage *message) {
   FillInMessageBase(level, monotonic_now, message);
@@ -180,105 +124,12 @@
       fprintf(output, AOS_LOGGING_BASE_FORMAT "%.*s", BASE_ARGS,
               static_cast<int>(message.message_length), message.message);
       break;
-    case LogMessage::Type::kStruct: {
-      char buffer[4096];
-      size_t output_length = sizeof(buffer);
-      size_t input_length = message.message_length;
-      if (!PrintMessage(
-              buffer, &output_length,
-              message.structure.serialized + message.structure.string_length,
-              &input_length, type_cache::Get(message.structure.type_id))) {
-        AOS_LOG(
-            FATAL,
-            "printing message (%.*s) of type %s into %zu-byte buffer failed\n",
-            static_cast<int>(message.message_length), message.message,
-            type_cache::Get(message.structure.type_id).name.c_str(),
-            sizeof(buffer));
-      }
-      if (input_length > 0) {
-        AOS_LOG(WARNING, "%zu extra bytes on message of type %s\n",
-                input_length,
-                type_cache::Get(message.structure.type_id).name.c_str());
-      }
-      fprintf(output, AOS_LOGGING_BASE_FORMAT "%.*s: %.*s\n", BASE_ARGS,
-              static_cast<int>(message.structure.string_length),
-              message.structure.serialized,
-              static_cast<int>(sizeof(buffer) - output_length), buffer);
-    } break;
-    case LogMessage::Type::kMatrix: {
-      char buffer[1024];
-      size_t output_length = sizeof(buffer);
-      if (message.message_length !=
-          static_cast<size_t>(message.matrix.rows * message.matrix.cols *
-                              MessageType::Sizeof(message.matrix.type))) {
-        AOS_LOG(FATAL, "expected %d bytes of matrix data but have %zu\n",
-                message.matrix.rows * message.matrix.cols *
-                    MessageType::Sizeof(message.matrix.type),
-                message.message_length);
-      }
-      if (!PrintMatrix(buffer, &output_length,
-                       message.matrix.data + message.matrix.string_length,
-                       message.matrix.type, message.matrix.rows,
-                       message.matrix.cols)) {
-        AOS_LOG(FATAL, "printing %dx%d matrix of type %" PRIu32 " failed\n",
-                message.matrix.rows, message.matrix.cols, message.matrix.type);
-      }
-      fprintf(output, AOS_LOGGING_BASE_FORMAT "%.*s: %.*s\n", BASE_ARGS,
-              static_cast<int>(message.matrix.string_length),
-              message.matrix.data,
-              static_cast<int>(sizeof(buffer) - output_length), buffer);
-    } break;
   }
 #undef BASE_ARGS
 }
 
 }  // namespace internal
 
-void SimpleLogImplementation::LogStruct(
-    log_level level, const ::std::string &message, size_t size,
-    const MessageType *type, const ::std::function<size_t(char *)> &serialize) {
-  char serialized[1024];
-  if (size > sizeof(serialized)) {
-    AOS_LOG(FATAL, "structure of type %s too big to serialize\n",
-            type->name.c_str());
-  }
-  size_t used = serialize(serialized);
-  char printed[1024];
-  size_t printed_bytes = sizeof(printed);
-  if (!PrintMessage(printed, &printed_bytes, serialized, &used, *type)) {
-    AOS_LOG(FATAL,
-            "PrintMessage(%p, %p(=%zd), %p, %p(=%zd), %p(name=%s)) failed\n",
-            printed, &printed_bytes, printed_bytes, serialized, &used, used,
-            type, type->name.c_str());
-  }
-  DoLogVariadic(level, "%.*s: %.*s\n", static_cast<int>(message.size()),
-                message.data(),
-                static_cast<int>(sizeof(printed) - printed_bytes), printed);
-}
-
-void SimpleLogImplementation::LogMatrix(
-    log_level level, const ::std::string &message, uint32_t type_id,
-    int rows, int cols, const void *data) {
-  char serialized[1024];
-  if (static_cast<size_t>(rows * cols * MessageType::Sizeof(type_id)) >
-      sizeof(serialized)) {
-    AOS_LOG(FATAL, "matrix of size %u too big to serialize\n",
-            rows * cols * MessageType::Sizeof(type_id));
-  }
-  SerializeMatrix(type_id, serialized, data, rows, cols);
-  char printed[1024];
-  size_t printed_bytes = sizeof(printed);
-  if (!PrintMatrix(printed, &printed_bytes, serialized, type_id, rows, cols)) {
-    AOS_LOG(FATAL,
-            "PrintMatrix(%p, %p(=%zd), %p, %" PRIu32 ", %d, %d) failed\n",
-            printed, &printed_bytes, printed_bytes, serialized, type_id, rows,
-            cols);
-  }
-  DoLogVariadic(level, "%.*s: %.*s\n", static_cast<int>(message.size()),
-                message.data(),
-                static_cast<int>(sizeof(printed) - printed_bytes), printed);
-}
-
 void HandleMessageLogImplementation::DoLog(log_level level, const char *format,
                                            va_list ap) {
   LogMessage message;
@@ -286,25 +137,6 @@
   HandleMessage(message);
 }
 
-void HandleMessageLogImplementation::LogStruct(
-    log_level level, const ::std::string &message_string, size_t size,
-    const MessageType *type, const ::std::function<size_t(char *)> &serialize) {
-  LogMessage message;
-  internal::FillInMessageStructure(fill_type_cache(), level, monotonic_now(),
-                                   message_string, size, type, serialize,
-                                   &message);
-  HandleMessage(message);
-}
-
-void HandleMessageLogImplementation::LogMatrix(
-    log_level level, const ::std::string &message_string, uint32_t type_id,
-    int rows, int cols, const void *data) {
-  LogMessage message;
-  internal::FillInMessageMatrix(level, monotonic_now(), message_string, type_id,
-                                rows, cols, data, &message);
-  HandleMessage(message);
-}
-
 StreamLogImplementation::StreamLogImplementation(FILE *stream)
     : stream_(stream) {}
 
@@ -415,25 +247,6 @@
     internal::FillInMessage(level, monotonic_now(), format, ap, message);
     Write(message);
   }
-
-  void LogStruct(log_level level, const ::std::string &message_string,
-                 size_t size, const MessageType *type,
-                 const ::std::function<size_t(char *)> &serialize) override {
-    LogMessage *message = GetMessageOrDie();
-    internal::FillInMessageStructure(fill_type_cache(), level, monotonic_now(),
-                                     message_string, size, type, serialize,
-                                     message);
-    Write(message);
-  }
-
-  void LogMatrix(log_level level, const ::std::string &message_string,
-                 uint32_t type_id, int rows, int cols,
-                 const void *data) override {
-    LogMessage *message = GetMessageOrDie();
-    internal::FillInMessageMatrix(level, monotonic_now(), message_string,
-                                  type_id, rows, cols, data, message);
-    Write(message);
-  }
 };
 
 }  // namespace
diff --git a/aos/logging/implementations.h b/aos/logging/implementations.h
index 5f7e1c5..27c0472 100644
--- a/aos/logging/implementations.h
+++ b/aos/logging/implementations.h
@@ -43,7 +43,7 @@
 // Contains all of the information about a given logging call.
 struct LogMessage {
   enum class Type : uint8_t {
-    kString, kStruct, kMatrix
+    kString
   };
 
   int32_t seconds, nseconds;
@@ -100,23 +100,6 @@
   return LOG_UNKNOWN;
 }
 
-// A LogImplementation where LogStruct and LogMatrix just create a string with
-// PrintMessage and then forward on to DoLog.
-class SimpleLogImplementation : public LogImplementation {
- protected:
-  virtual ::aos::monotonic_clock::time_point monotonic_now() const {
-    return ::aos::monotonic_clock::now();
-  }
-
- private:
-  void LogStruct(log_level level, const ::std::string &message, size_t size,
-                 const MessageType *type,
-                 const ::std::function<size_t(char *)> &serialize) override;
-  void LogMatrix(log_level level, const ::std::string &message,
-                 uint32_t type_id, int rows, int cols,
-                 const void *data) override;
-};
-
 // Implements all of the DoLog* methods in terms of a (pure virtual in this
 // class) HandleMessage method that takes a pointer to the message.
 class HandleMessageLogImplementation : public LogImplementation {
@@ -128,12 +111,6 @@
  private:
   __attribute__((format(GOOD_PRINTF_FORMAT_TYPE, 3, 0)))
   void DoLog(log_level level, const char *format, va_list ap) override;
-  void LogStruct(log_level level, const ::std::string &message_string,
-                 size_t size, const MessageType *type,
-                 const ::std::function<size_t(char *)> &serialize) override;
-  void LogMatrix(log_level level, const ::std::string &message_string,
-                 uint32_t type_id, int rows, int cols,
-                 const void *data) override;
 
   virtual void HandleMessage(const LogMessage &message) = 0;
 };
@@ -186,23 +163,6 @@
 // goes.
 namespace internal {
 
-// Fills in all the parts of message according to the given inputs (with type
-// kStruct).
-void FillInMessageStructure(bool add_to_type_cache, log_level level,
-                            ::aos::monotonic_clock::time_point monotonic_now,
-                            const ::std::string &message_string, size_t size,
-                            const MessageType *type,
-                            const ::std::function<size_t(char *)> &serialize,
-                            LogMessage *message);
-
-// Fills in all the parts of the message according to the given inputs (with
-// type kMatrix).
-void FillInMessageMatrix(log_level level,
-                         ::aos::monotonic_clock::time_point monotonic_now,
-                         const ::std::string &message_string, uint32_t type_id,
-                         int rows, int cols, const void *data,
-                         LogMessage *message);
-
 // Fills in *message according to the given inputs (with type kString).
 // Used for implementing LogImplementation::DoLog.
 void FillInMessage(log_level level,
diff --git a/aos/logging/implementations_test.cc b/aos/logging/implementations_test.cc
index 2accf35..d97e165 100644
--- a/aos/logging/implementations_test.cc
+++ b/aos/logging/implementations_test.cc
@@ -19,9 +19,13 @@
 
 namespace chrono = ::std::chrono;
 
-class TestLogImplementation : public SimpleLogImplementation {
-  __attribute__((format(GOOD_PRINTF_FORMAT_TYPE, 3, 0)))
-  void DoLog(log_level level, const char *format, va_list ap) override {
+class TestLogImplementation : public LogImplementation {
+  virtual ::aos::monotonic_clock::time_point monotonic_now() const {
+    return ::aos::monotonic_clock::now();
+  }
+
+  __attribute__((format(GOOD_PRINTF_FORMAT_TYPE, 3, 0))) void DoLog(
+      log_level level, const char *format, va_list ap) override {
     internal::FillInMessage(level, monotonic_now(), format, ap, &message_);
 
     if (level == FATAL) {
@@ -175,7 +179,8 @@
   monotonic_clock::time_point end = monotonic_clock::now();
   auto diff = end - start;
   printf("short message took %" PRId64 " nsec for %ld\n",
-         chrono::duration_cast<chrono::nanoseconds>(diff).count(),
+         static_cast<int64_t>(
+             chrono::duration_cast<chrono::nanoseconds>(diff).count()),
          kTimingCycles);
 
   start = monotonic_clock::now();
@@ -185,7 +190,8 @@
   end = monotonic_clock::now();
   diff = end - start;
   printf("long message took %" PRId64 " nsec for %ld\n",
-         chrono::duration_cast<chrono::nanoseconds>(diff).count(),
+         static_cast<int64_t>(
+             chrono::duration_cast<chrono::nanoseconds>(diff).count()),
          kTimingCycles);
 }
 
diff --git a/aos/logging/interface.cc b/aos/logging/interface.cc
index bcd8470..b72f8e1 100644
--- a/aos/logging/interface.cc
+++ b/aos/logging/interface.cc
@@ -19,7 +19,7 @@
   static const char *const continued = "...\n";
   const size_t size = output_size - strlen(continued);
   const int ret = vsnprintf(output, size, format, ap);
-  typedef ::std::common_type<typeof(ret), typeof(size)>::type RetType;
+  typedef ::std::common_type<int, size_t>::type RetType;
   if (ret < 0) {
     AOS_PLOG(FATAL, "vsnprintf(%p, %zd, %s, args) failed",
          output, size, format);
diff --git a/aos/logging/interface.h b/aos/logging/interface.h
index 50237fc..92f0b10 100644
--- a/aos/logging/interface.h
+++ b/aos/logging/interface.h
@@ -16,19 +16,6 @@
 struct MessageType;
 
 namespace logging {
-namespace internal {
-
-// Defined in queue_logging.cc.
-void DoLogStruct(log_level level, const ::std::string &message, size_t size,
-                 const MessageType *type,
-                 const ::std::function<size_t(char *)> &serialize, int levels);
-
-// Defined in matrix_logging.cc.
-void DoLogMatrix(log_level level, const ::std::string &message,
-                 uint32_t type_id, int rows, int cols, const void *data,
-                 int levels);
-
-}  // namespace internal
 
 // Takes a message and logs it. It will set everything up and then call DoLog
 // for the current LogImplementation.
@@ -75,20 +62,6 @@
     va_end(ap);
   }
 
-  // Logs the contents of an auto-generated structure.
-  // size and type are the result of calling Size() and Type() on the type of
-  // the message.
-  // serialize will call Serialize on the message.
-  virtual void LogStruct(log_level level, const ::std::string &message,
-                         size_t size, const MessageType *type,
-                         const ::std::function<size_t(char *)> &serialize) = 0;
-  // Similiar to LogStruct, except for matrixes.
-  // type_id is the type of the elements of the matrix.
-  // data points to rows*cols*type_id.Size() bytes of data in row-major order.
-  virtual void LogMatrix(log_level level, const ::std::string &message,
-                         uint32_t type_id, int rows, int cols,
-                         const void *data) = 0;
-
  private:
   // These functions call similar methods on the "current" LogImplementation or
   // Die if they can't find one.
@@ -97,14 +70,6 @@
       __attribute__((format(GOOD_PRINTF_FORMAT_TYPE, 2, 0)));
 
   friend void VLog(log_level, const char *, va_list);
-  friend void internal::DoLogStruct(
-      log_level level, const ::std::string &message, size_t size,
-      const MessageType *type, const ::std::function<size_t(char *)> &serialize,
-      int levels);
-  friend void internal::DoLogMatrix(log_level level,
-                                    const ::std::string &message,
-                                    uint32_t type_id, int rows, int cols,
-                                    const void *data, int levels);
 
   LogImplementation *next_;
 };
diff --git a/aos/logging/log_displayer.cc b/aos/logging/log_displayer.cc
index e63bdc3..fe902c0 100644
--- a/aos/logging/log_displayer.cc
+++ b/aos/logging/log_displayer.cc
@@ -13,7 +13,6 @@
 
 #include "aos/configuration.h"
 #include "aos/logging/binary_log_file.h"
-#include "aos/queue_types.h"
 #include "aos/logging/logging.h"
 #include "aos/logging/implementations.h"
 #include "aos/logging/printf_formats.h"
@@ -267,28 +266,6 @@
       return 0;
     }
 
-    if (msg->type == LogFileMessageHeader::MessageType::kStructType) {
-      size_t bytes = msg->message_size;
-      ::aos::MessageType *type = ::aos::MessageType::Deserialize(
-          reinterpret_cast<const char *>(msg + 1), &bytes);
-      if (type == nullptr) {
-        AOS_LOG(INFO, "Trying old version of type decoding.\n");
-        bytes = msg->message_size;
-        type = ::aos::MessageType::Deserialize(
-            reinterpret_cast<const char *>(msg + 1), &bytes, false);
-      }
-
-      if (type == nullptr) {
-        AOS_LOG(WARNING,
-                "Error deserializing MessageType of size %" PRIx32
-                " starting at %zx.\n",
-                msg->message_size, reader.file_offset(msg + 1));
-      } else {
-        ::aos::type_cache::Add(*type);
-      }
-      continue;
-    }
-
     if (source_pid >= 0 && msg->source != source_pid) {
       // Message is from the wrong process.
       continue;
@@ -342,69 +319,10 @@
         fprintf(stdout, AOS_LOGGING_BASE_FORMAT "%.*s", BASE_ARGS,
                 static_cast<int>(msg->message_size), position);
         break;
-      case LogFileMessageHeader::MessageType::kStruct: {
-        uint32_t type_id;
-        memcpy(&type_id, position, sizeof(type_id));
-        position += sizeof(type_id);
-
-        uint32_t string_length;
-        memcpy(&string_length, position, sizeof(string_length));
-        position += sizeof(string_length);
-
-        char buffer[4096];
-        size_t output_length = sizeof(buffer);
-        size_t input_length =
-            msg->message_size -
-            (sizeof(type_id) + sizeof(uint32_t) + string_length);
-        if (!PrintMessage(buffer, &output_length, position + string_length,
-                          &input_length, ::aos::type_cache::Get(type_id))) {
-          AOS_LOG(FATAL,
-                  "printing message (%.*s) of type %s into %zu-byte buffer "
-                  "failed\n",
-                  static_cast<int>(string_length), position,
-                  ::aos::type_cache::Get(type_id).name.c_str(), sizeof(buffer));
-        }
-        if (input_length > 0) {
-          AOS_LOG(WARNING, "%zu extra bytes on message of type %s\n",
-                  input_length, ::aos::type_cache::Get(type_id).name.c_str());
-        }
-        fprintf(stdout, AOS_LOGGING_BASE_FORMAT "%.*s: %.*s\n", BASE_ARGS,
-                static_cast<int>(string_length), position,
-                static_cast<int>(sizeof(buffer) - output_length), buffer);
-      } break;
-      case LogFileMessageHeader::MessageType::kMatrix: {
-        uint32_t type;
-        memcpy(&type, position, sizeof(type));
-        position += sizeof(type);
-
-        uint32_t string_length;
-        memcpy(&string_length, position, sizeof(string_length));
-        position += sizeof(string_length);
-
-        uint16_t rows;
-        memcpy(&rows, position, sizeof(rows));
-        position += sizeof(rows);
-        uint16_t cols;
-        memcpy(&cols, position, sizeof(cols));
-        position += sizeof(cols);
-
-        const size_t matrix_bytes =
-            msg->message_size -
-            (sizeof(type) + sizeof(uint32_t) + sizeof(uint16_t) +
-             sizeof(uint16_t) + string_length);
-        AOS_CHECK_EQ(matrix_bytes,
-                     ::aos::MessageType::Sizeof(type) * rows * cols);
-        char buffer[4096];
-        size_t output_length = sizeof(buffer);
-        if (!::aos::PrintMatrix(buffer, &output_length,
-                                position + string_length, type, rows, cols)) {
-          AOS_LOG(FATAL, "printing %dx%d matrix of type %" PRIu32 " failed\n",
-                  rows, cols, type);
-        }
-        fprintf(stdout, AOS_LOGGING_BASE_FORMAT "%.*s: %.*s\n", BASE_ARGS,
-                static_cast<int>(string_length), position,
-                static_cast<int>(sizeof(buffer) - output_length), buffer);
-      } break;
+      case LogFileMessageHeader::MessageType::kStruct:
+      case LogFileMessageHeader::MessageType::kMatrix:
+        AOS_LOG(FATAL, "Unsupported matrix or struct\n");
+        break;
       case LogFileMessageHeader::MessageType::kStructType:
         AOS_LOG(FATAL, "shouldn't get here\n");
         break;
diff --git a/aos/logging/matrix_logging.cc b/aos/logging/matrix_logging.cc
deleted file mode 100644
index e17c8a6..0000000
--- a/aos/logging/matrix_logging.cc
+++ /dev/null
@@ -1,39 +0,0 @@
-#include "aos/logging/matrix_logging.h"
-
-#include "aos/queue_types.h"
-#include "aos/logging/sizes.h"
-
-namespace aos {
-namespace logging {
-namespace internal {
-
-void DoLogMatrix(log_level level, const ::std::string &message,
-                 uint32_t type_id, int rows, int cols, const void *data,
-                 int levels) {
-  {
-    auto fn = [&](LogImplementation *implementation) {
-      implementation->LogMatrix(level, message, type_id, rows, cols, data);
-    };
-    RunWithCurrentImplementation(levels, ::std::ref(fn));
-  }
-
-  if (level == FATAL) {
-    char serialized[1024];
-    if (static_cast<size_t>(rows * cols * MessageType::Sizeof(type_id)) >
-        sizeof(serialized)) {
-      Die("LOG(FATAL) matrix too big to serialize");
-    }
-    SerializeMatrix(type_id, serialized, data, rows, cols);
-    char printed[LOG_MESSAGE_LEN];
-    size_t printed_bytes = sizeof(printed);
-    if (!PrintMatrix(printed, &printed_bytes, serialized, type_id, rows, cols)) {
-      Die("LOG(FATAL) PrintMatrix call failed");
-    }
-    Die("%.*s: %.*s\n", static_cast<int>(message.size()), message.data(),
-        static_cast<int>(printed_bytes), printed);
-  }
-}
-
-}  // namespace internal
-}  // namespace logging
-}  // namespace aos
diff --git a/aos/logging/matrix_logging.h b/aos/logging/matrix_logging.h
deleted file mode 100644
index ef51d56..0000000
--- a/aos/logging/matrix_logging.h
+++ /dev/null
@@ -1,47 +0,0 @@
-#ifndef AOS_LOGGING_MATRIX_LOGGING_H_
-#define AOS_LOGGING_MATRIX_LOGGING_H_
-
-#include <string>
-#include <functional>
-
-#include "Eigen/Dense"
-
-#include "aos/logging/interface.h"
-#include "aos/die.h"
-#include "aos/queue_primitives.h"
-
-namespace aos {
-namespace logging {
-
-// Logs the contents of a matrix and a constant string.
-// matrix must be an instance of an Eigen matrix (or something similar).
-#define AOS_LOG_MATRIX(level, message, matrix)                      \
-  do {                                                              \
-    static const ::std::string kAosLoggingMessage(                  \
-        LOG_SOURCENAME ": " STRINGIFY(__LINE__) ": " message);      \
-    ::aos::logging::DoLogMatrixTemplated(level, kAosLoggingMessage, \
-                                         (matrix).eval());          \
-    /* so that GCC knows that it won't return */                    \
-    if (level == FATAL) {                                           \
-      ::aos::Die("DoLogStruct(FATAL) fell through!!!!!\n");         \
-    }                                                               \
-  } while (false)
-
-template <class T>
-void DoLogMatrixTemplated(log_level level, const ::std::string &message,
-                          const T &matrix) {
-  if (T::IsRowMajor) {
-    typename T::Scalar data[matrix.rows() * matrix.cols()];
-    ::Eigen::Map<T>(data, matrix.rows(), matrix.cols()) = matrix;
-    internal::DoLogMatrix(level, message, TypeID<typename T::Scalar>::id,
-                          matrix.rows(), matrix.cols(), data, 1);
-  } else {
-    internal::DoLogMatrix(level, message, TypeID<typename T::Scalar>::id,
-                          matrix.rows(), matrix.cols(), matrix.data(), 1);
-  }
-}
-
-}  // namespace logging
-}  // namespace aos
-
-#endif  // AOS_LOGGING_MATRIX_LOGGING_H_
diff --git a/aos/logging/queue_logging.cc b/aos/logging/queue_logging.cc
deleted file mode 100644
index 541ddb1..0000000
--- a/aos/logging/queue_logging.cc
+++ /dev/null
@@ -1,39 +0,0 @@
-#include "aos/logging/queue_logging.h"
-
-#include "aos/logging/interface.h"
-#include "aos/logging/sizes.h"
-#include "aos/queue_types.h"
-
-namespace aos {
-namespace logging {
-namespace internal {
-
-void DoLogStruct(log_level level, const ::std::string &message, size_t size,
-                 const MessageType *type,
-                 const ::std::function<size_t(char *)> &serialize, int levels) {
-  {
-    auto fn = [&](LogImplementation *implementation) {
-      implementation->LogStruct(level, message, size, type, serialize);
-    };
-    RunWithCurrentImplementation(levels, ::std::ref(fn));
-  }
-
-  if (level == FATAL) {
-    char serialized[1024];
-    if (size > sizeof(serialized)) {
-      Die("LOG(FATAL) structure too big to serialize");
-    }
-    size_t used = serialize(serialized);
-    char printed[LOG_MESSAGE_LEN];
-    size_t printed_bytes = sizeof(printed);
-    if (!PrintMessage(printed, &printed_bytes, serialized, &used, *type)) {
-      Die("LOG(FATAL) PrintMessage call failed");
-    }
-    Die("%.*s: %.*s\n", static_cast<int>(message.size()), message.data(),
-        static_cast<int>(printed_bytes), printed);
-  }
-}
-
-}  // namespace internal
-}  // namespace logging
-}  // namespace aos
diff --git a/aos/logging/queue_logging.h b/aos/logging/queue_logging.h
deleted file mode 100644
index fdebcc3..0000000
--- a/aos/logging/queue_logging.h
+++ /dev/null
@@ -1,43 +0,0 @@
-#ifndef AOS_LOGGING_QUEUE_LOGGING_H_
-#define AOS_LOGGING_QUEUE_LOGGING_H_
-
-#include <stdio.h>
-#include <stdlib.h>
-
-#include <functional>
-#include <string>
-
-#include "aos/logging/interface.h"
-#include "aos/die.h"
-
-namespace aos {
-namespace logging {
-
-// Logs the contents of a structure (or Queue message) and a constant string.
-// structure must be an instance of one of the generated queue types.
-#define AOS_LOG_STRUCT(level, message, structure)                   \
-  do {                                                              \
-    static const ::std::string kAosLoggingMessage(                  \
-        LOG_SOURCENAME ": " STRINGIFY(__LINE__) ": " message);      \
-    ::aos::logging::DoLogStructTemplated(level, kAosLoggingMessage, \
-                                         structure);                \
-    /* so that GCC knows that it won't return */                    \
-    if (level == FATAL) {                                           \
-      ::aos::Die("DoLogStruct(FATAL) fell through!!!!!\n");         \
-    }                                                               \
-  } while (false)
-
-template <class T>
-void DoLogStructTemplated(log_level level, const ::std::string &message,
-                          const T &structure) {
-  auto fn = [&structure](char *buffer)
-                -> size_t { return structure.Serialize(buffer); };
-
-  internal::DoLogStruct(level, message, T::Size(), T::GetType(), ::std::ref(fn),
-                        1);
-}
-
-}  // namespace logging
-}  // namespace aos
-
-#endif  // AOS_LOGGING_QUEUE_LOGGING_H_
diff --git a/aos/logging/replay.cc b/aos/logging/replay.cc
deleted file mode 100644
index c58ee8c..0000000
--- a/aos/logging/replay.cc
+++ /dev/null
@@ -1,49 +0,0 @@
-#include "aos/logging/replay.h"
-
-#include <chrono>
-
-namespace aos {
-namespace logging {
-namespace linux_code {
-
-namespace chrono = ::std::chrono;
-
-bool LogReplayer::ProcessMessage() {
-  const LogFileMessageHeader *message = reader_->ReadNextMessage(false);
-  if (message == nullptr) return true;
-  if (message->type != LogFileMessageHeader::MessageType::kStruct) return false;
-
-  const char *position = reinterpret_cast<const char *>(message + 1);
-
-  ::std::string process(position, message->name_size);
-  position += message->name_size;
-
-  uint32_t type_id;
-  memcpy(&type_id, position, sizeof(type_id));
-  position += sizeof(type_id);
-
-  uint32_t message_length;
-  memcpy(&message_length, position, sizeof(message_length));
-  position += sizeof(message_length);
-  ::std::string message_text(position, message_length);
-  position += message_length;
-
-  size_t split_index = message_text.find_first_of(':') + 2;
-  split_index = message_text.find_first_of(':', split_index) + 2;
-  message_text = message_text.substr(split_index);
-
-  auto handler = handlers_.find(Key(process, message_text));
-  if (handler == handlers_.end()) return false;
-
-  handler->second->HandleStruct(
-      monotonic_clock::time_point(chrono::seconds(message->time_sec) +
-                                  chrono::nanoseconds(message->time_nsec)),
-      type_id, position,
-      message->message_size -
-          (sizeof(type_id) + sizeof(message_length) + message_length));
-  return false;
-}
-
-}  // namespace linux_code
-}  // namespace logging
-}  // namespace aos
diff --git a/aos/logging/replay.h b/aos/logging/replay.h
deleted file mode 100644
index 6604591..0000000
--- a/aos/logging/replay.h
+++ /dev/null
@@ -1,171 +0,0 @@
-#ifndef AOS_LOGGING_REPLAY_H_
-#define AOS_LOGGING_REPLAY_H_
-
-#include <unordered_map>
-#include <string>
-#include <functional>
-#include <memory>
-
-#include "aos/events/event-loop.h"
-#include "aos/ipc_lib/queue.h"
-#include "aos/logging/binary_log_file.h"
-#include "aos/logging/logging.h"
-#include "aos/logging/queue_logging.h"
-#include "aos/macros.h"
-#include "aos/queue.h"
-#include "aos/queue_types.h"
-
-namespace aos {
-namespace logging {
-namespace linux_code {
-
-// Manages pulling logged queue messages out of log files.
-//
-// Basic usage:
-//   - Use the Add* methods to register handlers for various message sources.
-//   - Call OpenFile to open a log file.
-//   - Call ProcessMessage repeatedly until it returns true.
-//
-// This code could do something to adapt similar-but-not-identical
-// messages to the current versions, but currently it will LOG(FATAL) if any of
-// the messages don't match up exactly.
-class LogReplayer {
- public:
-  LogReplayer() {}
-
-  // Gets ready to read messages from fd.
-  // Does not take ownership of fd.
-  void OpenFile(int fd) {
-    reader_.reset(new LogFileReader(fd));
-  }
-  // Closes the currently open file.
-  void CloseCurrentFile() { reader_.reset(); }
-  // Returns true if we have a file which is currently open.
-  bool HasCurrentFile() const { return reader_.get() != nullptr; }
-
-  // Processes a single message from the currently open file.
-  // Returns true if there are no more messages in the file.
-  // This will not call any of the handlers if the next message either has no
-  // registered handlers or is not a queue message.
-  bool ProcessMessage();
-
-  // Adds a handler for messages with a certain string from a certain process.
-  // T must be a Message with the same format as the messages generated by
-  // the .q files.
-  // LOG(FATAL)s for duplicate handlers.
-  template <class T>
-  void AddHandler(const ::std::string &process_name,
-                  const ::std::string &log_message,
-                  ::std::function<void(const T &message)> handler) {
-    AOS_CHECK(handlers_
-                  .emplace(::std::piecewise_construct,
-                           ::std::forward_as_tuple(process_name, log_message),
-                           ::std::forward_as_tuple(
-                               ::std::unique_ptr<StructHandlerInterface>(
-                                   new TypedStructHandler<T>(handler))))
-                  .second);
-  }
-
-  // Adds a handler which takes messages and places them directly on a queue.
-  // T must be a Message with the same format as the messages generated by
-  // the .q files.
-  template <class T>
-  void AddDirectQueueSender(const ::std::string &process_name,
-                            const ::std::string &log_message,
-                            const ::std::string &name) {
-    AddHandler(process_name, log_message,
-               ::std::function<void(const T &)>(
-                   QueueDumpStructHandler<T>(name.c_str())));
-  }
-
- private:
-  // A generic handler of struct log messages.
-  class StructHandlerInterface {
-   public:
-    virtual ~StructHandlerInterface() {}
-
-    virtual void HandleStruct(::aos::monotonic_clock::time_point log_time,
-                              uint32_t type_id, const void *data,
-                              size_t data_size) = 0;
-  };
-
-  // Converts struct log messages to a message type and passes it to an
-  // ::std::function.
-  template <class T>
-  class TypedStructHandler : public StructHandlerInterface {
-   public:
-    TypedStructHandler(::std::function<void(const T &message)> handler)
-        : handler_(handler) {}
-
-    void HandleStruct(::aos::monotonic_clock::time_point log_time,
-                      uint32_t type_id, const void *data,
-                      size_t data_size) override {
-      AOS_CHECK_EQ(type_id, T::GetType()->id);
-      T message;
-      AOS_CHECK_EQ(data_size, T::Size());
-      AOS_CHECK_EQ(data_size,
-                   message.Deserialize(static_cast<const char *>(data)));
-      message.sent_time = log_time;
-      handler_(message);
-    }
-
-   private:
-    const ::std::function<void(T message)> handler_;
-  };
-
-  // A callable class which dumps messages straight to a queue.
-  template <class T>
-  class QueueDumpStructHandler {
-   public:
-    QueueDumpStructHandler(const ::std::string &queue_name)
-        : queue_(RawQueue::Fetch(queue_name.c_str(), sizeof(T), T::kHash,
-                                 T::kQueueLength)) {}
-
-    void operator()(const T &message) {
-      AOS_LOG_STRUCT(DEBUG, "re-sending", message);
-      void *raw_message = queue_->GetMessage();
-      AOS_CHECK_NOTNULL(raw_message);
-      memcpy(raw_message, &message, sizeof(message));
-      AOS_CHECK(queue_->WriteMessage(raw_message, RawQueue::kOverride));
-    }
-
-   private:
-    ::aos::RawQueue *const queue_;
-  };
-
-  // A key for specifying log messages to give to a certain handler.
-  struct Key {
-    Key(const ::std::string &process_name, const ::std::string &log_message)
-        : process_name(process_name), log_message(log_message) {}
-
-    ::std::string process_name;
-    ::std::string log_message;
-  };
-
-  struct KeyHash {
-    size_t operator()(const Key &key) const {
-      return string_hash(key.process_name) ^
-             (string_hash(key.log_message) << 1);
-    }
-
-   private:
-    const ::std::hash<::std::string> string_hash = ::std::hash<::std::string>();
-  };
-  struct KeyEqual {
-    bool operator()(const Key &a, const Key &b) const {
-      return a.process_name == b.process_name && a.log_message == b.log_message;
-    }
-  };
-
-  ::std::unordered_map<const Key, ::std::unique_ptr<StructHandlerInterface>,
-                       KeyHash, KeyEqual> handlers_;
-  ::std::unique_ptr<LogFileReader> reader_;
-
-  DISALLOW_COPY_AND_ASSIGN(LogReplayer);
-};
-
-}  // namespace linux_code
-}  // namespace logging
-}  // namespace aos
-
-#endif  // AOS_LOGGING_REPLAY_H_
diff --git a/aos/mutex/BUILD b/aos/mutex/BUILD
index 43c9616..e698f62 100644
--- a/aos/mutex/BUILD
+++ b/aos/mutex/BUILD
@@ -9,10 +9,9 @@
         "mutex.h",
     ],
     deps = [
-        "//aos:die",
-        "//aos/type_traits:type_traits",
-        "//aos/logging",
         "//aos/ipc_lib:aos_sync",
+        "//aos/type_traits",
+        "@com_github_google_glog//:glog",
     ],
 )
 
@@ -22,14 +21,13 @@
         "mutex_test.cc",
     ],
     deps = [
-        "//aos:die",
         ":mutex",
-        "//aos/time:time",
-        "//aos/logging",
-        "//aos/util:death_test_log_implementation",
-        "//aos/util:thread",
         "//aos/testing:googletest",
         "//aos/testing:test_logging",
         "//aos/testing:test_shm",
+        "//aos/time",
+        "//aos/util:death_test_log_implementation",
+        "//aos/util:thread",
+        "@com_github_google_glog//:glog",
     ],
 )
diff --git a/aos/mutex/mutex.cc b/aos/mutex/mutex.cc
index c5570aa..ef4fbbe 100644
--- a/aos/mutex/mutex.cc
+++ b/aos/mutex/mutex.cc
@@ -5,7 +5,7 @@
 #include <string.h>
 
 #include "aos/type_traits/type_traits.h"
-#include "aos/logging/logging.h"
+#include "glog/logging.h"
 
 namespace aos {
 
@@ -19,8 +19,8 @@
   } else if (ret == 1) {
     return true;
   } else {
-    AOS_LOG(FATAL, "mutex_grab(%p(=%" PRIu32 ")) failed with %d\n", &impl_,
-            impl_.futex, ret);
+    LOG(FATAL) << "mutex_grab(" << &impl_ << "(=" << std::hex << impl_.futex
+               << ")) failed with " << ret;
   }
 }
 
@@ -38,8 +38,8 @@
     case 4:
       return State::kLockFailed;
     default:
-      AOS_LOG(FATAL, "mutex_trylock(%p(=%" PRIu32 ")) failed with %d\n", &impl_,
-              impl_.futex, ret);
+      LOG(FATAL) << "mutex_trylock(" << &impl_ << "(=" << std::hex
+                 << impl_.futex << ")) failed with " << ret;
   }
 }
 
diff --git a/aos/mutex/mutex.h b/aos/mutex/mutex.h
index ad678cc..a2af7ae 100644
--- a/aos/mutex/mutex.h
+++ b/aos/mutex/mutex.h
@@ -1,10 +1,10 @@
 #ifndef AOS_MUTEX_H_
 #define AOS_MUTEX_H_
 
+#include "aos/ipc_lib/aos_sync.h"
 #include "aos/macros.h"
 #include "aos/type_traits/type_traits.h"
-#include "aos/die.h"
-#include "aos/ipc_lib/aos_sync.h"
+#include "glog/logging.h"
 
 namespace aos {
 
@@ -73,8 +73,8 @@
  public:
   explicit MutexLocker(Mutex *mutex) : mutex_(mutex) {
     if (__builtin_expect(mutex_->Lock(), false)) {
-      ::aos::Die("previous owner of mutex %p died but it shouldn't be able to",
-                 this);
+      LOG(FATAL) << "previous owner of mutex " << this
+                 << " died but it shouldn't be able to";
     }
   }
   ~MutexLocker() {
@@ -95,13 +95,14 @@
       : mutex_(mutex), owner_died_(mutex_->Lock()) {}
   ~IPCMutexLocker() {
     if (__builtin_expect(!owner_died_checked_, false)) {
-      ::aos::Die("nobody checked if the previous owner of mutex %p died", this);
+      LOG(FATAL) << "nobody checked if the previous owner of mutex " << this
+                 << " died";
     }
     mutex_->Unlock();
   }
 
   // Whether or not the previous owner died. If this is not called at least
-  // once, the destructor will ::aos::Die.
+  // once, the destructor will LOG(FATAL)
   __attribute__((warn_unused_result)) bool owner_died() {
     owner_died_checked_ = true;
     return __builtin_expect(owner_died_, false);
@@ -125,13 +126,14 @@
         owner_died_(locked_ ? mutex_->Lock() : false) {}
   ~IPCRecursiveMutexLocker() {
     if (__builtin_expect(!owner_died_checked_, false)) {
-      ::aos::Die("nobody checked if the previous owner of mutex %p died", this);
+      LOG(FATAL) << "nobody checked if the previous owner of mutex " << this
+                 << " died";
     }
     if (locked_) mutex_->Unlock();
   }
 
   // Whether or not the previous owner died. If this is not called at least
-  // once, the destructor will ::aos::Die.
+  // once, the destructor will LOG(FATAL)
   __attribute__((warn_unused_result)) bool owner_died() {
     owner_died_checked_ = true;
     return __builtin_expect(owner_died_, false);
diff --git a/aos/mutex/mutex_test.cc b/aos/mutex/mutex_test.cc
index 9d371b7..cc659a5 100644
--- a/aos/mutex/mutex_test.cc
+++ b/aos/mutex/mutex_test.cc
@@ -10,13 +10,13 @@
 #include "gtest/gtest.h"
 
 #include "aos/die.h"
-#include "aos/time/time.h"
-#include "aos/util/death_test_log_implementation.h"
-#include "aos/util/thread.h"
 #include "aos/ipc_lib/aos_sync.h"
 #include "aos/ipc_lib/core_lib.h"
 #include "aos/testing/test_logging.h"
 #include "aos/testing/test_shm.h"
+#include "aos/time/time.h"
+#include "aos/util/death_test_log_implementation.h"
+#include "aos/util/thread.h"
 
 namespace aos {
 namespace testing {
diff --git a/aos/queue-tmpl.h b/aos/queue-tmpl.h
deleted file mode 100644
index 2ca79b8..0000000
--- a/aos/queue-tmpl.h
+++ /dev/null
@@ -1,106 +0,0 @@
-namespace aos {
-
-template <class T>
-bool ScopedMessagePtr<T>::Send() {
-  assert(msg_ != NULL);
-  msg_->SetTimeToNow();
-  assert(queue_ != NULL);
-  bool return_value = queue_->WriteMessage(msg_, RawQueue::kOverride);
-  msg_ = NULL;
-  return return_value;
-}
-
-template <class T>
-void ScopedMessagePtr<T>::reset(T *msg) {
-  if (queue_ != NULL && msg_ != NULL) {
-    queue_->FreeMessage(msg_);
-  }
-  msg_ = msg;
-}
-
-template <class T>
-void Queue<T>::Init() {
-  if (queue_ == NULL) {
-    queue_ = RawQueue::Fetch(queue_name_, sizeof(T),
-                             static_cast<int>(T::kHash),
-                             T::kQueueLength);
-    queue_msg_.set_queue(queue_);
-  }
-}
-
-template <class T>
-void Queue<T>::Clear() {
-  if (queue_ != NULL) {
-    queue_msg_.reset();
-    queue_ = NULL;
-    queue_msg_.set_queue(NULL);
-  }
-  index_ = 0;
-}
-
-template <class T>
-bool Queue<T>::FetchNext() {
-  Init();
-  const T *msg = static_cast<const T *>(
-      queue_->ReadMessageIndex(RawQueue::kNonBlock, &index_));
-  // Only update the internal pointer if we got a new message.
-  if (msg != NULL) {
-    queue_msg_.reset(msg);
-  }
-  return msg != NULL;
-}
-
-template <class T>
-void Queue<T>::FetchNextBlocking() {
-  Init();
-  const T *msg = static_cast<const T *>(
-      queue_->ReadMessageIndex(RawQueue::kBlock, &index_));
-  queue_msg_.reset(msg);
-  assert (msg != NULL);
-}
-
-template <class T>
-bool Queue<T>::FetchLatest() {
-  Init();
-  static constexpr Options<RawQueue> kOptions =
-      RawQueue::kFromEnd | RawQueue::kNonBlock;
-  const T *msg =
-      static_cast<const T *>(queue_->ReadMessageIndex(kOptions, &index_));
-  // Only update the internal pointer if we got a new message.
-  if (msg != NULL && msg != queue_msg_.get()) {
-    queue_msg_.reset(msg);
-    return true;
-  }
-  // The message has to get freed if we didn't use it (and RawQueue::FreeMessage
-  // is ok to call on NULL).
-  queue_->FreeMessage(msg);
-  return false;
-}
-
-template <class T>
-void Queue<T>::FetchAnother() {
-  if (!FetchLatest()) FetchNextBlocking();
-}
-
-template <class T>
-ScopedMessagePtr<T> Queue<T>::MakeMessage() {
-  Init();
-  return ScopedMessagePtr<T>(queue_, MakeRawMessage());
-}
-
-template <class T>
-T *Queue<T>::MakeRawMessage() {
-  T *ret = static_cast<T *>(queue_->GetMessage());
-  assert(ret != NULL);
-  ret->Zero();
-  return ret;
-}
-
-template <class T>
-aos::MessageBuilder<T> Queue<T>::MakeWithBuilder() {
-  Init();
-  T *const ret = MakeRawMessage();
-  return aos::MessageBuilder<T>(queue_, ret);
-}
-
-}  // namespace aos
diff --git a/aos/queue.h b/aos/queue.h
deleted file mode 100644
index fb11f4f..0000000
--- a/aos/queue.h
+++ /dev/null
@@ -1,219 +0,0 @@
-#ifndef AOS_QUEUE_H_
-#define AOS_QUEUE_H_
-
-#include <assert.h>
-
-#include "aos/macros.h"
-#include "aos/ipc_lib/queue.h"
-#include "aos/messages/message.h"
-
-namespace aos {
-
-template <class T> class Queue;
-
-// A ScopedMessagePtr<> manages a queue message pointer.
-// It frees it properly when the ScopedMessagePtr<> goes out of scope or gets
-// sent.  By design, there is no way to get the ScopedMessagePtr to release the
-// message pointer to external code.
-template <class T>
-class ScopedMessagePtr {
- public:
-  // Returns a pointer to the message.
-  // This stays valid until Send or the destructor have been called.
-  const T *get() const { return msg_; }
-  T *get() { return msg_; }
-
-  const T &operator*() const {
-    const T *msg = get();
-    assert(msg != NULL);
-    return *msg;
-  }
-
-  T &operator*() {
-    T *msg = get();
-    assert(msg != NULL);
-    return *msg;
-  }
-
-  const T *operator->() const {
-    const T *msg = get();
-    assert(msg != NULL);
-    return msg;
-  }
-
-  T *operator->() {
-    T *msg = get();
-    assert(msg != NULL);
-    return msg;
-  }
-
-  operator bool() {
-    return msg_ != NULL;
-  }
-
-  // Sends the message and removes our reference to it.
-  // If the queue is full, over-ride the oldest message in it with our new
-  // message.
-  // Returns true on success, and false otherwise.
-  // The message will be freed.
-  bool Send();
-
-  // Frees the contained message.
-  ~ScopedMessagePtr() {
-    reset();
-  }
-
-  // Implements a move constructor.  This only takes rvalue references
-  // because we want to allow someone to say
-  // ScopedMessagePtr<X> ptr = queue.MakeMessage();
-  // but we don't want to allow them to then say
-  // ScopedMessagePtr<X> new_ptr = ptr;
-  // And, if they do actually want to move the pointer, then it will correctly
-  // clear out the source so there aren't 2 pointers to the message lying
-  // around.
-  ScopedMessagePtr(ScopedMessagePtr<T> &&ptr)
-      : queue_(ptr.queue_), msg_(ptr.msg_) {
-    ptr.msg_ = NULL;
-  }
-
- private:
-  // Provide access to set_queue and the constructor for init.
-  friend class aos::Queue<typename std::remove_const<T>::type>;
-  // Provide access to the copy constructor for MakeWithBuilder.
-  friend class aos::MessageBuilder<T>;
-
-  // Only Queue should be able to build a message.
-  ScopedMessagePtr(RawQueue *queue, T *msg)
-      : queue_(queue), msg_(msg) {}
-
-  // Sets the pointer to msg, freeing the old value if it was there.
-  // This is private because nobody should be able to get a pointer to a message
-  // that needs to be scoped without using the queue.
-  void reset(T *msg = NULL);
-
-  // Sets the queue that owns this message.
-  void set_queue(RawQueue *queue) { queue_ = queue; }
-
-  // The queue that the message is a part of.
-  RawQueue *queue_;
-  // The message or NULL.
-  T *msg_;
-
-  // Protect evil constructors.
-  DISALLOW_COPY_AND_ASSIGN(ScopedMessagePtr<T>);
-};
-
-// TODO(aschuh): Base class
-// T must be a Message with the same format as the messages generated by
-// the .q files.
-template <class T>
-class Queue {
- public:
-  typedef T Message;
-
-  explicit Queue(const char *queue_name)
-      : queue_name_(queue_name), queue_(NULL), queue_msg_(NULL, NULL) {
-    static_assert(shm_ok<T>::value,
-                  "The provided message type can't be put in shmem.");
-  }
-
-  // Initializes the queue.  This may optionally be called to do any one time
-  // work before sending information, and may be be called multiple times.
-  // Init will be called when a message is sent, but this will cause sending to
-  // take a different amount of time the first cycle.
-  void Init();
-
-  // Removes all internal references to shared memory so shared memory can be
-  // restarted safely.  This should only be used in testing.
-  void Clear();
-
-  // Fetches the next message from the queue.
-  // Returns true if there was a new message available and we successfully
-  // fetched it.
-  bool FetchNext();
-
-  // Fetches the next message from the queue, waiting if necessary until there
-  // is one.
-  void FetchNextBlocking();
-
-  // Fetches the last message from the queue.
-  // Returns true if there was a new message available and we successfully
-  // fetched it.
-  bool FetchLatest();
-
-  // Fetches the latest message from the queue, or blocks if we have already
-  // fetched it until another is avilable.
-  void FetchAnother();
-
-  // Returns the age of the message.
-  const monotonic_clock::duration Age() const {
-    return monotonic_clock::now() - queue_msg_->sent_time;
-  }
-
-  bool IsNewerThan(const monotonic_clock::duration age) const {
-    return get() != nullptr && Age() < age;
-  }
-
-  // Returns a pointer to the current message.
-  // This pointer will be valid until a new message is fetched.
-  const T *get() const { return queue_msg_.get(); }
-
-  // Returns a reference to the message.
-  // The message will be valid until a new message is fetched.
-  const T &operator*() const {
-    const T *msg = get();
-    assert(msg != NULL);
-    return *msg;
-  }
-
-  // Returns a pointer to the current message.
-  // This pointer will be valid until a new message is fetched.
-  const T *operator->() const {
-    const T *msg = get();
-    assert(msg != NULL);
-    return msg;
-  }
-
-  // Returns a scoped_ptr containing a message.
-  // GCC will optimize away the copy constructor, so this is safe.
-  ScopedMessagePtr<T> MakeMessage();
-
-  // Returns a message builder that contains a pre-allocated message.
-  // This message will start out completely zeroed.
-  aos::MessageBuilder<T> MakeWithBuilder();
-
-  const char *name() const { return queue_name_; }
-
- private:
-  const char *queue_name_;
-
-  T *MakeRawMessage();
-
-  // Pointer to the queue that this object fetches from.
-  RawQueue *queue_;
-  int index_ = 0;
-  // Scoped pointer holding the latest message or NULL.
-  ScopedMessagePtr<const T> queue_msg_;
-
-  DISALLOW_COPY_AND_ASSIGN(Queue<T>);
-};
-
-// Base class for all queue groups.
-class QueueGroup {
- public:
-  // Constructs a queue group given its name and a unique hash of the name and
-  // type.
-  QueueGroup(const char *name) : name_(name) {}
-
-  // Returns the name of the queue group.
-  const char *name() const { return name_.c_str(); }
-
- private:
-  std::string name_;
-};
-
-}  // namespace aos
-
-#include "aos/queue-tmpl.h"
-
-#endif  // AOS_QUEUE_H_
diff --git a/aos/queue_test.cc b/aos/queue_test.cc
deleted file mode 100644
index 1c4ebdd..0000000
--- a/aos/queue_test.cc
+++ /dev/null
@@ -1,316 +0,0 @@
-#include <unistd.h>
-
-#include <chrono>
-#include <memory>
-
-#include "gtest/gtest.h"
-
-#include "aos/die.h"
-#include "aos/test_queue.q.h"
-#include "aos/util/thread.h"
-#include "aos/testing/test_shm.h"
-
-namespace aos {
-namespace common {
-namespace testing {
-
-namespace chrono = ::std::chrono;
-
-class QueueTest : public ::testing::Test {
- protected:
-  void SetUp() override {
-    SetDieTestMode(true);
-  }
-
-  ::aos::testing::TestSharedMemory my_shm_;
-  // Create a new instance of the test queue so that it invalidates the queue
-  // that it points to.  Otherwise, we will have a pointer to shared memory that
-  // is no longer valid.
-  ::aos::Queue<TestingMessage> my_test_queue;
-
-  QueueTest() : my_test_queue(".aos.common.testing.test_queue") {}
-};
-
-class MyThread : public util::Thread {
- public:
-  MyThread() : threaded_test_queue(".aos.common.testing.test_queue") {}
-
-  virtual void Run() {
-    threaded_test_queue.FetchNextBlocking();
-    EXPECT_TRUE(threaded_test_queue->test_bool);
-    EXPECT_EQ(0x971, threaded_test_queue->test_int);
-  }
-
-  ::aos::Queue<TestingMessage> threaded_test_queue;
- private:
-  DISALLOW_COPY_AND_ASSIGN(MyThread);
-};
-
-
-// Tests that we can send a message to another thread and it blocking receives
-// it at the correct time.
-TEST_F(QueueTest, FetchBlocking) {
-  MyThread t;
-  t.Start();
-  usleep(50000);
-  my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
-  t.Join();
-  EXPECT_LE(t.threaded_test_queue.Age(), chrono::milliseconds(57));
-}
-
-// Tests that we can send a message with the message pointer and get it back.
-TEST_F(QueueTest, SendMessage) {
-  ScopedMessagePtr<TestingMessage> msg = my_test_queue.MakeMessage();
-  msg->test_bool = true;
-  msg->test_int = 0x971;
-  msg.Send();
-
-  ASSERT_TRUE(my_test_queue.FetchLatest());
-  EXPECT_TRUE(my_test_queue->test_bool);
-  EXPECT_EQ(0x971, my_test_queue->test_int);
-}
-
-// Tests that we can send a message with the builder and get it back.
-TEST_F(QueueTest, SendWithBuilder) {
-  my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
-
-  ASSERT_TRUE(my_test_queue.FetchLatest());
-  EXPECT_EQ(true, my_test_queue->test_bool);
-  EXPECT_EQ(0x971, my_test_queue->test_int);
-  EXPECT_EQ(true, my_test_queue.IsNewerThan(chrono::milliseconds(10000)));
-}
-
-// Tests that multiple queue instances don't break each other.
-TEST_F(QueueTest, MultipleQueues) {
-  my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
-  ASSERT_TRUE(my_test_queue.FetchLatest());
-  EXPECT_TRUE(my_test_queue.get());
-
-  {
-    ::aos::Queue<TestingMessage> my_other_test_queue(
-        ".aos.common.testing.queue_name");
-    my_other_test_queue.MakeMessage();
-    EXPECT_FALSE(my_other_test_queue.FetchLatest());
-    EXPECT_FALSE(my_test_queue.FetchLatest());
-  }
-
-  EXPECT_TRUE(my_test_queue.get());
-}
-
-// Tests that using a queue from multiple threads works correctly.
-TEST_F(QueueTest, MultipleThreads) {
-  my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
-  ASSERT_TRUE(my_test_queue.FetchLatest());
-  my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x254).Send();
-  EXPECT_EQ(0x971, my_test_queue->test_int);
-
-  ::aos::util::FunctionThread::RunInOtherThread([this]() {
-    ASSERT_TRUE(my_test_queue.FetchLatest());
-    EXPECT_EQ(0x254, my_test_queue->test_int);
-  });
-  EXPECT_EQ(0x254, my_test_queue->test_int);
-}
-
-// Makes sure that MakeWithBuilder zeros the message initially.
-// This might randomly succeed sometimes, but it will fail with asan if it
-// doesn't.
-TEST_F(QueueTest, BuilderZero) {
-  my_test_queue.MakeWithBuilder().Send();
-
-  ASSERT_TRUE(my_test_queue.FetchLatest());
-  EXPECT_FALSE(my_test_queue->test_bool);
-  EXPECT_EQ(0, my_test_queue->test_int);
-}
-
-// Tests that various pointer deref functions at least seem to work.
-TEST_F(QueueTest, PointerDeref) {
-  my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
-
-  ASSERT_TRUE(my_test_queue.FetchLatest());
-  const TestingMessage *msg_ptr = my_test_queue.get();
-  ASSERT_NE(static_cast<TestingMessage*>(NULL), msg_ptr);
-  EXPECT_EQ(0x971, msg_ptr->test_int);
-  EXPECT_EQ(msg_ptr, &(*my_test_queue));
-}
-
-// Tests that FetchNext doesn't miss any messages.
-TEST_F(QueueTest, FetchNext) {
-  for (int i = 0; i < 10; ++i) {
-    my_test_queue.MakeWithBuilder().test_bool(true).test_int(i).Send();
-  }
-
-  for (int i = 0; i < 10; ++i) {
-    ASSERT_TRUE(my_test_queue.FetchNext());
-    EXPECT_EQ(i, my_test_queue->test_int);
-  }
-}
-
-// Tests that FetchLatest skips a missing message.
-TEST_F(QueueTest, FetchLatest) {
-  my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x254).Send();
-  my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
-
-  ASSERT_TRUE(my_test_queue.FetchLatest());
-  EXPECT_EQ(0x971, my_test_queue->test_int);
-}
-
-// Tests that FetchLatest works with multiple readers.
-TEST_F(QueueTest, FetchLatestMultiple) {
-  ::aos::Queue<TestingMessage> my_second_test_queue(
-      ".aos.common.testing.test_queue");
-  my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x254).Send();
-  my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
-
-  ASSERT_TRUE(my_test_queue.FetchLatest());
-  EXPECT_EQ(0x971, my_test_queue->test_int);
-  ASSERT_TRUE(my_second_test_queue.FetchLatest());
-  ASSERT_TRUE(my_second_test_queue.get() != NULL);
-  EXPECT_EQ(0x971, my_second_test_queue->test_int);
-}
-
-
-// Tests that fetching without a new message returns false.
-TEST_F(QueueTest, FetchLatestWithoutMessage) {
-  my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x254).Send();
-  EXPECT_TRUE(my_test_queue.FetchLatest());
-  EXPECT_FALSE(my_test_queue.FetchLatest());
-  EXPECT_FALSE(my_test_queue.FetchLatest());
-  EXPECT_EQ(0x254, my_test_queue->test_int);
-}
-
-// Tests that fetching without a message returns false.
-TEST_F(QueueTest, FetchOnFreshQueue) {
-  EXPECT_FALSE(my_test_queue.FetchLatest());
-  EXPECT_EQ(static_cast<TestingMessage*>(NULL), my_test_queue.get());
-}
-
-// Tests that fetch next without a message returns false.
-TEST_F(QueueTest, FetchNextOnFreshQueue) {
-  EXPECT_FALSE(my_test_queue.FetchNext());
-  EXPECT_EQ(static_cast<TestingMessage*>(NULL), my_test_queue.get());
-}
-
-// Tests that fetch next without a new message returns false.
-TEST_F(QueueTest, FetchNextWithoutMessage) {
-  my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x254).Send();
-  EXPECT_TRUE(my_test_queue.FetchNext());
-  EXPECT_FALSE(my_test_queue.FetchNext());
-  EXPECT_NE(static_cast<TestingMessage*>(NULL), my_test_queue.get());
-}
-
-// Tests that age makes some sense.
-TEST_F(QueueTest, Age) {
-  my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
-
-  ASSERT_TRUE(my_test_queue.FetchLatest());
-  EXPECT_TRUE(my_test_queue.IsNewerThan(chrono::milliseconds(100)));
-  const auto age = my_test_queue.Age();
-  EXPECT_GE(chrono::nanoseconds(100000000), age);
-}
-
-
-class GroupTest : public ::testing::Test {
- protected:
-  GroupTest()
-      : my_test_queuegroup(".aos.common.testing.test_queuegroup",
-                           ".aos.common.testing.test_queuegroup.first",
-                           ".aos.common.testing.test_queuegroup.second") {}
-
-  // Create a new instance of the test group so that it invalidates the queue
-  // that it points to.  Otherwise, we will have a pointer to shared memory that
-  // is no longer valid.
-  TwoQueues my_test_queuegroup;
-
- private:
-  ::aos::testing::TestSharedMemory my_shm_;
-};
-
-// Tests that name works.
-TEST_F(GroupTest, Name) {
-  EXPECT_EQ(std::string(".aos.common.testing.test_queuegroup"),
-            std::string(my_test_queuegroup.name()));
-}
-
-
-class MessageTest : public ::testing::Test {
- public:
-  TestingMessage msg;
-};
-
-TEST_F(MessageTest, Zeroing) {
-  msg.test_bool = true;
-  msg.test_int = 0x254;
-  msg.SetTimeToNow();
-
-  msg.Zero();
-
-  EXPECT_FALSE(msg.test_bool);
-  EXPECT_EQ(0, msg.test_int);
-  EXPECT_EQ(monotonic_clock::min_time, msg.sent_time);
-}
-
-TEST_F(MessageTest, Size) {
-  EXPECT_EQ(static_cast<size_t>(13), msg.Size());
-}
-
-TEST_F(MessageTest, Serialize) {
-  char serialized_data[msg.Size()];
-  msg.test_bool = true;
-  msg.test_int = 0x254;
-  msg.SetTimeToNow();
-
-  msg.Serialize(serialized_data);
-
-  TestingMessage new_msg;
-  new_msg.Deserialize(serialized_data);
-
-  EXPECT_EQ(msg.test_bool, new_msg.test_bool);
-  EXPECT_EQ(msg.test_int, new_msg.test_int);
-  EXPECT_EQ(msg.sent_time, new_msg.sent_time);
-}
-
-// Tests that Print prints out a message nicely.
-TEST_F(MessageTest, Print) {
-  char printdata[1024];
-  msg.test_bool = true;
-  msg.test_int = 2056;
-  msg.sent_time = monotonic_clock::time_point(chrono::seconds(971) +
-                                              chrono::nanoseconds(254));
-
-  std::string golden("971.000000254s, T, 2056");
-  EXPECT_EQ(golden.size(), msg.Print(printdata, sizeof(printdata)));
-
-  EXPECT_EQ(golden, std::string(printdata));
-}
-
-// Tests that the hash never changes.  If it changes, then someone broke the
-// hash routine or changed the message declaration.  Both changes need to be
-// validated by hand.
-TEST_F(MessageTest, Hash) {
-  EXPECT_EQ(static_cast<uint32_t>(0xc33651ac),
-            static_cast<uint32_t>(TestingMessage::kHash));
-}
-
-TEST_F(MessageTest, SetNow) {
-  msg.SetTimeToNow();
-  EXPECT_LE(msg.sent_time - monotonic_clock::now(), chrono::milliseconds(20));
-}
-
-// Tests that EqualsNoTime works.
-TEST_F(MessageTest, EqualsNoTime) {
-  msg.test_bool = true;
-  msg.test_int = 971;
-  TestingMessage other;
-  other.test_int = 971;
-  EXPECT_FALSE(other.EqualsNoTime(msg));
-  EXPECT_FALSE(msg.EqualsNoTime(other));
-  other.test_bool = true;
-  EXPECT_TRUE(other.EqualsNoTime(msg));
-  EXPECT_TRUE(msg.EqualsNoTime(other));
-  msg.SetTimeToNow();
-  EXPECT_TRUE(msg.EqualsNoTime(other));
-}
-
-}  // namespace testing
-}  // namespace common
-}  // namespace aos
diff --git a/aos/queue_types.cc b/aos/queue_types.cc
deleted file mode 100644
index a48c5a0..0000000
--- a/aos/queue_types.cc
+++ /dev/null
@@ -1,462 +0,0 @@
-#include "aos/queue_types.h"
-
-#include <inttypes.h>
-
-#include <memory>
-#include <unordered_map>
-
-#include "aos/byteorder.h"
-#include "aos/ipc_lib/shared_mem.h"
-#include "aos/logging/logging.h"
-#include "aos/ipc_lib/core_lib.h"
-#include "aos/mutex/mutex.h"
-
-namespace aos {
-
-ssize_t MessageType::Serialize(char *buffer, size_t max_bytes) const {
-  char *const buffer_start = buffer;
-  uint16_t fields_size = 0;
-  for (int i = 0; i < number_fields; ++i) {
-    fields_size += sizeof(fields[i]->type);
-    fields_size += sizeof(fields[i]->length);
-    fields_size += sizeof(uint16_t);
-    fields_size += fields[i]->name.size();
-  }
-  if (max_bytes < sizeof(id) + sizeof(super_size) + sizeof(uint16_t) +
-                      sizeof(number_fields) + name.size() + fields_size) {
-    return -1;
-  }
-
-  uint16_t length;
-
-  to_network(&super_size, buffer);
-  buffer += sizeof(super_size);
-  to_network(&id, buffer);
-  buffer += sizeof(id);
-  length = name.size();
-  to_network(&length, buffer);
-  buffer += sizeof(length);
-  to_network(&number_fields, buffer);
-  buffer += sizeof(number_fields);
-  memcpy(buffer, name.data(), length);
-  buffer += name.size();
-
-  for (int i = 0; i < number_fields; ++i) {
-    to_network(&fields[i]->type, buffer);
-    buffer += sizeof(fields[i]->type);
-    to_network(&fields[i]->length, buffer);
-    buffer += sizeof(fields[i]->length);
-    length = fields[i]->name.size();
-    to_network(&length, buffer);
-    buffer += sizeof(length);
-    memcpy(buffer, fields[i]->name.data(), length);
-    buffer += length;
-  }
-
-  return buffer - buffer_start;
-}
-
-MessageType *MessageType::Deserialize(const char *buffer, size_t *bytes,
-                                      bool deserialize_length) {
-  uint16_t name_length;
-  decltype(MessageType::super_size) super_size;
-  decltype(MessageType::id) id;
-  decltype(MessageType::number_fields) number_fields;
-  if (*bytes < sizeof(super_size) + sizeof(id) + sizeof(name_length) +
-                   sizeof(number_fields)) {
-    return nullptr;
-  }
-  *bytes -= sizeof(super_size) + sizeof(id) + sizeof(name_length) +
-            sizeof(number_fields);
-
-  to_host(buffer, &super_size);
-  buffer += sizeof(super_size);
-  to_host(buffer, &id);
-  buffer += sizeof(id);
-  to_host(buffer, &name_length);
-  buffer += sizeof(name_length);
-  to_host(buffer, &number_fields);
-  buffer += sizeof(number_fields);
-
-  if (*bytes < name_length) {
-    return nullptr;
-  }
-  *bytes -= name_length;
-
-  Field **fields = new Field *[number_fields];
-  ::std::unique_ptr<MessageType> r(
-      new MessageType(super_size, id, ::std::string(buffer, name_length),
-                      number_fields, fields));
-  buffer += name_length;
-
-  for (int i = 0; i < number_fields; ++i) {
-    uint16_t field_name_length;
-    if (*bytes < sizeof(fields[i]->type) + sizeof(field_name_length) +
-                     (deserialize_length ? sizeof(fields[i]->length) : 0)) {
-      return nullptr;
-    }
-    *bytes -= sizeof(fields[i]->type) + sizeof(field_name_length);
-
-    to_host(buffer, &fields[i]->type);
-    buffer += sizeof(fields[i]->type);
-    if (deserialize_length) {
-      to_host(buffer, &fields[i]->length);
-      buffer += sizeof(fields[i]->length);
-      *bytes -= sizeof(fields[i]->length);
-    }
-    to_host(buffer, &field_name_length);
-    buffer += sizeof(field_name_length);
-
-    if (*bytes < field_name_length) {
-      return nullptr;
-    }
-    *bytes -= field_name_length;
-    fields[i]->name = ::std::string(buffer, field_name_length);
-    buffer += field_name_length;
-  }
-
-  return r.release();
-}
-
-bool PrintArray(char *output, size_t *output_bytes, const void *input,
-                size_t *input_bytes, uint32_t type_id, uint32_t length) {
-  if (*output_bytes < 1) return false;
-  *output_bytes -= 1;
-  *(output++) = '[';
-
-  bool first = true;
-  for (uint32_t i = 0; i < length; ++i) {
-    if (first) {
-      first = false;
-    } else {
-      if (*output_bytes < 2) return false;
-      *output_bytes -= 2;
-      *(output++) = ',';
-      *(output++) = ' ';
-    }
-
-    const size_t output_bytes_before = *output_bytes,
-                 input_bytes_before = *input_bytes;
-    if (MessageType::IsPrimitive(type_id)) {
-      if (!PrintField(output, output_bytes, input, input_bytes, type_id)) {
-        return false;
-      }
-    } else {
-      if (!PrintMessage(output, output_bytes, input, input_bytes,
-                        type_cache::Get(type_id))) {
-        return false;
-      }
-      // Ignore the trailing '\0' that the subcall put on.
-      *output_bytes += 1;
-    }
-
-    // Update the input and output pointers.
-    output += output_bytes_before - *output_bytes;
-    input =
-        static_cast<const char *>(input) + input_bytes_before - *input_bytes;
-  }
-  if (*output_bytes < 2) return false;
-  *output_bytes -= 2;
-  *(output++) = ']';
-  *(output++) = '\0';
-  return true;
-}
-
-bool PrintMessage(char *output, size_t *output_bytes, const void *input,
-                  size_t *input_bytes, const MessageType &type) {
-  if (*output_bytes < type.name.size() + 1) return false;
-  *output_bytes -= type.name.size() + 1;
-  memcpy(output, type.name.data(), type.name.size());
-  output += type.name.size();
-  *output = '{';
-  ++output;
-
-  bool first = true;
-  if (type.super_size == 8) {
-    size_t start_input_bytes = *input_bytes;
-
-    // Default value is -633437440.3735158
-    if (*output_bytes < 10) return false;
-    memcpy(output, "sendtime: ", 10);
-    output += 10;
-    *output_bytes -= 10;
-
-    size_t output_bytes_before = *output_bytes;
-    if (!PrintField(output, output_bytes, input, input_bytes, 0x5f372008u)) {
-      return false;
-    }
-    output += output_bytes_before - *output_bytes;
-    input = static_cast<const char *>(input) + type.super_size;
-    first = false;
-    AOS_CHECK(start_input_bytes == (*input_bytes + 8));
-  } else {
-    *input_bytes -= type.super_size;
-    input = static_cast<const char *>(input) + type.super_size;
-  }
-
-  for (int i = 0; i < type.number_fields; ++i) {
-    if (first) {
-      first = false;
-    } else {
-      if (*output_bytes < 2) return false;
-      *output_bytes -= 2;
-      *(output++) = ',';
-      *(output++) = ' ';
-    }
-
-    if (*output_bytes < type.fields[i]->name.size() + 1) return false;
-    *output_bytes -= type.fields[i]->name.size() + 1;
-    memcpy(output, type.fields[i]->name.data(), type.fields[i]->name.size());
-    output += type.fields[i]->name.size();
-    *(output++) = ':';
-
-    const size_t output_bytes_before = *output_bytes,
-                 input_bytes_before = *input_bytes;
-    const uint32_t type_id = type.fields[i]->type;
-    if (type.fields[i]->length > 0) {
-      if (!PrintArray(output, output_bytes, input, input_bytes, type_id,
-                      type.fields[i]->length)) {
-        return false;
-      }
-      // Ignore the trailing '\0' that the subcall put on.
-      *output_bytes += 1;
-    } else if (MessageType::IsPrimitive(type_id)) {
-      if (!PrintField(output, output_bytes, input, input_bytes, type_id)) {
-        return false;
-      }
-    } else {
-      if (!PrintMessage(output, output_bytes, input, input_bytes,
-                        type_cache::Get(type_id))) {
-        return false;
-      }
-      // Ignore the trailing '\0' that the subcall put on.
-      *output_bytes += 1;
-    }
-
-    // Update the input and output pointers.
-    output += output_bytes_before - *output_bytes;
-    input =
-        static_cast<const char *>(input) + input_bytes_before - *input_bytes;
-  }
-  if (*output_bytes < 2) return false;
-  *output_bytes -= 2;
-  *(output++) = '}';
-  *(output++) = '\0';
-  return true;
-}
-
-bool PrintMatrix(char *output, size_t *output_bytes, const void *input,
-                 uint32_t type_id, int rows, int cols) {
-  AOS_CHECK(MessageType::IsPrimitive(type_id));
-  const size_t element_size = MessageType::Sizeof(type_id);
-
-  if (*output_bytes < 1) return false;
-  *output_bytes -= 1;
-  *(output++) = '[';
-
-  bool first_row = true;
-  for (int row = 0; row < rows; ++row) {
-    if (first_row) {
-      first_row = false;
-    } else {
-      if (*output_bytes < 2) return false;
-      *output_bytes -= 2;
-      *(output++) = ',';
-      *(output++) = ' ';
-    }
-
-    if (*output_bytes < 1) return false;
-    *output_bytes -= 1;
-    *(output++) = '[';
-
-    bool first_col = true;
-    for (int col = 0; col < cols; ++col) {
-      if (first_col) {
-        first_col = false;
-      } else {
-        if (*output_bytes < 2) return false;
-        *output_bytes -= 2;
-        *(output++) = ',';
-        *(output++) = ' ';
-      }
-
-      const size_t output_bytes_before = *output_bytes;
-      size_t input_bytes = element_size;
-      if (!PrintField(output, output_bytes,
-                      static_cast<const char *>(input) +
-                          (row + col * rows) * element_size,
-                      &input_bytes, type_id)) {
-        return false;
-      }
-      AOS_CHECK_EQ(0u, input_bytes);
-      // Update the output pointer.
-      output += output_bytes_before - *output_bytes;
-    }
-
-    if (*output_bytes < 1) return false;
-    *output_bytes -= 1;
-    *(output++) = ']';
-  }
-  if (*output_bytes < 2) return false;
-  *output_bytes -= 2;
-  *(output++) = ']';
-  *(output++) = '\0';
-  return true;
-}
-
-void SerializeMatrix(int type_id, void *output_void, const void *input_void,
-                     int rows, int cols) {
-  char *const output = static_cast<char *>(output_void);
-  const char *const input = static_cast<const char *>(input_void);
-
-  AOS_CHECK(MessageType::IsPrimitive(type_id));
-  const size_t element_size = MessageType::Sizeof(type_id);
-
-  for (int i = 0; i < rows * cols; ++i) {
-    switch(element_size) {
-      case 1:
-        to_network<1>(&input[i * element_size], &output[i * element_size]);
-        break;
-      case 2:
-        to_network<2>(&input[i * element_size], &output[i * element_size]);
-        break;
-      case 4:
-        to_network<4>(&input[i * element_size], &output[i * element_size]);
-        break;
-      case 8:
-        to_network<8>(&input[i * element_size], &output[i * element_size]);
-        break;
-      default:
-        AOS_LOG(FATAL, "illegal primitive type size %zu\n", element_size);
-    }
-  }
-}
-
-namespace type_cache {
-namespace {
-
-struct CacheEntry {
-  const MessageType &type;
-  bool in_shm;
-
-  CacheEntry(const MessageType &type, bool in_shm)
-      : type(type), in_shm(in_shm) {}
-};
-
-struct ShmType {
-  uint32_t id;
-  volatile ShmType *next;
-
-  size_t serialized_size;
-  char serialized[];
-};
-
-::std::unordered_map<uint32_t, CacheEntry> cache;
-::aos::Mutex cache_lock;
-
-}  // namespace
-
-void Add(const MessageType &type) {
-  ::aos::MutexLocker locker(&cache_lock);
-  if (cache.count(type.id) == 0) {
-    cache.emplace(::std::piecewise_construct, ::std::forward_as_tuple(type.id),
-                  ::std::forward_as_tuple(type, false));
-  }
-}
-
-const MessageType &Get(uint32_t type_id) {
-  ::aos::MutexLocker locker(&cache_lock);
-
-  {
-    const auto cached = cache.find(type_id);
-    if (cached != cache.end()) {
-      return cached->second.type;
-    }
-  }
-
-  if (aos_core_is_init()) {
-    // No need to lock because the only thing that happens is somebody adds on
-    // to the end, and they shouldn't be adding the one we're looking for.
-    const volatile ShmType *c = static_cast<volatile ShmType *>(
-        global_core->mem_struct->queue_types.pointer);
-    while (c != nullptr) {
-      if (c->id == type_id) {
-        size_t bytes = c->serialized_size;
-        MessageType *type = MessageType::Deserialize(
-            const_cast<const char *>(c->serialized), &bytes);
-        cache.emplace(::std::piecewise_construct,
-                      ::std::forward_as_tuple(type_id),
-                      ::std::forward_as_tuple(*type, true));
-        return *type;
-      }
-      c = c->next;
-    }
-  } else {
-    AOS_LOG(INFO, "FYI: no shm. going to LOG(FATAL) now\n");
-  }
-
-  AOS_LOG(FATAL, "MessageType for id 0x%" PRIx32 " not found\n", type_id);
-}
-
-void AddShm(uint32_t type_id) {
-  if (!aos_core_is_init()) {
-    AOS_LOG(FATAL, "can't AddShm(%" PRIu32 ") without shm!\n", type_id);
-  }
-
-  const MessageType::Field **fields;
-  int number_fields;
-  {
-    ::aos::MutexLocker locker(&cache_lock);
-    CacheEntry &cached = cache.at(type_id);
-    if (cached.in_shm) return;
-
-    fields = cached.type.fields;
-    number_fields = cached.type.number_fields;
-
-    if (mutex_lock(&global_core->mem_struct->queue_types.lock) != 0) {
-      AOS_LOG(FATAL, "locking queue_types lock failed\n");
-    }
-    volatile ShmType *current = static_cast<volatile ShmType *>(
-        global_core->mem_struct->queue_types.pointer);
-    if (current != nullptr) {
-      while (true) {
-        if (current->id == type_id) {
-          cached.in_shm = true;
-          mutex_unlock(&global_core->mem_struct->queue_types.lock);
-          return;
-        }
-        if (current->next == nullptr) break;
-        current = current->next;
-      }
-    }
-    char buffer[1024];
-    ssize_t size = cached.type.Serialize(buffer, sizeof(buffer));
-    if (size == -1) {
-      AOS_LOG(FATAL, "type %s is too big to fit into %zd bytes\n",
-              cached.type.name.c_str(), sizeof(buffer));
-    }
-
-    volatile ShmType *shm =
-        static_cast<volatile ShmType *>(shm_malloc(sizeof(ShmType) + size));
-    shm->id = type_id;
-    shm->next = nullptr;
-    shm->serialized_size = size;
-    memcpy(const_cast<char *>(shm->serialized), buffer, size);
-
-    if (current == NULL) {
-      global_core->mem_struct->queue_types.pointer = const_cast<ShmType *>(shm);
-    } else {
-      current->next = shm;
-    }
-    mutex_unlock(&global_core->mem_struct->queue_types.lock);
-  }
-
-  for (int i = 0; i < number_fields; ++i) {
-    if (!MessageType::IsPrimitive(fields[i]->type)) {
-      AddShm(fields[i]->type);
-    }
-  }
-}
-
-}  // namespace type_cache
-}  // namespace aos
diff --git a/aos/queue_types.h b/aos/queue_types.h
deleted file mode 100644
index bff06bb..0000000
--- a/aos/queue_types.h
+++ /dev/null
@@ -1,148 +0,0 @@
-#ifndef AOS_QUEUE_TYPES_H_
-#define AOS_QUEUE_TYPES_H_
-
-#include <sys/types.h>
-#include <stdint.h>
-#include <string.h>
-
-#include <initializer_list>
-#include <string>
-
-#include "aos/macros.h"
-#include "aos/byteorder.h"
-
-namespace aos {
-
-// The type IDs this uses are 2 parts: a 16 bit size and a 16 bit hash. Sizes
-// for primitive types are stored with 8192 (0x2000) added.
-//
-// Serializing/deserializing includes all of the fields too.
-struct MessageType {
-  struct Field {
-    // The type ID for the type of this field.
-    uint32_t type;
-    // The length of the array if it is one or 0.
-    uint32_t length;
-    ::std::string name;
-  };
-
-  // Takes ownership of all the Field pointers in fields_initializer.
-  MessageType(size_t super_size, uint32_t id, const ::std::string &name,
-              ::std::initializer_list<const Field *> fields_initializer)
-      : super_size(super_size), id(id), name(name) {
-    number_fields = fields_initializer.size();
-    fields = new const Field *[number_fields];
-    int i = 0;
-    for (const Field *c : fields_initializer) {
-      fields[i++] = c;
-    }
-  }
-
-  ~MessageType() {
-    for (int i = 0; i < number_fields; ++i) {
-      delete fields[i];
-    }
-    delete[] fields;
-  }
-
-  // Returns -1 if max_bytes is too small.
-  ssize_t Serialize(char *buffer, size_t max_bytes) const;
-  // bytes should start out as the number of bytes available in buffer and gets
-  // reduced by the number actually read before returning.
-  // deserialize_length is whether to look for a length field in the serialized
-  // data.
-  // Returns a new instance allocated with new or nullptr for error.
-  static MessageType *Deserialize(const char *buffer, size_t *bytes,
-                                  bool deserialize_length = true);
-
-  static bool IsPrimitive(uint32_t type_id) {
-    return (type_id & 0x2000) != 0;
-  }
-
-  static unsigned int Sizeof(uint32_t type_id) {
-    if (IsPrimitive(type_id)) {
-      return (type_id & 0xFFFF) - 0x2000;
-    } else {
-      return type_id & 0xFFFF;
-    }
-  }
-
-  // How many (serialized) bytes the superclass takes up.
-  uint16_t super_size;
-  // The type ID for this.
-  uint32_t id;
-  ::std::string name;
-
-  uint16_t number_fields;
-  const Field **fields;
-
- private:
-  // Internal constructor for Deserialize to use.
-  MessageType(uint16_t super_size, uint32_t id, ::std::string &&name,
-              uint16_t number_fields, Field **fields)
-      : super_size(super_size),
-        id(id),
-        name(name),
-        number_fields(number_fields),
-        fields(const_cast<const Field **>(fields)) {
-    for (int i = 0; i < number_fields; ++i) {
-      fields[i] = new Field();
-    }
-  }
-
-  DISALLOW_COPY_AND_ASSIGN(MessageType);
-};
-
-// The arguments are the same for both of these.
-//
-// output is where to write the text representation ('\0'-terminated
-// human-readable string).
-// output_bytes should point to the number of bytes available to write in
-// output. It will be reduced by the number of bytes that were actually written.
-// input is where to read the data in from (in network byte order, aka from
-// Serialize).
-// input_bytes should point to the number of bytes available to read from input.
-// It will be reduced by the number of bytes that were actually read.
-// type is which type to print.
-// Returns true for success and false for not.
-//
-// Prints the value from 1 primitive message field into output.
-// The implementation of this is generated by the ruby code.
-// Does not include a trailing '\0' in what it subtracts from *output_bytes.
-bool PrintField(char *output, size_t *output_bytes, const void *input,
-                size_t *input_bytes, uint32_t type)
-    __attribute__((warn_unused_result));
-// Prints a whole message into output.
-// This calls itself recursively and PrintField to print out the whole thing.
-bool PrintMessage(char *output, size_t *output_bytes, const void *input,
-                  size_t *input_bytes, const MessageType &type)
-    __attribute__((warn_unused_result));
-// Calls PrintField to print out a matrix of values.
-bool PrintMatrix(char *output, size_t *output_bytes, const void *input,
-                 uint32_t type, int rows, int cols);
-
-// "Serializes" a matrix (basically just converts to network byte order). The
-// result can be passed to PrintMatrix.
-void SerializeMatrix(int type_id, void *output_void, const void *input_void,
-                     int rows, int cols);
-
-// Implements a cache of types which generally works per-process but can (when
-// instructed) put a type in shared memory which other processes will
-// automatically be able to retrieve.
-// All of these functions are thread-safe.
-namespace type_cache {
-
-// Makes sure a type is in the type cache. This will store a reference to type.
-// The types of any non-primitive fields of type must already be added.
-void Add(const MessageType &type);
-// Retrieves a type from the type cache or shm. LOG(FATAL)s if it can't find it.
-const MessageType &Get(uint32_t type_id);
-// Makes sure a type is in the list in shm. Add must have already been called
-// for type.
-// Also adds the types of any non-primitive fields of type.
-void AddShm(uint32_t type_id);
-
-}  // namespace type_cache
-}  // namespace aos
-
-#endif  // AOS_QUEUE_TYPES_H_
diff --git a/aos/queue_types_test.cc b/aos/queue_types_test.cc
deleted file mode 100644
index 6503f02..0000000
--- a/aos/queue_types_test.cc
+++ /dev/null
@@ -1,274 +0,0 @@
-#include "aos/queue_types.h"
-
-#include <memory>
-#include <limits>
-#include <string>
-
-#include "gtest/gtest.h"
-
-#include "aos/test_queue.q.h"
-#include "aos/byteorder.h"
-#include "aos/queue_primitives.h"
-#include "aos/logging/logging.h"
-#include "aos/testing/test_logging.h"
-
-using ::aos::common::testing::Structure;
-using ::aos::common::testing::MessageWithStructure;
-using ::aos::common::testing::OtherTestingMessage;
-using ::aos::common::testing::MessageWithArrays;
-
-namespace aos {
-namespace testing {
-
-typedef MessageType::Field Field;
-
-static const MessageType kTestType1(5, 0x1234, "TestType1",
-                                    {new Field{0, 0, "field1"},
-                                     new Field{0, 0, "field2"},
-                                     new Field{0, 0, "field3"}});
-
-class QueueTypesTest : public ::testing::Test {
- public:
-  QueueTypesTest() {
-    ::aos::testing::EnableTestLogging();
-  }
-
-  ::testing::AssertionResult Equal(const MessageType &l, const MessageType &r) {
-    using ::testing::AssertionFailure;
-    if (l.id != r.id) {
-      return AssertionFailure() << "id " << l.id << " != " << r.id;
-    }
-    if (l.name != r.name) {
-      return AssertionFailure() << "name '" << l.name << "' != '" << r.name
-                                << "'";
-    }
-    if (l.number_fields != r.number_fields) {
-      return AssertionFailure() << "number_fields " << l.number_fields
-                                << " != " << r.number_fields;
-    }
-    for (int i = 0; i < l.number_fields; ++i) {
-      SCOPED_TRACE("field " + ::std::to_string(i));
-      if (l.fields[i]->type != r.fields[i]->type) {
-        return AssertionFailure() << "type " << l.fields[i]->type
-                                  << " != " << r.fields[i]->type;
-      }
-      if (l.fields[i]->name != r.fields[i]->name) {
-        return AssertionFailure() << "name '" << l.fields[i]->name << "' != '"
-                                  << r.fields[i]->name << "'";
-      }
-    }
-    return ::testing::AssertionSuccess();
-  }
-};
-
-TEST_F(QueueTypesTest, Serialization) {
-  char buffer[512];
-  ssize_t size;
-  size_t out_size;
-  ::std::unique_ptr<MessageType> deserialized;
-
-  size = kTestType1.Serialize(buffer, sizeof(buffer));
-  ASSERT_GT(size, 1);
-  ASSERT_LE(static_cast<size_t>(size), sizeof(buffer));
-
-  out_size = size;
-  deserialized.reset(MessageType::Deserialize(buffer, &out_size));
-  EXPECT_EQ(0u, out_size);
-  EXPECT_TRUE(Equal(kTestType1, *deserialized));
-
-  out_size = size - 1;
-  deserialized.reset(MessageType::Deserialize(buffer, &out_size));
-  EXPECT_EQ(nullptr, deserialized.get());
-
-  out_size = size + 1;
-  ASSERT_LE(out_size, sizeof(buffer));
-  deserialized.reset(MessageType::Deserialize(buffer, &out_size));
-  EXPECT_EQ(1u, out_size);
-  EXPECT_TRUE(Equal(kTestType1, *deserialized));
-}
-
-class PrintMessageTest : public ::testing::Test {
- public:
-  char input[512], output[512];
-  size_t input_bytes, output_bytes;
-};
-
-class PrintFieldTest : public PrintMessageTest {
- public:
-  template <typename T>
-  void TestInteger(T value, ::std::string result) {
-    input_bytes = sizeof(value);
-    to_network(&value, input);
-    output_bytes = sizeof(output);
-    ASSERT_TRUE(
-        PrintField(output, &output_bytes, input, &input_bytes, TypeID<T>::id));
-    EXPECT_EQ(0u, input_bytes);
-    EXPECT_EQ(sizeof(output) - result.size(), output_bytes);
-    EXPECT_EQ(result, ::std::string(output, sizeof(output) - output_bytes));
-  }
-
-  template <typename T>
-  void TestAllIntegers(T multiple) {
-    for (T i = ::std::numeric_limits<T>::min();
-         i < ::std::numeric_limits<T>::max() - multiple; i += multiple) {
-      TestInteger<T>(i, ::std::to_string(i));
-    }
-  }
-};
-
-TEST_F(PrintFieldTest, Basic) {
-  TestInteger<uint16_t>(971, "971");
-  TestInteger<uint8_t>(8, "8");
-  TestInteger<uint8_t>(254, "254");
-  TestInteger<uint8_t>(0, "0");
-  TestInteger<int8_t>(254, "-2");
-  TestInteger<int8_t>(67, "67");
-  TestInteger<int8_t>(0, "0");
-
-  input_bytes = 1;
-  input[0] = 1;
-  output_bytes = sizeof(output);
-  ASSERT_TRUE(PrintField(output, &output_bytes, input, &input_bytes,
-                         queue_primitive_types::bool_p));
-  EXPECT_EQ(0u, input_bytes);
-  EXPECT_EQ(sizeof(output) - 1, output_bytes);
-  EXPECT_EQ(::std::string("T"),
-            ::std::string(output, sizeof(output) - output_bytes));
-
-  input_bytes = 1;
-  input[0] = 0;
-  output_bytes = sizeof(output);
-  ASSERT_TRUE(PrintField(output, &output_bytes, input, &input_bytes,
-                         queue_primitive_types::bool_p));
-  EXPECT_EQ(0u, input_bytes);
-  EXPECT_EQ(sizeof(output) - 1, output_bytes);
-  EXPECT_EQ(::std::string("f"),
-            ::std::string(output, sizeof(output) - output_bytes));
-}
-
-// Runs through lots of integers and makes sure PrintField gives the same result
-// as ::std::to_string.
-TEST_F(PrintFieldTest, Integers) {
-  TestAllIntegers<uint8_t>(1);
-  TestAllIntegers<int8_t>(1);
-  TestAllIntegers<uint16_t>(1);
-  TestAllIntegers<int16_t>(3);
-  TestAllIntegers<uint32_t>(43129);
-  TestAllIntegers<int32_t>(654321);
-  TestAllIntegers<uint64_t>(123456789101112);
-  TestAllIntegers<int64_t>(91011121249856532);
-}
-
-// Tests PrintField with trailing input bytes and only 1 extra output byte.
-TEST_F(PrintFieldTest, OtherSizes) {
-  static const float kData = 16.78;
-  static const ::std::string kString("16.780001");
-  static const size_t kExtraInputBytes = 4;
-  input_bytes = sizeof(kData) + kExtraInputBytes;
-  to_network(&kData, input);
-  output_bytes = kString.size() + 1;
-  ASSERT_LE(output_bytes, sizeof(output));
-  ASSERT_TRUE(PrintField(output, &output_bytes, input, &input_bytes,
-                         Structure::GetType()->fields[2]->type));
-  EXPECT_EQ(kExtraInputBytes, input_bytes);
-  EXPECT_EQ(1u, output_bytes);
-  EXPECT_EQ(kString, ::std::string(output));
-}
-
-TEST_F(PrintFieldTest, InputTooSmall) {
-  static const float kData = 0;
-  input_bytes = sizeof(kData) - 1;
-  output_bytes = sizeof(output);
-  EXPECT_FALSE(PrintField(output, &output_bytes, input, &input_bytes,
-                          Structure::GetType()->fields[2]->type));
-}
-
-TEST_F(PrintFieldTest, OutputTooSmall) {
-  static const uint16_t kData = 12345;
-  input_bytes = sizeof(input);
-  to_network(&kData, input);
-  output_bytes = 4;
-  EXPECT_FALSE(PrintField(output, &output_bytes, input, &input_bytes,
-                          Structure::GetType()->fields[1]->type));
-}
-
-static const OtherTestingMessage kTestMessage1(true, 8971, 3.2);
-static const ::std::string kTestMessage1String =
-    ".aos.common.testing.OtherTestingMessage{sendtime: -633437440.3735158s, test_bool:T, test_int:8971"
-    ", test_double:3.200000}";
-static const Structure kTestStructure1(false, 973, 8.56);
-static const ::std::string kTestStructure1String =
-    ".aos.common.testing.Structure{struct_bool:f, struct_int:973, "
-    "struct_float:8.560000}";
-static const ::aos::common::testing::Structure kStructureValue(true, 973, 3.14);
-static const MessageWithArrays kTestMessageWithArrays({{971, 254, 1678}},
-                                                      {{kStructureValue,
-                                                        kStructureValue}});
-static const ::std::string kTestMessageWithArraysString =
-    ".aos.common.testing.MessageWithArrays{sendtime: -633437440.3735158s, test_int:[971, 254, 1678], "
-    "test_struct:[.aos.common.testing.Structure{struct_bool:T, struct_int:973, "
-    "struct_float:3.140000}, .aos.common.testing.Structure{struct_bool:T, "
-    "struct_int:973, struct_float:3.140000}]}";
-
-TEST_F(PrintMessageTest, Basic) {
-  ASSERT_GE(sizeof(input), kTestMessage1.Size());
-  input_bytes = kTestMessage1.Serialize(input);
-  output_bytes = sizeof(output);
-  ASSERT_TRUE(PrintMessage(output, &output_bytes, input, &input_bytes,
-                           *kTestMessage1.GetType()));
-  EXPECT_EQ(kTestMessage1String, ::std::string(output));
-  EXPECT_EQ(kTestMessage1String.size() + 1, sizeof(output) - output_bytes);
-}
-
-TEST_F(PrintMessageTest, OutputTooSmall) {
-  ASSERT_GE(sizeof(input), kTestMessage1.Size());
-  input_bytes = kTestMessage1.Serialize(input);
-  output_bytes = kTestMessage1String.size();
-  EXPECT_FALSE(PrintMessage(output, &output_bytes, input, &input_bytes,
-                           *kTestMessage1.GetType()));
-}
-
-TEST_F(PrintMessageTest, InputTooSmall) {
-  input_bytes = kTestMessage1.Size() - 1;
-  output_bytes = sizeof(output);
-  EXPECT_FALSE(PrintMessage(output, &output_bytes, input, &input_bytes,
-                           *kTestMessage1.GetType()));
-}
-
-TEST_F(PrintMessageTest, Structure) {
-  ASSERT_GE(sizeof(input), kTestStructure1.Size());
-  input_bytes = kTestStructure1.Serialize(input);
-  output_bytes = sizeof(output);
-  ASSERT_TRUE(PrintMessage(output, &output_bytes, input, &input_bytes,
-                           *kTestStructure1.GetType()));
-  EXPECT_EQ(kTestStructure1String, ::std::string(output));
-  EXPECT_EQ(kTestStructure1String.size() + 1, sizeof(output) - output_bytes);
-}
-
-TEST_F(PrintMessageTest, Matrix) {
-  static const uint16_t kTestMatrix[] = {971, 254, 1768, 8971, 9971, 973};
-  uint16_t test_matrix[sizeof(kTestMatrix) / sizeof(kTestMatrix[0])];
-  SerializeMatrix(queue_primitive_types::uint16_t_p, test_matrix, kTestMatrix,
-                  3, 2);
-  static const ::std::string kOutput =
-      "[[971, 8971], [254, 9971], [1768, 973]]";
-  output_bytes = sizeof(output);
-  ASSERT_TRUE(PrintMatrix(output, &output_bytes, test_matrix,
-                          queue_primitive_types::uint16_t_p, 3, 2));
-  EXPECT_EQ(kOutput, ::std::string(output));
-  EXPECT_EQ(kOutput.size() + 1, sizeof(output) - output_bytes);
-}
-
-TEST_F(PrintMessageTest, Array) {
-  ASSERT_GE(sizeof(input), kTestMessageWithArrays.Size());
-  input_bytes = kTestMessageWithArrays.Serialize(input);
-  output_bytes = sizeof(output);
-  ASSERT_TRUE(PrintMessage(output, &output_bytes, input, &input_bytes,
-                           *kTestMessageWithArrays.GetType()));
-  EXPECT_EQ(kTestMessageWithArraysString, ::std::string(output));
-  EXPECT_EQ(kTestMessageWithArraysString.size() + 1,
-            sizeof(output) - output_bytes);
-}
-
-}  // namespace testing
-}  // namespace aos
diff --git a/aos/realtime.cc b/aos/realtime.cc
new file mode 100644
index 0000000..6a80550
--- /dev/null
+++ b/aos/realtime.cc
@@ -0,0 +1,127 @@
+#include "aos/realtime.h"
+
+#include <stdio.h>
+#include <string.h>
+#include <sys/mman.h>
+#include <errno.h>
+#include <sched.h>
+#include <sys/resource.h>
+#include <sys/types.h>
+#include <unistd.h>
+#include <stdlib.h>
+#include <stdint.h>
+#include <sys/prctl.h>
+#include <malloc.h>
+
+#include "glog/logging.h"
+
+namespace FLAG__namespace_do_not_use_directly_use_DECLARE_double_instead {
+extern double FLAGS_tcmalloc_release_rate __attribute__((weak));
+}
+using FLAG__namespace_do_not_use_directly_use_DECLARE_double_instead::
+    FLAGS_tcmalloc_release_rate;
+
+namespace aos {
+namespace logging {
+namespace internal {
+
+// Implemented in aos/logging/context.cc.
+void ReloadThreadName() __attribute__((weak));
+
+}  // namespace internal
+}  // namespace logging
+
+namespace {
+
+void SetSoftRLimit(int resource, rlim64_t soft, bool set_for_root) {
+  bool am_root = getuid() == 0;
+  if (set_for_root || !am_root) {
+    struct rlimit64 rlim;
+    PCHECK(getrlimit64(resource, &rlim) == 0)
+        << ": " << program_invocation_short_name << "-init: getrlimit64("
+        << resource << ") failed";
+
+    rlim.rlim_cur = soft;
+    rlim.rlim_max = ::std::max(rlim.rlim_max, soft);
+
+    PCHECK(setrlimit64(resource, &rlim) == 0)
+        << ": " << program_invocation_short_name << "-init: setrlimit64("
+        << resource << ", {cur=" << (uintmax_t)rlim.rlim_cur
+        << ",max=" << (uintmax_t)rlim.rlim_max << "}) failed";
+  }
+}
+
+}  // namespace
+
+void LockAllMemory() {
+  // Allow locking as much as we want into RAM.
+  SetSoftRLimit(RLIMIT_MEMLOCK, RLIM_INFINITY, false);
+
+  WriteCoreDumps();
+  PCHECK(mlockall(MCL_CURRENT | MCL_FUTURE) == 0)
+      << ": " << program_invocation_short_name << "-init: mlockall failed";
+
+  // Don't give freed memory back to the OS.
+  CHECK_EQ(1, mallopt(M_TRIM_THRESHOLD, -1));
+  // Don't use mmap for large malloc chunks.
+  CHECK_EQ(1, mallopt(M_MMAP_MAX, 0));
+
+  if (&FLAGS_tcmalloc_release_rate) {
+    // Tell tcmalloc not to return memory.
+    FLAGS_tcmalloc_release_rate = 0.0;
+  }
+
+  // Forces the memory pages for all the stack space that we're ever going to
+  // use to be loaded into memory (so it can be locked there).
+  uint8_t data[4096 * 8];
+  // Not 0 because linux might optimize that to a 0-filled page.
+  memset(data, 1, sizeof(data));
+
+  static const size_t kHeapPreallocSize = 512 * 1024;
+  char *const heap_data = static_cast<char *>(malloc(kHeapPreallocSize));
+  memset(heap_data, 1, kHeapPreallocSize);
+  free(heap_data);
+}
+
+void InitRT() {
+  LockAllMemory();
+
+  // Only let rt processes run for 3 seconds straight.
+  SetSoftRLimit(RLIMIT_RTTIME, 3000000, true);
+
+  // Allow rt processes up to priority 40.
+  SetSoftRLimit(RLIMIT_RTPRIO, 40, false);
+}
+
+void UnsetCurrentThreadRealtimePriority() {
+  struct sched_param param;
+  param.sched_priority = 0;
+  PCHECK(sched_setscheduler(0, SCHED_OTHER, &param) == 0)
+      << ": sched_setscheduler(0, SCHED_OTHER, 0) failed";
+}
+
+void SetCurrentThreadName(const ::std::string &name) {
+  CHECK_LE(name.size(), 16u) << ": thread name '" << name << "' too long";
+  VLOG(1) << "This thread is changing to '" << name << "'";
+  PCHECK(prctl(PR_SET_NAME, name.c_str()) == 0);
+  if (&logging::internal::ReloadThreadName != nullptr) {
+    logging::internal::ReloadThreadName();
+  }
+}
+
+void SetCurrentThreadRealtimePriority(int priority) {
+  // Make sure we will only be allowed to run for 3 seconds straight.
+  SetSoftRLimit(RLIMIT_RTTIME, 3000000, true);
+
+  struct sched_param param;
+  param.sched_priority = priority;
+  PCHECK(sched_setscheduler(0, SCHED_FIFO, &param) == 0)
+      << ": sched_setscheduler(0, SCHED_FIFO, " << priority << ") failed";
+}
+
+void WriteCoreDumps() {
+  // Do create core files of unlimited size.
+  SetSoftRLimit(RLIMIT_CORE, RLIM_INFINITY, true);
+}
+
+}  // namespace aos
diff --git a/aos/realtime.h b/aos/realtime.h
new file mode 100644
index 0000000..a6b4223
--- /dev/null
+++ b/aos/realtime.h
@@ -0,0 +1,33 @@
+#ifndef AOS_REALTIME_H_
+#define AOS_REALTIME_H_
+
+#include <string>
+
+namespace aos {
+
+// Locks everything into memory and sets the limits.  This plus InitNRT are
+// everything you need to do before SetCurrentThreadRealtimePriority will make
+// your thread RT.  Called as part of ShmEventLoop::Run()
+void InitRT();
+
+// Sets the current thread back down to non-realtime priority.
+void UnsetCurrentThreadRealtimePriority();
+
+// Sets the name of the current thread.
+// This will displayed by `top -H`, dump_rtprio, and show up in logs.
+// name can have a maximum of 16 characters.
+void SetCurrentThreadName(const ::std::string &name);
+
+// Sets the current thread's realtime priority.
+void SetCurrentThreadRealtimePriority(int priority);
+
+// Sets up this process to write core dump files.
+// This is called by Init*, but it's here for other files that want this
+// behavior without calling Init*.
+void WriteCoreDumps();
+
+void LockAllMemory();
+
+}  // namespace aos
+
+#endif  // AOS_REALTIME_H_
diff --git a/aos/robot_state/BUILD b/aos/robot_state/BUILD
index e392c56..5a9c255 100644
--- a/aos/robot_state/BUILD
+++ b/aos/robot_state/BUILD
@@ -1,10 +1,26 @@
-package(default_visibility = ['//visibility:public'])
+package(default_visibility = ["//visibility:public"])
 
-load('//aos/build:queues.bzl', 'queue_library')
+load("//aos:config.bzl", "aos_config")
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
 
-queue_library(
-  name = 'robot_state',
-  srcs = [
-    'robot_state.q',
-  ],
+flatbuffer_cc_library(
+    name = "robot_state_fbs",
+    srcs = ["robot_state.fbs"],
+    gen_reflections = 1,
+)
+
+flatbuffer_cc_library(
+    name = "joystick_state_fbs",
+    srcs = ["joystick_state.fbs"],
+    gen_reflections = 1,
+)
+
+aos_config(
+    name = "config",
+    src = "robot_state_config.json",
+    flatbuffers = [
+        "//aos/robot_state:joystick_state_fbs",
+        "//aos/robot_state:robot_state_fbs",
+    ],
+    visibility = ["//visibility:public"],
 )
diff --git a/aos/robot_state/joystick_state.fbs b/aos/robot_state/joystick_state.fbs
new file mode 100644
index 0000000..f21b211
--- /dev/null
+++ b/aos/robot_state/joystick_state.fbs
@@ -0,0 +1,41 @@
+namespace aos;
+
+table Joystick {
+  // A bitmask of the butotn state.
+  buttons:ushort;
+
+  // The 6 joystick axes.
+  // TODO: Should have size of 6
+  axis:[double];
+
+  // The POV axis.
+  pov:int;
+}
+
+// This message is checked by all control loops to make sure that the
+// joystick code hasn't died.  It is published on "/aos"
+table JoystickState {
+  //TODO: should have fixed size.
+  joysticks:[Joystick];
+
+  test_mode:bool;
+  fms_attached:bool;
+  enabled:bool;
+  autonomous:bool;
+  team_id:ushort;
+
+  // 2018 scale and switch positions.
+  // TODO(austin): Push these out to a new message?
+  switch_left:bool;
+  scale_left:bool;
+
+  // If this is true, then this message isn't actually from the control
+  // system and so should not be trusted as evidence that the button inputs
+  // etc are actually real and should be acted on.
+  // However, most things should ignore this so that sending fake messages is
+  // useful for testing. The only difference in behavior should be motors not
+  // actually turning on.
+  fake:bool;
+}
+
+root_type JoystickState;
diff --git a/aos/robot_state/robot_state.fbs b/aos/robot_state/robot_state.fbs
new file mode 100644
index 0000000..437cfd7
--- /dev/null
+++ b/aos/robot_state/robot_state.fbs
@@ -0,0 +1,35 @@
+namespace aos;
+
+// This message is sent out on this queue when sensors are read. It contains
+// global robot state and information about whether the process reading sensors
+// has been restarted, along with all counters etc it keeps track of.  It is
+// published on "/aos"
+table RobotState {
+  // The PID of the process reading sensors.
+  // This is here so control loops can tell when it changes.
+  reader_pid:int;
+
+  // True when outputs are enabled.
+  // Motor controllers keep going for a bit after this goes to false.
+  outputs_enabled:bool;
+  // Indicates whether something is browned out (I think motor controller
+  // outputs). IMPORTANT: This is NOT !outputs_enabled. outputs_enabled goes to
+  // false for other reasons too (disabled, e-stopped, maybe more).
+  browned_out:bool;
+
+  // Whether the two sensor rails are currently working.
+  is_3v3_active:bool;
+  is_5v_active:bool;
+  // The current voltages measured on the two sensor rails.
+  voltage_3v3:double;
+  voltage_5v:double;
+
+  // The input voltage to the roboRIO.
+  voltage_roborio_in:double;
+
+  // From the DriverStation object, aka what FMS sees and what shows up on the
+  // actual driver's station.
+  voltage_battery:double;
+}
+
+root_type RobotState;
diff --git a/aos/robot_state/robot_state.q b/aos/robot_state/robot_state.q
deleted file mode 100644
index e482c5d..0000000
--- a/aos/robot_state/robot_state.q
+++ /dev/null
@@ -1,70 +0,0 @@
-package aos;
-
-struct Joystick {
-  // A bitmask of the button state.
-  uint16_t buttons;
-
-  // The 6 joystick axes.
-  double[6] axis;
-
-  // The POV axis.
-  int32_t pov;
-};
-
-// This message is checked by all control loops to make sure that the
-// joystick code hasn't died.  It is published on ".aos.joystick_state"
-message JoystickState {
-  Joystick[6] joysticks;
-
-  bool test_mode;
-  bool fms_attached;
-  bool enabled;
-  bool autonomous;
-  uint16_t team_id;
-
-  // 2018 scale and switch positions.
-  // TODO(austin): Push these out to a new message?
-  bool switch_left;
-  bool scale_left;
-
-  // If this is true, then this message isn't actually from the control
-  // system and so should not be trusted as evidence that the button inputs
-  // etc are actually real and should be acted on.
-  // However, most things should ignore this so that sending fake messages is
-  // useful for testing. The only difference in behavior should be motors not
-  // actually turning on.
-  bool fake;
-};
-
-// This message is sent out on this queue when sensors are read. It contains
-// global robot state and information about whether the process reading sensors
-// has been restarted, along with all counters etc it keeps track of.  It is
-// published on ".aos.robot_state"
-message RobotState {
-  // The PID of the process reading sensors.
-  // This is here so control loops can tell when it changes.
-  int32_t reader_pid;
-
-  // True when outputs are enabled.
-  // Motor controllers keep going for a bit after this goes to false.
-  bool outputs_enabled;
-  // Indicates whether something is browned out (I think motor controller
-  // outputs). IMPORTANT: This is NOT !outputs_enabled. outputs_enabled goes to
-  // false for other reasons too (disabled, e-stopped, maybe more).
-  bool browned_out;
-
-  // Whether the two sensor rails are currently working.
-  bool is_3v3_active;
-  bool is_5v_active;
-  // The current voltages measured on the two sensor rails.
-  double voltage_3v3;
-  double voltage_5v;
-
-  // The input voltage to the roboRIO.
-  double voltage_roborio_in;
-
-  // From the DriverStation object, aka what FMS sees and what shows up on the
-  // actual driver's station.
-  double voltage_battery;
-};
-
diff --git a/aos/robot_state/robot_state_config.json b/aos/robot_state/robot_state_config.json
new file mode 100644
index 0000000..0b2a5cc
--- /dev/null
+++ b/aos/robot_state/robot_state_config.json
@@ -0,0 +1,15 @@
+{
+  "channels":
+  [
+    {
+      "name": "/aos",
+      "type": "aos.JoystickState",
+      "frequency": 75
+    },
+    {
+      "name": "/aos",
+      "type": "aos.RobotState",
+      "frequency": 200
+    }
+  ]
+}
diff --git a/aos/scoped/BUILD b/aos/scoped/BUILD
index f5b3832..1ec0f1b 100644
--- a/aos/scoped/BUILD
+++ b/aos/scoped/BUILD
@@ -9,6 +9,7 @@
         "scoped_fd.h",
     ],
     deps = [
-        "//aos/logging",
+        "//aos:macros",
+        "@com_github_google_glog//:glog",
     ],
 )
diff --git a/aos/scoped/scoped_fd.cc b/aos/scoped/scoped_fd.cc
index 74f8882..846736d 100644
--- a/aos/scoped/scoped_fd.cc
+++ b/aos/scoped/scoped_fd.cc
@@ -1,13 +1,13 @@
 #include "aos/scoped/scoped_fd.h"
 
-#include "aos/logging/logging.h"
+#include "glog/logging.h"
 
 namespace aos {
 
 void ScopedFD::Close() {
   if (fd_ != -1) {
     if (close(fd_) == -1) {
-      AOS_PLOG(WARNING, "close(%d) failed", fd_);
+      PLOG(WARNING) << "close(" << fd_ << ") failed";
     }
   }
 }
diff --git a/aos/test_queue.q b/aos/test_queue.q
deleted file mode 100644
index 827b607..0000000
--- a/aos/test_queue.q
+++ /dev/null
@@ -1,38 +0,0 @@
-package aos.common.testing;
-
-struct Structure {
-  bool struct_bool;
-  uint16_t struct_int;
-  float struct_float;
-};
-
-message MessageWithStructure {
-  bool other_member;
-  Structure struct1;
-  Structure struct2;
-};
-
-message TestingMessage {
-  bool test_bool;
-  int32_t test_int;
-};
-
-message OtherTestingMessage {
-  bool test_bool;
-  int32_t test_int;
-  double test_double;
-};
-
-message MessageWithArrays {
-  uint16_t[3] test_int;
-  Structure[2] test_struct;
-};
-
-queue TestingMessage test_queue;
-
-queue_group TwoQueues {
-  queue TestingMessage first;
-  queue OtherTestingMessage second;
-};
-
-queue_group TwoQueues test_queuegroup;
diff --git a/aos/testdata/backwards.json b/aos/testdata/backwards.json
new file mode 100644
index 0000000..192005e
--- /dev/null
+++ b/aos/testdata/backwards.json
@@ -0,0 +1,13 @@
+{
+  "channels": [
+    {
+      "name": ".aos.robot_state",
+      "type": "aos.RobotState",
+      "max_size": 5
+    },
+    {
+      "name": ".aos.joystick_state",
+      "type": "aos.JoystickState"
+    }
+  ]
+}
diff --git a/aos/testing/BUILD b/aos/testing/BUILD
index 0c214ed..99a3569 100644
--- a/aos/testing/BUILD
+++ b/aos/testing/BUILD
@@ -6,9 +6,9 @@
     ],
     visibility = ["//visibility:public"],
     deps = [
-        "//third_party/googletest:gtest",
         "@com_github_gflags_gflags//:gflags",
         "@com_github_google_glog//:glog",
+        "@com_google_googletest//:gtest",
     ],
 )
 
@@ -53,7 +53,7 @@
     ],
     visibility = ["//visibility:public"],
     deps = [
-        "//aos/logging",
+        "@com_github_google_glog//:glog",
     ],
 )
 
@@ -69,7 +69,7 @@
     visibility = ["//visibility:public"],
     deps = [
         ":test_logging",
-        "//aos:queues",
+        "//aos/ipc_lib:queue",
         "//aos/ipc_lib:shared_mem",
         "//aos/logging",
     ],
diff --git a/aos/testing/gtest_main.cc b/aos/testing/gtest_main.cc
index c8c5062..52159c3 100644
--- a/aos/testing/gtest_main.cc
+++ b/aos/testing/gtest_main.cc
@@ -25,6 +25,7 @@
   FLAGS_logtostderr = true;
   google::InitGoogleLogging(argv[0]);
   ::gflags::ParseCommandLineFlags(&argc, &argv, false);
+  google::InstallFailureSignalHandler();
 
   if (FLAGS_print_logs) {
     if (::aos::testing::ForcePrintLogsDuringTests) {
diff --git a/aos/testing/prevent_exit.cc b/aos/testing/prevent_exit.cc
index ed6644b..8624c93 100644
--- a/aos/testing/prevent_exit.cc
+++ b/aos/testing/prevent_exit.cc
@@ -3,7 +3,7 @@
 #include <stdlib.h>
 #include <unistd.h>
 
-#include "aos/logging/logging.h"
+#include "glog/logging.h"
 
 namespace aos {
 namespace testing {
@@ -16,7 +16,7 @@
 }  // namespace
 
 void PreventExit() {
-  AOS_CHECK_EQ(atexit(TerminateExitHandler), 0);
+  CHECK_EQ(atexit(TerminateExitHandler), 0);
 }
 
 }  // namespace testing
diff --git a/aos/testing/test_shm.cc b/aos/testing/test_shm.cc
index e9a637a..b1c3848 100644
--- a/aos/testing/test_shm.cc
+++ b/aos/testing/test_shm.cc
@@ -2,7 +2,7 @@
 
 #include <sys/mman.h>
 
-#include "aos/queue.h"
+#include "aos/ipc_lib/queue.h"
 #include "aos/logging/logging.h"
 #include "aos/testing/test_logging.h"
 
diff --git a/aos/time/BUILD b/aos/time/BUILD
index e08ef7b..619642e 100644
--- a/aos/time/BUILD
+++ b/aos/time/BUILD
@@ -11,7 +11,6 @@
     visibility = ["//visibility:public"],
     deps = [
         "//aos:macros",
-        "//aos/ipc_lib:shared_mem",
         "//aos/mutex",
         "//aos/type_traits",
         "@com_github_google_glog//:glog",
diff --git a/aos/time/time.cc b/aos/time/time.cc
index 9736009..6c2d254 100644
--- a/aos/time/time.cc
+++ b/aos/time/time.cc
@@ -8,10 +8,6 @@
 
 #ifdef __linux__
 
-// We only use global_core from here, which is weak, so we don't really have a
-// dependency on it.
-#include "aos/ipc_lib/shared_mem.h"
-
 #include "aos/mutex/mutex.h"
 #include "glog/logging.h"
 
@@ -103,15 +99,6 @@
   SetMockTime(monotonic_clock::now() + amount);
 }
 
-void OffsetToNow(monotonic_clock::time_point now) {
-  CHECK_NOTNULL(&global_core);
-  CHECK_NOTNULL(global_core);
-  CHECK_NOTNULL(global_core->mem_struct);
-  const auto offset = now - monotonic_clock::now();
-  global_core->mem_struct->time_offset =
-      chrono::duration_cast<chrono::nanoseconds>(offset).count();
-}
-
 #endif  // __linux__
 
 struct timespec to_timespec(
@@ -150,14 +137,8 @@
       << ": clock_gettime(" << static_cast<uintmax_t>(CLOCK_MONOTONIC) << ", "
       << &current_time << ") failed";
 
-  const chrono::nanoseconds offset =
-      (&global_core == nullptr || global_core == nullptr ||
-       global_core->mem_struct == nullptr)
-          ? chrono::nanoseconds(0)
-          : chrono::nanoseconds(global_core->mem_struct->time_offset);
-
   return time_point(::std::chrono::seconds(current_time.tv_sec) +
-                    ::std::chrono::nanoseconds(current_time.tv_nsec)) + offset;
+                    ::std::chrono::nanoseconds(current_time.tv_nsec));
 
 #else  // __linux__
 
diff --git a/aos/time/time.h b/aos/time/time.h
index 469534f..881f0f1 100644
--- a/aos/time/time.h
+++ b/aos/time/time.h
@@ -82,14 +82,6 @@
 // Disables mocking time.
 void DisableMockTime();
 
-// Sets the global offset for all times so monotonic_clock::now() will return
-// now.
-// There is no synchronization here, so this is only safe when only a single
-// task is running.
-// This is only allowed when the shared memory core infrastructure has been
-// initialized in this process.
-void OffsetToNow(const monotonic_clock::time_point now);
-
 // Construct a time representing the period of hertz.
 constexpr ::std::chrono::nanoseconds FromRate(int hertz) {
   return ::std::chrono::duration_cast<::std::chrono::nanoseconds>(
diff --git a/aos/type_traits/type_traits.h b/aos/type_traits/type_traits.h
index 437cb3e..45268d5 100644
--- a/aos/type_traits/type_traits.h
+++ b/aos/type_traits/type_traits.h
@@ -12,8 +12,10 @@
 // 4.6 seems like a reasonable place to switch.
 #if ((__GNUC__ < 4) || (__GNUC__ == 4 && __GNUC_MINOR__ < 6)) && !defined(__clang__)
     ::std::has_trivial_assign<Tp>::value> {};
-#else
+#elif (__clang_major__ < 5)
     ::std::has_trivial_copy_assign<Tp>::value> {};
+#else
+    ::std::is_trivially_copy_assignable<Tp>::value> {};
 #endif
 
 }  // namespace
@@ -31,10 +33,15 @@
 struct shm_ok : public std::integral_constant<
                     bool,
 #if ((__GNUC__ < 5))
-                    (::std::has_trivial_copy_constructor<Tp>::value &&
+#if (__clang_major__ > 5)
+                    (::std::is_trivially_copy_constructible<Tp>::value &&
                      ::aos::has_trivial_copy_assign<Tp>::value)
 #else
-                    (::std::is_trivially_copyable<Tp>::value)
+                    (::std::has_trivial_copy_constructor<Tp>::value &&
+                     ::aos::has_trivial_copy_assign<Tp>::value)
+#endif
+#else
+                    (::std::is_trivially_copy_constructible<Tp>::value)
 #endif
                     > {
 };
diff --git a/aos/util/BUILD b/aos/util/BUILD
index f18fd82..4d7a3d1 100644
--- a/aos/util/BUILD
+++ b/aos/util/BUILD
@@ -65,7 +65,7 @@
     name = "math",
     hdrs = ["math.h"],
     deps = [
-        "//third_party/eigen",
+        "@org_tuxfamily_eigen//:eigen",
     ],
 )
 
@@ -111,7 +111,6 @@
         "phased_loop.h",
     ],
     deps = [
-        "//aos/logging",
         "//aos/time",
         "@com_github_google_glog//:glog",
     ],
@@ -156,7 +155,7 @@
     ],
     deps = [
         "//aos:macros",
-        "//aos/logging",
+        "@com_github_google_glog//:glog",
     ],
 )
 
@@ -174,7 +173,7 @@
     deps = [
         "//aos/logging",
         "//aos/time",
-        "//third_party/eigen",
+        "@org_tuxfamily_eigen//:eigen",
     ],
 )
 
@@ -296,8 +295,8 @@
         "file.h",
     ],
     deps = [
-        "//aos/logging",
         "//aos/scoped:scoped_fd",
+        "@com_github_google_glog//:glog",
         "@com_google_absl//absl/strings",
     ],
 )
@@ -311,7 +310,6 @@
     deps = [
         ":file",
         "//aos/testing:googletest",
-        "//aos/testing:test_logging",
     ],
 )
 
diff --git a/aos/util/file.cc b/aos/util/file.cc
index 5418aab..f78239a 100644
--- a/aos/util/file.cc
+++ b/aos/util/file.cc
@@ -4,8 +4,8 @@
 #include <unistd.h>
 
 #include "absl/strings/string_view.h"
-#include "aos/logging/logging.h"
 #include "aos/scoped/scoped_fd.h"
+#include "glog/logging.h"
 
 namespace aos {
 namespace util {
@@ -13,17 +13,12 @@
 ::std::string ReadFileToStringOrDie(const absl::string_view filename) {
   ::std::string r;
   ScopedFD fd(open(::std::string(filename).c_str(), O_RDONLY));
-  if (fd.get() == -1) {
-    AOS_PLOG(FATAL, "opening %*s", static_cast<int>(filename.size()),
-             filename.data());
-  }
+  PCHECK(fd.get() != -1) << ": opening " << filename;
   while (true) {
     char buffer[1024];
     const ssize_t result = read(fd.get(), buffer, sizeof(buffer));
-    if (result < 0) {
-      AOS_PLOG(FATAL, "reading from %*s", static_cast<int>(filename.size()),
-               filename.data());
-    } else if (result == 0) {
+    PCHECK(result >= 0) << ": reading from " << filename;
+    if (result == 0) {
       break;
     }
     r.append(buffer, result);
@@ -31,5 +26,24 @@
   return r;
 }
 
+void WriteStringToFileOrDie(const absl::string_view filename,
+                            const absl::string_view contents) {
+  ::std::string r;
+  ScopedFD fd(open(::std::string(filename).c_str(),
+                   O_CREAT | O_WRONLY | O_TRUNC, S_IRWXU));
+  PCHECK(fd.get() != -1) << ": opening " << filename;
+  size_t size_written = 0;
+  while (size_written != contents.size()) {
+    const ssize_t result = write(fd.get(), contents.data() + size_written,
+                                 contents.size() - size_written);
+    PCHECK(result >= 0) << ": reading from " << filename;
+    if (result == 0) {
+      break;
+    }
+
+    size_written += result;
+  }
+}
+
 }  // namespace util
 }  // namespace aos
diff --git a/aos/util/file.h b/aos/util/file.h
index 385aba7..5d354a7 100644
--- a/aos/util/file.h
+++ b/aos/util/file.h
@@ -12,6 +12,10 @@
 // encountered.
 ::std::string ReadFileToStringOrDie(const absl::string_view filename);
 
+// Creates filename if it doesn't exist and sets the contents to contents.
+void WriteStringToFileOrDie(const absl::string_view filename,
+                            const absl::string_view contents);
+
 }  // namespace util
 }  // namespace aos
 
diff --git a/aos/util/file_test.cc b/aos/util/file_test.cc
index f904259..fa259e8 100644
--- a/aos/util/file_test.cc
+++ b/aos/util/file_test.cc
@@ -6,21 +6,12 @@
 
 #include "gtest/gtest.h"
 
-#include "aos/testing/test_logging.h"
-
 namespace aos {
 namespace util {
 namespace testing {
 
-class FileTest : public ::testing::Test {
- protected:
-  FileTest() {
-    ::aos::testing::EnableTestLogging();
-  }
-};
-
 // Basic test of reading a normal file.
-TEST_F(FileTest, ReadNormalFile) {
+TEST(FileTest, ReadNormalFile) {
   const ::std::string tmpdir(getenv("TEST_TMPDIR"));
   const ::std::string test_file = tmpdir + "/test_file";
   ASSERT_EQ(0, system(("echo contents > " + test_file).c_str()));
@@ -28,7 +19,7 @@
 }
 
 // Tests reading a file with 0 size, among other weird things.
-TEST_F(FileTest, ReadSpecialFile) {
+TEST(FileTest, ReadSpecialFile) {
   const ::std::string stat = ReadFileToStringOrDie("/proc/self/stat");
   EXPECT_EQ('\n', stat[stat.size() - 1]);
   const ::std::string my_pid = ::std::to_string(getpid());
diff --git a/aos/util/phased_loop_test.cc b/aos/util/phased_loop_test.cc
index 0a0d5db..4a80522 100644
--- a/aos/util/phased_loop_test.cc
+++ b/aos/util/phased_loop_test.cc
@@ -10,11 +10,7 @@
 
 using ::std::chrono::milliseconds;
 
-class PhasedLoopTest : public ::testing::Test {
- protected:
-  PhasedLoopTest() { ::aos::testing::EnableTestLogging(); }
-};
-
+typedef ::testing::Test PhasedLoopTest;
 typedef PhasedLoopTest PhasedLoopDeathTest;
 
 monotonic_clock::time_point InMs(int ms) {
diff --git a/aos/util/thread.cc b/aos/util/thread.cc
index ae18fe9..bb5999f 100644
--- a/aos/util/thread.cc
+++ b/aos/util/thread.cc
@@ -3,7 +3,7 @@
 #include <pthread.h>
 #include <signal.h>
 
-#include "aos/logging/logging.h"
+#include "glog/logging.h"
 
 namespace aos {
 namespace util {
@@ -11,24 +11,24 @@
 Thread::Thread() : started_(false), joined_(false), should_terminate_(false) {}
 
 Thread::~Thread() {
-  AOS_CHECK(!(started_ && !joined_));
+  CHECK(!(started_ && !joined_));
 }
 
 void Thread::Start() {
-  AOS_CHECK(!started_);
+  CHECK(!started_);
   started_ = true;
-  AOS_CHECK(pthread_create(&thread_, NULL, &Thread::StaticRun, this) == 0);
+  CHECK(pthread_create(&thread_, NULL, &Thread::StaticRun, this) == 0);
 }
 
 void Thread::Join() {
-  AOS_CHECK(!joined_ && started_);
+  CHECK(!joined_ && started_);
   joined_ = true;
   should_terminate_.store(true);
-  AOS_CHECK(pthread_join(thread_, NULL) == 0);
+  CHECK(pthread_join(thread_, NULL) == 0);
 }
 
 bool Thread::TryJoin() {
-  AOS_CHECK(!joined_ && started_);
+  CHECK(!joined_ && started_);
 #ifdef AOS_SANITIZER_thread
   // ThreadSanitizer misses the tryjoin and then complains about leaking the
   // thread. Instead, we'll just check if the thread is still around and then
@@ -39,7 +39,8 @@
   if (kill_ret == 0) return false;
   // If it died, we'll get ESRCH. Otherwise, something went wrong.
   if (kill_ret != ESRCH) {
-    AOS_PELOG(FATAL, kill_ret, "pthread_kill(thread_, 0) failed");
+    errno = kill_ret;
+    PLOG(FATAL) << "pthread_kill(thread_, 0) failed";
   }
   Join();
   return true;
@@ -51,20 +52,22 @@
   } else if (ret == EBUSY) {
     return false;
   } else {
-    AOS_PELOG(FATAL, ret, "pthread_tryjoin_np(thread_, nullptr) failed");
+    errno = ret;
+    PLOG(FATAL) << "pthread_tryjoin_np(thread_, nullptr) failed";
+    return false;
   }
 #endif
 }
 
 void Thread::RequestStop() {
-  AOS_CHECK(!joined_ && started_);
+  CHECK(!joined_ && started_);
   should_terminate_.store(true);
 }
 
 void Thread::WaitUntilDone() {
-  AOS_CHECK(!joined_ && started_);
+  CHECK(!joined_ && started_);
   joined_ = true;
-  AOS_CHECK(pthread_join(thread_, NULL) == 0);
+  CHECK(pthread_join(thread_, NULL) == 0);
 }
 
 void *Thread::StaticRun(void *self) {
diff --git a/aos/util/thread.h b/aos/util/thread.h
index 5992810..337ea48 100644
--- a/aos/util/thread.h
+++ b/aos/util/thread.h
@@ -13,7 +13,7 @@
 
 // A nice wrapper around a pthreads thread.
 //
-// TODO(aschuh): Test this.
+// TODO(aschuh): replace this with std::thread
 class Thread {
  public:
   Thread();
diff --git a/aos/vision/blob/BUILD b/aos/vision/blob/BUILD
index 7d5f930..e025ed3 100644
--- a/aos/vision/blob/BUILD
+++ b/aos/vision/blob/BUILD
@@ -11,7 +11,7 @@
         "//aos/vision/image:image_types",
         "//aos/vision/math:segment",
         "//aos/vision/math:vector",
-        "//third_party/eigen",
+        "@org_tuxfamily_eigen//:eigen",
     ],
 )
 
@@ -72,7 +72,7 @@
         ":contour",
         ":disjoint_set",
         ":range_image",
-        "//third_party/eigen",
+        "@org_tuxfamily_eigen//:eigen",
     ],
 )
 
@@ -90,7 +90,7 @@
         ":range_image",
         "//aos/vision/debug:overlay",
         "//aos/vision/math:segment",
-        "//third_party/eigen",
+        "@org_tuxfamily_eigen//:eigen",
     ],
 )
 
@@ -102,7 +102,7 @@
         ":range_image",
         "//aos/vision/debug:overlay",
         "//aos/vision/math:segment",
-        "//third_party/eigen",
+        "@org_tuxfamily_eigen//:eigen",
     ],
 )
 
diff --git a/aos/vision/blob/threshold.h b/aos/vision/blob/threshold.h
index 8251b3a..f126b14 100644
--- a/aos/vision/blob/threshold.h
+++ b/aos/vision/blob/threshold.h
@@ -1,6 +1,7 @@
 #ifndef AOS_VISION_BLOB_THRESHOLD_H_
 #define AOS_VISION_BLOB_THRESHOLD_H_
 
+#include <array>
 #include <condition_variable>
 #include <mutex>
 #include <thread>
diff --git a/aos/vision/blob/threshold_test.cc b/aos/vision/blob/threshold_test.cc
index 108da35..3bbef1d 100644
--- a/aos/vision/blob/threshold_test.cc
+++ b/aos/vision/blob/threshold_test.cc
@@ -49,84 +49,84 @@
   std::vector<char> image;
   image.resize(8 * 8 * 2);
   //  --+-----
-  image[0 * 2 + 0 * 16] = 0;
-  image[1 * 2 + 0 * 16] = 0;
-  image[2 * 2 + 0 * 16] = 128;
-  image[3 * 2 + 0 * 16] = 127;
-  image[4 * 2 + 0 * 16] = 0;
-  image[5 * 2 + 0 * 16] = 0;
-  image[6 * 2 + 0 * 16] = 0;
-  image[7 * 2 + 0 * 16] = 0;
+  image[0 * 2 + 0 * 16] = static_cast<char>(0);
+  image[1 * 2 + 0 * 16] = static_cast<char>(0);
+  image[2 * 2 + 0 * 16] = static_cast<char>(128);
+  image[3 * 2 + 0 * 16] = static_cast<char>(127);
+  image[4 * 2 + 0 * 16] = static_cast<char>(0);
+  image[5 * 2 + 0 * 16] = static_cast<char>(0);
+  image[6 * 2 + 0 * 16] = static_cast<char>(0);
+  image[7 * 2 + 0 * 16] = static_cast<char>(0);
   expected_ranges.push_back({{{2, 3}}});
   //  +------+
-  image[0 * 2 + 1 * 16] = 128;
-  image[1 * 2 + 1 * 16] = 0;
-  image[2 * 2 + 1 * 16] = 0;
-  image[3 * 2 + 1 * 16] = 10;
-  image[4 * 2 + 1 * 16] = 30;
-  image[5 * 2 + 1 * 16] = 50;
-  image[6 * 2 + 1 * 16] = 70;
-  image[7 * 2 + 1 * 16] = 255;
+  image[0 * 2 + 1 * 16] = static_cast<char>(128);
+  image[1 * 2 + 1 * 16] = static_cast<char>(0);
+  image[2 * 2 + 1 * 16] = static_cast<char>(0);
+  image[3 * 2 + 1 * 16] = static_cast<char>(10);
+  image[4 * 2 + 1 * 16] = static_cast<char>(30);
+  image[5 * 2 + 1 * 16] = static_cast<char>(50);
+  image[6 * 2 + 1 * 16] = static_cast<char>(70);
+  image[7 * 2 + 1 * 16] = static_cast<char>(255);
   expected_ranges.push_back({{{0, 1}, {7, 8}}});
   //  -++++++-
-  image[0 * 2 + 2 * 16] = 73;
-  image[1 * 2 + 2 * 16] = 246;
-  image[2 * 2 + 2 * 16] = 247;
-  image[3 * 2 + 2 * 16] = 248;
-  image[4 * 2 + 2 * 16] = 249;
-  image[5 * 2 + 2 * 16] = 250;
-  image[6 * 2 + 2 * 16] = 250;
-  image[7 * 2 + 2 * 16] = 45;
+  image[0 * 2 + 2 * 16] = static_cast<char>(73);
+  image[1 * 2 + 2 * 16] = static_cast<char>(246);
+  image[2 * 2 + 2 * 16] = static_cast<char>(247);
+  image[3 * 2 + 2 * 16] = static_cast<char>(248);
+  image[4 * 2 + 2 * 16] = static_cast<char>(249);
+  image[5 * 2 + 2 * 16] = static_cast<char>(250);
+  image[6 * 2 + 2 * 16] = static_cast<char>(250);
+  image[7 * 2 + 2 * 16] = static_cast<char>(45);
   expected_ranges.push_back({{{1, 7}}});
   //  +++-++++
-  image[0 * 2 + 3 * 16] = 128;
-  image[1 * 2 + 3 * 16] = 134;
-  image[2 * 2 + 3 * 16] = 250;
-  image[3 * 2 + 3 * 16] = 0;
-  image[4 * 2 + 3 * 16] = 230;
-  image[5 * 2 + 3 * 16] = 230;
-  image[6 * 2 + 3 * 16] = 230;
-  image[7 * 2 + 3 * 16] = 210;
+  image[0 * 2 + 3 * 16] = static_cast<char>(128);
+  image[1 * 2 + 3 * 16] = static_cast<char>(134);
+  image[2 * 2 + 3 * 16] = static_cast<char>(250);
+  image[3 * 2 + 3 * 16] = static_cast<char>(0);
+  image[4 * 2 + 3 * 16] = static_cast<char>(230);
+  image[5 * 2 + 3 * 16] = static_cast<char>(230);
+  image[6 * 2 + 3 * 16] = static_cast<char>(230);
+  image[7 * 2 + 3 * 16] = static_cast<char>(210);
   expected_ranges.push_back({{{0, 3}, {4, 8}}});
   //  --------
-  image[0 * 2 + 4 * 16] = 7;
-  image[1 * 2 + 4 * 16] = 120;
-  image[2 * 2 + 4 * 16] = 127;
-  image[3 * 2 + 4 * 16] = 0;
-  image[4 * 2 + 4 * 16] = 50;
-  image[5 * 2 + 4 * 16] = 80;
-  image[6 * 2 + 4 * 16] = 110;
-  image[7 * 2 + 4 * 16] = 25;
+  image[0 * 2 + 4 * 16] = static_cast<char>(7);
+  image[1 * 2 + 4 * 16] = static_cast<char>(120);
+  image[2 * 2 + 4 * 16] = static_cast<char>(127);
+  image[3 * 2 + 4 * 16] = static_cast<char>(0);
+  image[4 * 2 + 4 * 16] = static_cast<char>(50);
+  image[5 * 2 + 4 * 16] = static_cast<char>(80);
+  image[6 * 2 + 4 * 16] = static_cast<char>(110);
+  image[7 * 2 + 4 * 16] = static_cast<char>(25);
   expected_ranges.push_back({{}});
   //  ++++-+++
-  image[0 * 2 + 5 * 16] = 140;
-  image[1 * 2 + 5 * 16] = 140;
-  image[2 * 2 + 5 * 16] = 140;
-  image[3 * 2 + 5 * 16] = 140;
-  image[4 * 2 + 5 * 16] = 0;
-  image[5 * 2 + 5 * 16] = 140;
-  image[6 * 2 + 5 * 16] = 140;
-  image[7 * 2 + 5 * 16] = 140;
+  image[0 * 2 + 5 * 16] = static_cast<char>(140);
+  image[1 * 2 + 5 * 16] = static_cast<char>(140);
+  image[2 * 2 + 5 * 16] = static_cast<char>(140);
+  image[3 * 2 + 5 * 16] = static_cast<char>(140);
+  image[4 * 2 + 5 * 16] = static_cast<char>(0);
+  image[5 * 2 + 5 * 16] = static_cast<char>(140);
+  image[6 * 2 + 5 * 16] = static_cast<char>(140);
+  image[7 * 2 + 5 * 16] = static_cast<char>(140);
   expected_ranges.push_back({{{0, 4}, {5, 8}}});
   //  ++++++++
-  image[0 * 2 + 6 * 16] = 128;
-  image[1 * 2 + 6 * 16] = 128;
-  image[2 * 2 + 6 * 16] = 128;
-  image[3 * 2 + 6 * 16] = 128;
-  image[4 * 2 + 6 * 16] = 128;
-  image[5 * 2 + 6 * 16] = 128;
-  image[6 * 2 + 6 * 16] = 128;
-  image[7 * 2 + 6 * 16] = 128;
+  image[0 * 2 + 6 * 16] = static_cast<char>(128);
+  image[1 * 2 + 6 * 16] = static_cast<char>(128);
+  image[2 * 2 + 6 * 16] = static_cast<char>(128);
+  image[3 * 2 + 6 * 16] = static_cast<char>(128);
+  image[4 * 2 + 6 * 16] = static_cast<char>(128);
+  image[5 * 2 + 6 * 16] = static_cast<char>(128);
+  image[6 * 2 + 6 * 16] = static_cast<char>(128);
+  image[7 * 2 + 6 * 16] = static_cast<char>(128);
   expected_ranges.push_back({{{0, 8}}});
   //  +-+-+--+
-  image[0 * 2 + 7 * 16] = 200;
-  image[1 * 2 + 7 * 16] = 0;
-  image[2 * 2 + 7 * 16] = 200;
-  image[3 * 2 + 7 * 16] = 0;
-  image[4 * 2 + 7 * 16] = 200;
-  image[5 * 2 + 7 * 16] = 0;
-  image[6 * 2 + 7 * 16] = 0;
-  image[7 * 2 + 7 * 16] = 200;
+  image[0 * 2 + 7 * 16] = static_cast<char>(200);
+  image[1 * 2 + 7 * 16] = static_cast<char>(0);
+  image[2 * 2 + 7 * 16] = static_cast<char>(200);
+  image[3 * 2 + 7 * 16] = static_cast<char>(0);
+  image[4 * 2 + 7 * 16] = static_cast<char>(200);
+  image[5 * 2 + 7 * 16] = static_cast<char>(0);
+  image[6 * 2 + 7 * 16] = static_cast<char>(0);
+  image[7 * 2 + 7 * 16] = static_cast<char>(200);
   expected_ranges.push_back({{{0, 1}, {2, 3}, {4, 5}, {7, 8}}});
   const RangeImage expected_result(0, std::move(expected_ranges));
 
diff --git a/aos/vision/events/BUILD b/aos/vision/events/BUILD
index b887872..a991968 100644
--- a/aos/vision/events/BUILD
+++ b/aos/vision/events/BUILD
@@ -52,6 +52,7 @@
     deps = [
         "//aos:macros",
         "//aos/scoped:scoped_fd",
+        "@com_github_google_glog//:glog",
     ],
 )
 
diff --git a/aos/vision/events/udp.cc b/aos/vision/events/udp.cc
index 8734443..7ac72e8 100644
--- a/aos/vision/events/udp.cc
+++ b/aos/vision/events/udp.cc
@@ -2,23 +2,23 @@
 
 #include <string.h>
 
-#include "aos/logging/logging.h"
+#include "glog/logging.h"
 
 namespace aos {
 namespace events {
 
 TXUdpSocket::TXUdpSocket(const std::string &ip_addr, int port)
-    : fd_(AOS_PCHECK(socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP))) {
+    : fd_(socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) {
+  PCHECK(fd_.get() != -1);
   sockaddr_in destination_in;
   memset(&destination_in, 0, sizeof(destination_in));
   destination_in.sin_family = AF_INET;
   destination_in.sin_port = htons(port);
-  if (inet_aton(ip_addr.c_str(), &destination_in.sin_addr) == 0) {
-    AOS_LOG(FATAL, "invalid IP address %s\n", ip_addr.c_str());
-  }
+  CHECK(inet_aton(ip_addr.c_str(), &destination_in.sin_addr) != 0)
+      << ": invalid IP address " << ip_addr;
 
-  AOS_PCHECK(connect(fd_.get(), reinterpret_cast<sockaddr *>(&destination_in),
-                     sizeof(destination_in)));
+  PCHECK(connect(fd_.get(), reinterpret_cast<sockaddr *>(&destination_in),
+                 sizeof(destination_in)) == 0);
 }
 
 int TXUdpSocket::Send(const char *data, int size) {
@@ -27,7 +27,8 @@
 }
 
 int RXUdpSocket::SocketBindListenOnPort(int port) {
-  int fd = AOS_PCHECK(socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP));
+  int fd;
+  PCHECK((fd = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) != -1);
   sockaddr_in bind_address;
   memset(&bind_address, 0, sizeof(bind_address));
 
@@ -35,15 +36,17 @@
   bind_address.sin_port = htons(port);
   bind_address.sin_addr.s_addr = htonl(INADDR_ANY);
 
-  AOS_PCHECK(bind(fd, reinterpret_cast<sockaddr *>(&bind_address),
-                  sizeof(bind_address)));
+  PCHECK(bind(fd, reinterpret_cast<sockaddr *>(&bind_address),
+              sizeof(bind_address)) == 0);
   return fd;
 }
 
 RXUdpSocket::RXUdpSocket(int port) : fd_(SocketBindListenOnPort(port)) {}
 
 int RXUdpSocket::Recv(void *data, int size) {
-  return AOS_PCHECK(recv(fd_.get(), static_cast<char *>(data), size, 0));
+  int result;
+  PCHECK((result = recv(fd_.get(), static_cast<char *>(data), size, 0)) != -1);
+  return result;
 }
 
 }  // namespace events
diff --git a/aos/vision/image/BUILD b/aos/vision/image/BUILD
index 21dbbb8..9b6d30a 100644
--- a/aos/vision/image/BUILD
+++ b/aos/vision/image/BUILD
@@ -5,6 +5,9 @@
 cc_library(
     name = "image_types",
     hdrs = ["image_types.h"],
+    deps = [
+        "@com_google_absl//absl/strings",
+    ],
 )
 
 cc_proto_library(
diff --git a/aos/vision/image/image_dataset.cc b/aos/vision/image/image_dataset.cc
index d4dde95..33bf0e4 100644
--- a/aos/vision/image/image_dataset.cc
+++ b/aos/vision/image/image_dataset.cc
@@ -37,10 +37,10 @@
   res.reserve(pos.size() + 1);
   i = 0;
   for (auto p : pos) {
-    res.emplace_back(inp.substr(i, p - i).to_string());
+    res.emplace_back(std::string(inp.substr(i, p - i)));
     i = p + 1;
   }
-  res.emplace_back(inp.substr(i).to_string());
+  res.emplace_back(std::string(inp.substr(i)));
   return res;
 }
 }  // namespace
diff --git a/aos/vision/image/image_types.h b/aos/vision/image/image_types.h
index a620d8a..aff7056 100644
--- a/aos/vision/image/image_types.h
+++ b/aos/vision/image/image_types.h
@@ -6,7 +6,7 @@
 #include <memory>
 #include <sstream>
 
-#include <experimental/string_view>
+#include "absl/strings/string_view.h"
 
 namespace aos {
 namespace vision {
@@ -20,7 +20,7 @@
 };
 
 // This will go into c++17. No sense writing my own version.
-using DataRef = std::experimental::string_view;
+using DataRef = absl::string_view;
 
 // Represents the dimensions of an image.
 struct ImageFormat {
diff --git a/aos/vision/math/BUILD b/aos/vision/math/BUILD
index 0fbdf7a..2c71e8f 100644
--- a/aos/vision/math/BUILD
+++ b/aos/vision/math/BUILD
@@ -12,8 +12,7 @@
         "vector.h",
     ],
     deps = [
-        "//third_party/eigen",
-        "@com_google_ceres_solver//:ceres",
+        "@org_tuxfamily_eigen//:eigen",
     ],
 )