Make y2020 multinode!

Update the configs.  It all starts on a roboRIO, and forwards RobotState
between nodes.  Need to finalize deployment for pi's.

Change-Id: I2601419a94ca154e9663c916e9b8987d73ffa814
diff --git a/y2020/BUILD b/y2020/BUILD
index bc22b96..aa5f16e 100644
--- a/y2020/BUILD
+++ b/y2020/BUILD
@@ -10,9 +10,11 @@
     start_binaries = [
         ":joystick_reader",
         ":wpilib_interface",
+        "//aos/network:message_bridge_client",
+        "//aos/network:message_bridge_server",
+        "//y2020/actors:binaries",
         "//y2020/control_loops/drivetrain:drivetrain",
         "//y2020/control_loops/superstructure:superstructure",
-        "//y2020/actors:binaries",
     ],
 )
 
@@ -110,13 +112,16 @@
     name = "config",
     src = "y2020.json",
     flatbuffers = [
+        "//aos/network:message_bridge_client_fbs",
+        "//aos/network:message_bridge_server_fbs",
+        "//aos/network:timestamp_fbs",
+        "//y2019/control_loops/drivetrain:target_selector_fbs",
         "//y2020/control_loops/superstructure:superstructure_goal_fbs",
         "//y2020/control_loops/superstructure:superstructure_output_fbs",
         "//y2020/control_loops/superstructure:superstructure_position_fbs",
-        "//y2019/control_loops/drivetrain:target_selector_fbs",
         "//y2020/control_loops/superstructure:superstructure_status_fbs",
-        "//y2020/vision:vision_fbs",
         "//y2020/vision/sift:sift_fbs",
+        "//y2020/vision:vision_fbs",
     ],
     visibility = ["//visibility:public"],
     deps = [
diff --git a/y2020/control_loops/drivetrain/drivetrain_replay_test.cc b/y2020/control_loops/drivetrain/drivetrain_replay_test.cc
index 6933a51..3e391c8 100644
--- a/y2020/control_loops/drivetrain/drivetrain_replay_test.cc
+++ b/y2020/control_loops/drivetrain/drivetrain_replay_test.cc
@@ -46,8 +46,10 @@
                               "frc971.control_loops.drivetrain.Output");
     reader_.Register();
 
+    roborio_ = aos::configuration::GetNode(reader_.configuration(), "roborio");
+
     drivetrain_event_loop_ =
-        reader_.event_loop_factory()->MakeEventLoop("drivetrain");
+        reader_.event_loop_factory()->MakeEventLoop("drivetrain", roborio_);
     drivetrain_event_loop_->SkipTimingReport();
 
     localizer_ =
@@ -59,13 +61,14 @@
             localizer_.get());
 
     test_event_loop_ =
-        reader_.event_loop_factory()->MakeEventLoop("drivetrain");
+        reader_.event_loop_factory()->MakeEventLoop("drivetrain", roborio_);
     status_fetcher_ = test_event_loop_->MakeFetcher<
         frc971::control_loops::drivetrain::Status>("/drivetrain");
   }
 
   const aos::FlatbufferDetachedBuffer<aos::Configuration> config_;
   aos::logger::LogReader reader_;
+  const aos::Node *roborio_;
 
   std::unique_ptr<aos::EventLoop> drivetrain_event_loop_;
   std::unique_ptr<frc971::control_loops::drivetrain::DeadReckonEkf> localizer_;
diff --git a/y2020/control_loops/drivetrain/localizer.cc b/y2020/control_loops/drivetrain/localizer.cc
index 5551179..4b11f6f 100644
--- a/y2020/control_loops/drivetrain/localizer.cc
+++ b/y2020/control_loops/drivetrain/localizer.cc
@@ -42,7 +42,7 @@
 
   image_fetchers_.emplace_back(
       event_loop_->MakeFetcher<frc971::vision::sift::ImageMatchResult>(
-          "/camera"));
+          "/pi1/camera"));
 
   target_selector_.set_has_target(false);
 }
diff --git a/y2020/control_loops/drivetrain/localizer_test.cc b/y2020/control_loops/drivetrain/localizer_test.cc
index acab856..1e72c39 100644
--- a/y2020/control_loops/drivetrain/localizer_test.cc
+++ b/y2020/control_loops/drivetrain/localizer_test.cc
@@ -101,7 +101,9 @@
             aos::configuration::ReadConfig(
                 "y2020/control_loops/drivetrain/simulation_config.json"),
             GetTest2020DrivetrainConfig().dt),
-        test_event_loop_(MakeEventLoop("test")),
+        roborio_(aos::configuration::GetNode(configuration(), "roborio")),
+        pi1_(aos::configuration::GetNode(configuration(), "pi1")),
+        test_event_loop_(MakeEventLoop("test", roborio_)),
         drivetrain_goal_sender_(
             test_event_loop_->MakeSender<Goal>("/drivetrain")),
         drivetrain_goal_fetcher_(
@@ -111,13 +113,14 @@
         superstructure_status_sender_(
             test_event_loop_->MakeSender<superstructure::Status>(
                 "/superstructure")),
-        drivetrain_event_loop_(MakeEventLoop("drivetrain")),
+        drivetrain_event_loop_(MakeEventLoop("drivetrain", roborio_)),
         dt_config_(GetTest2020DrivetrainConfig()),
+        pi1_event_loop_(MakeEventLoop("test", pi1_)),
         camera_sender_(
-            test_event_loop_->MakeSender<ImageMatchResult>("/camera")),
+            pi1_event_loop_->MakeSender<ImageMatchResult>("/pi1/camera")),
         localizer_(drivetrain_event_loop_.get(), dt_config_),
         drivetrain_(dt_config_, drivetrain_event_loop_.get(), &localizer_),
-        drivetrain_plant_event_loop_(MakeEventLoop("plant")),
+        drivetrain_plant_event_loop_(MakeEventLoop("plant", roborio_)),
         drivetrain_plant_(drivetrain_plant_event_loop_.get(), dt_config_),
         last_frame_(monotonic_now()) {
     set_team_id(frc971::control_loops::testing::kTeamNumber);
@@ -127,7 +130,7 @@
     if (!FLAGS_output_file.empty()) {
       log_buffer_writer_ = std::make_unique<aos::logger::DetachedBufferWriter>(
           FLAGS_output_file);
-      logger_event_loop_ = MakeEventLoop("logger");
+      logger_event_loop_ = MakeEventLoop("logger", roborio_);
       logger_ = std::make_unique<aos::logger::Logger>(log_buffer_writer_.get(),
                                                       logger_event_loop_.get());
     }
@@ -290,6 +293,9 @@
     }
   }
 
+  const aos::Node *const roborio_;
+  const aos::Node *const pi1_;
+
   std::unique_ptr<aos::EventLoop> test_event_loop_;
   aos::Sender<Goal> drivetrain_goal_sender_;
   aos::Fetcher<Goal> drivetrain_goal_fetcher_;
@@ -300,6 +306,7 @@
   const frc971::control_loops::drivetrain::DrivetrainConfig<double>
       dt_config_;
 
+  std::unique_ptr<aos::EventLoop> pi1_event_loop_;
   aos::Sender<ImageMatchResult> camera_sender_;
 
   Localizer localizer_;
diff --git a/y2020/control_loops/superstructure/superstructure_lib_test.cc b/y2020/control_loops/superstructure/superstructure_lib_test.cc
index ee94dd6..f68db08 100644
--- a/y2020/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2020/control_loops/superstructure/superstructure_lib_test.cc
@@ -374,7 +374,8 @@
       : ::aos::testing::ControlLoopTest(
             aos::configuration::ReadConfig("y2020/config.json"),
             chrono::microseconds(5050)),
-        test_event_loop_(MakeEventLoop("test")),
+        roborio_(aos::configuration::GetNode(configuration(), "roborio")),
+        test_event_loop_(MakeEventLoop("test", roborio_)),
         superstructure_goal_fetcher_(
             test_event_loop_->MakeFetcher<Goal>("/superstructure")),
         superstructure_goal_sender_(
@@ -385,9 +386,9 @@
             test_event_loop_->MakeFetcher<Output>("/superstructure")),
         superstructure_position_fetcher_(
             test_event_loop_->MakeFetcher<Position>("/superstructure")),
-        superstructure_event_loop_(MakeEventLoop("superstructure")),
+        superstructure_event_loop_(MakeEventLoop("superstructure", roborio_)),
         superstructure_(superstructure_event_loop_.get()),
-        superstructure_plant_event_loop_(MakeEventLoop("plant")),
+        superstructure_plant_event_loop_(MakeEventLoop("plant", roborio_)),
         superstructure_plant_(superstructure_plant_event_loop_.get(), dt()) {
     set_team_id(::frc971::control_loops::testing::kTeamNumber);
 
@@ -395,7 +396,7 @@
       unlink(FLAGS_output_file.c_str());
       log_buffer_writer_ = std::make_unique<aos::logger::DetachedBufferWriter>(
           FLAGS_output_file);
-      logger_event_loop_ = MakeEventLoop("logger");
+      logger_event_loop_ = MakeEventLoop("logger", roborio_);
       logger_ = std::make_unique<aos::logger::Logger>(log_buffer_writer_.get(),
                                                       logger_event_loop_.get());
     }
@@ -484,6 +485,8 @@
              !superstructure_status_fetcher_.get()->zeroed());
   }
 
+  const aos::Node *const roborio_;
+
   ::std::unique_ptr<::aos::EventLoop> test_event_loop_;
 
   ::aos::Fetcher<Goal> superstructure_goal_fetcher_;
diff --git a/y2020/y2020.json b/y2020/y2020.json
index d0c74e4..3673eee 100644
--- a/y2020/y2020.json
+++ b/y2020/y2020.json
@@ -1,42 +1,361 @@
 {
+  "channel_storage_duration": 5000000000,
   "channels":
   [
     {
+      "name": "/aos/roborio",
+      "type": "aos.JoystickState",
+      "source_node": "roborio",
+      "frequency": 75
+    },
+    {
+      "name": "/aos/roborio",
+      "type": "aos.RobotState",
+      "source_node": "roborio",
+      "frequency": 200,
+      "destination_nodes": [
+        {
+          "name": "pi1",
+          "priority": 2,
+          "timestamp_logger": "LOCAL_LOGGER",
+          "time_to_live": 10000000
+        },
+        {
+          "name": "pi2",
+          "priority": 2,
+          "timestamp_logger": "LOCAL_LOGGER",
+          "time_to_live": 10000000
+        },
+        {
+          "name": "pi3",
+          "priority": 2,
+          "timestamp_logger": "LOCAL_LOGGER",
+          "time_to_live": 10000000
+        }
+      ]
+    },
+    {
+      "name": "/aos/roborio",
+      "type": "aos.timing.Report",
+      "source_node": "roborio",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 2048
+    },
+    {
+      "name": "/aos/roborio",
+      "type": "aos.logging.LogMessageFbs",
+      "source_node": "roborio",
+      "frequency": 200,
+      "num_senders": 20
+    },
+    {
+      "name": "/aos/roborio",
+      "type": "aos.message_bridge.ServerStatistics",
+      "source_node": "roborio",
+      "frequency": 2,
+      "num_senders": 2
+    },
+    {
+      "name": "/aos/roborio",
+      "type": "aos.message_bridge.ClientStatistics",
+      "source_node": "roborio",
+      "frequency": 2,
+      "num_senders": 2
+    },
+    {
+      "name": "/aos/roborio",
+      "type": "aos.message_bridge.Timestamp",
+      "source_node": "roborio",
+      "frequency": 10,
+      "num_senders": 2,
+      "max_size": 200,
+      "destination_nodes": [
+        {
+          "name": "pi1",
+          "priority": 1,
+          "time_to_live": 5000000
+        },
+        {
+          "name": "pi2",
+          "priority": 1,
+          "time_to_live": 5000000
+        },
+        {
+          "name": "pi3",
+          "priority": 1,
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/aos/pi1",
+      "type": "aos.timing.Report",
+      "source_node": "pi1",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 2048
+    },
+    {
+      "name": "/aos/pi1",
+      "type": "aos.logging.LogMessageFbs",
+      "source_node": "pi1",
+      "frequency": 200,
+      "num_senders": 20
+    },
+    {
+      "name": "/aos/pi1",
+      "type": "aos.message_bridge.ServerStatistics",
+      "source_node": "pi1",
+      "frequency": 2,
+      "num_senders": 2
+    },
+    {
+      "name": "/aos/pi1",
+      "type": "aos.message_bridge.ClientStatistics",
+      "source_node": "pi1",
+      "frequency": 2,
+      "num_senders": 2
+    },
+    {
+      "name": "/aos/pi1",
+      "type": "aos.message_bridge.Timestamp",
+      "source_node": "pi1",
+      "frequency": 10,
+      "num_senders": 2,
+      "max_size": 200,
+      "destination_nodes": [
+        {
+          "name": "roborio",
+          "priority": 1,
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/aos/pi2",
+      "type": "aos.timing.Report",
+      "source_node": "pi2",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 2048
+    },
+    {
+      "name": "/aos/pi2",
+      "type": "aos.logging.LogMessageFbs",
+      "source_node": "pi2",
+      "frequency": 200,
+      "num_senders": 20
+    },
+    {
+      "name": "/aos/pi2",
+      "type": "aos.message_bridge.ServerStatistics",
+      "source_node": "pi2",
+      "frequency": 2,
+      "num_senders": 2
+    },
+    {
+      "name": "/aos/pi2",
+      "type": "aos.message_bridge.ClientStatistics",
+      "source_node": "pi2",
+      "frequency": 2,
+      "num_senders": 2
+    },
+    {
+      "name": "/aos/pi2",
+      "type": "aos.message_bridge.Timestamp",
+      "source_node": "pi2",
+      "frequency": 10,
+      "num_senders": 2,
+      "max_size": 200,
+      "destination_nodes": [
+        {
+          "name": "roborio",
+          "priority": 1,
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/aos/pi3",
+      "type": "aos.timing.Report",
+      "source_node": "pi3",
+      "frequency": 50,
+      "num_senders": 20,
+      "max_size": 2048
+    },
+    {
+      "name": "/aos/pi3",
+      "type": "aos.logging.LogMessageFbs",
+      "source_node": "pi3",
+      "frequency": 200,
+      "num_senders": 20
+    },
+    {
+      "name": "/aos/pi3",
+      "type": "aos.message_bridge.ServerStatistics",
+      "source_node": "pi3",
+      "frequency": 2,
+      "num_senders": 2
+    },
+    {
+      "name": "/aos/pi3",
+      "type": "aos.message_bridge.ClientStatistics",
+      "source_node": "pi3",
+      "frequency": 2,
+      "num_senders": 2
+    },
+    {
+      "name": "/aos/pi3",
+      "type": "aos.message_bridge.Timestamp",
+      "source_node": "pi3",
+      "frequency": 10,
+      "num_senders": 2,
+      "max_size": 200,
+      "destination_nodes": [
+        {
+          "name": "roborio",
+          "priority": 1,
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
       "name": "/superstructure",
       "type": "y2020.control_loops.superstructure.Goal",
+      "source_node": "roborio",
       "frequency": 200
     },
     {
       "name": "/superstructure",
       "type": "y2020.control_loops.superstructure.Status",
-      "frequency": 200
+      "source_node": "roborio",
+      "frequency": 200,
+      "num_senders": 2
     },
     {
       "name": "/superstructure",
       "type": "y2020.control_loops.superstructure.Output",
-      "frequency": 200
-    },
-    {
-      "name": "/drivetrain",
-      "type": "y2019.control_loops.drivetrain.TargetSelectorHint"
+      "source_node": "roborio",
+      "frequency": 200,
+      "num_senders": 2
     },
     {
       "name": "/superstructure",
       "type": "y2020.control_loops.superstructure.Position",
+      "source_node": "roborio",
+      "frequency": 200,
+      "num_senders": 2
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.IMUValues",
+      "source_node": "roborio",
+      "frequency": 2000,
+      "num_senders": 2
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.sensors.GyroReading",
+      "source_node": "roborio",
+      "frequency": 200,
+      "num_senders": 2
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.sensors.Uid",
+      "source_node": "roborio",
+      "frequency": 200,
+      "num_senders": 2
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.control_loops.drivetrain.Goal",
+      "source_node": "roborio",
       "frequency": 200
     },
     {
-      "name": "/camera",
+      "name": "/drivetrain",
+      "type": "frc971.control_loops.drivetrain.Position",
+      "source_node": "roborio",
+      "frequency": 200,
+      "num_senders": 2
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.control_loops.drivetrain.Status",
+      "source_node": "roborio",
+      "frequency": 200,
+      "max_size": 2000,
+      "num_senders": 2
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.control_loops.drivetrain.Output",
+      "source_node": "roborio",
+      "frequency": 200,
+      "num_senders": 2
+    },
+    {
+      "name": "/drivetrain",
+      "type": "frc971.control_loops.drivetrain.LocalizerControl",
+      "source_node": "roborio",
+      "frequency": 200
+    },
+    {
+      "name": "/drivetrain",
+      "type": "y2019.control_loops.drivetrain.TargetSelectorHint",
+      "source_node": "roborio"
+    },
+    {
+      "name": "/pi1/camera",
       "type": "frc971.vision.CameraImage",
+      "source_node": "pi1",
       "frequency": 25,
       "max_size": 620000,
       "num_senders": 18
     },
     {
-      "name": "/camera",
+      "name": "/pi1/camera",
       "type": "frc971.vision.sift.ImageMatchResult",
+      "source_node": "pi1",
       "frequency": 25,
-      "max_size": 300000
+      "max_size": 300000,
+      "destination_nodes": [
+        {
+          "name": "roborio",
+          "priority": 1,
+          "time_to_live": 5000000
+        }
+      ]
+    },
+    {
+      "name": "/autonomous",
+      "type": "aos.common.actions.Status",
+      "source_node": "roborio"
+    },
+    {
+      "name": "/autonomous",
+      "type": "frc971.autonomous.Goal",
+      "source_node": "roborio"
+    },
+    {
+      "name": "/autonomous",
+      "type": "frc971.autonomous.AutonomousMode",
+      "source_node": "roborio",
+      "frequency": 200
+    },
+    {
+      "name": "/aos/roborio",
+      "type": "frc971.PDPValues",
+      "source_node": "roborio",
+      "frequency": 50
+    },
+    {
+      "name": "/aos/roborio",
+      "type": "frc971.wpilib.PneumaticsToLog",
+      "source_node": "roborio",
+      "frequency": 50
     }
   ],
   "applications": [
@@ -47,10 +366,97 @@
       "name": "camera_reader"
     }
   ],
-  "imports": [
-    "../aos/robot_state/robot_state_config.json",
-    "../frc971/control_loops/drivetrain/drivetrain_config.json",
-    "../frc971/autonomous/autonomous_config.json",
-    "../frc971/wpilib/wpilib_config.json"
+  "maps": [
+    {
+      "match": {
+        "name": "/aos",
+        "source_node": "roborio"
+      },
+      "rename": {
+        "name": "/aos/roborio"
+      }
+    },
+    {
+      "match": {
+        "name": "/aos",
+        "source_node": "pi1"
+      },
+      "rename": {
+        "name": "/aos/pi1"
+      }
+    },
+    {
+      "match": {
+        "name": "/aos",
+        "source_node": "pi2"
+      },
+      "rename": {
+        "name": "/aos/pi2"
+      }
+    },
+    {
+      "match": {
+        "name": "/aos",
+        "source_node": "pi3"
+      },
+      "rename": {
+        "name": "/aos/pi3"
+      }
+    },
+    {
+      "match": {
+        "name": "/aos",
+        "type": "aos.RobotState"
+      },
+      "rename": {
+        "name": "/aos/roborio"
+      }
+    }
+  ],
+  "nodes": [
+    {
+      "name": "roborio",
+      "hostname": "roborio",
+      "hostnames": [
+        "roboRIO-971-FRC",
+        "roboRIO-7971-FRC",
+        "roboRIO-8971-FRC",
+        "roboRIO-9971-FRC"
+      ],
+      "port": 9971
+    },
+    {
+      "name": "pi1",
+      "hostname": "pi1",
+      "hostnames": [
+        "pi-971-1",
+        "pi-7971-1",
+        "pi-8971-1",
+        "pi-9971-1"
+      ],
+      "port": 9971
+    },
+    {
+      "name": "pi2",
+      "hostname": "pi2",
+      "hostnames": [
+        "pi-971-2",
+        "pi-7971-2",
+        "pi-8971-2",
+        "pi-9971-2"
+      ],
+      "port": 9971
+    },
+    {
+      "name": "pi3",
+      "hostname": "pi3",
+      "hostnames": [
+        "pi-971-3",
+        "pi-7971-3",
+        "pi-8971-3",
+        "pi-9971-3"
+      ],
+      "port": 9971
+    }
   ]
 }