Rename timer `Setup` function to `Schedule`

This patch was motivated by my desire to fix a typo in the function
name. The noun "setup" is 1 word. The verb "set up" is 2 words. All
other member functions are verbs, so this one should be a verb too.
That means that the function should be called `SetUp`. During the
discussion that resulted from the rename, James Kuszmaul pointed out
that "setting up" a timer can be confusing. It implies that you can
only "set up" a timer once. But the intent is to let users set up
timers as many times as they like. So we decided on renaming the
function to `Schedule`. That conveys the purpose and intent better.

I took this opportunity to fix some other typos involving the verb
"set up".

Signed-off-by: Philipp Schrader <philipp.schrader@gmail.com>
Change-Id: I2f557d1f946960af82711f248820d5e2d385a5d3
diff --git a/y2020/actors/autonomous_actor.cc b/y2020/actors/autonomous_actor.cc
index 2f9a8c6..160d36a 100644
--- a/y2020/actors/autonomous_actor.cc
+++ b/y2020/actors/autonomous_actor.cc
@@ -47,8 +47,9 @@
   set_max_drivetrain_voltage(12.0);
   replan_timer_ = event_loop->AddTimer([this]() { Replan(); });
   event_loop->OnRun([this, event_loop]() {
-    replan_timer_->Setup(event_loop->monotonic_now());
-    button_poll_->Setup(event_loop->monotonic_now(), chrono::milliseconds(50));
+    replan_timer_->Schedule(event_loop->monotonic_now());
+    button_poll_->Schedule(event_loop->monotonic_now(),
+                           chrono::milliseconds(50));
   });
 
   button_poll_ = event_loop->AddTimer([this]() {
@@ -67,12 +68,12 @@
         is_planned_ = false;
         // Only kick the planning out by 2 seconds. If we end up enabled in that
         // second, then we will kick it out further based on the code below.
-        replan_timer_->Setup(now + std::chrono::seconds(2));
+        replan_timer_->Schedule(now + std::chrono::seconds(2));
       }
       if (joystick_state_fetcher_->enabled()) {
         if (!is_planned_) {
           // Only replan once we've been disabled for 5 seconds.
-          replan_timer_->Setup(now + std::chrono::seconds(5));
+          replan_timer_->Schedule(now + std::chrono::seconds(5));
         }
       }
     }
diff --git a/y2020/control_loops/drivetrain/localizer_test.cc b/y2020/control_loops/drivetrain/localizer_test.cc
index bb85921..3e2cf6b 100644
--- a/y2020/control_loops/drivetrain/localizer_test.cc
+++ b/y2020/control_loops/drivetrain/localizer_test.cc
@@ -603,7 +603,7 @@
   event_loop_factory()->set_network_delay(std::chrono::nanoseconds(1));
   test_event_loop_
       ->AddTimer([this]() { drivetrain_plant_.set_send_messages(false); })
-      ->Setup(test_event_loop_->monotonic_now());
+      ->Schedule(test_event_loop_->monotonic_now());
   test_event_loop_->AddPhasedLoop(
       [this](int) {
         auto builder = camera_sender_.MakeBuilder();
@@ -617,7 +617,7 @@
         drivetrain_plant_.set_send_messages(true);
         SimulateSensorReset();
       })
-      ->Setup(test_event_loop_->monotonic_now() + std::chrono::seconds(10));
+      ->Schedule(test_event_loop_->monotonic_now() + std::chrono::seconds(10));
 
   RunFor(chrono::seconds(20));
 }
diff --git a/y2020/control_loops/superstructure/superstructure_lib_test.cc b/y2020/control_loops/superstructure/superstructure_lib_test.cc
index b146149..d2051df 100644
--- a/y2020/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2020/control_loops/superstructure/superstructure_lib_test.cc
@@ -605,7 +605,7 @@
     test_event_loop_
         ->AddTimer(
             [this, velocity_finisher] { finisher_goal_ = velocity_finisher; })
-        ->Setup(test_event_loop_->monotonic_now() + time_offset);
+        ->Schedule(test_event_loop_->monotonic_now() + time_offset);
   }
 
   // Simulates the friction of a ball in the flywheel
@@ -617,12 +617,12 @@
           superstructure_plant_.set_finisher_voltage_offset(voltage_offset);
           ball_in_finisher_ = ball_in_finisher;
         })
-        ->Setup(test_event_loop_->monotonic_now() + time_offset);
+        ->Schedule(test_event_loop_->monotonic_now() + time_offset);
     test_event_loop_
         ->AddTimer(
             [this] { superstructure_plant_.set_finisher_voltage_offset(0); })
-        ->Setup(test_event_loop_->monotonic_now() + time_offset +
-                chrono::seconds(1));
+        ->Schedule(test_event_loop_->monotonic_now() + time_offset +
+                   chrono::seconds(1));
   }
 
   const aos::Node *const roborio_;
@@ -878,7 +878,7 @@
         EXPECT_TRUE((subsystems_not_ready->Get(0) == Subsystem::ACCELERATOR) !=
                     (subsystems_not_ready->Get(1) == Subsystem::ACCELERATOR));
       })
-      ->Setup(test_event_loop_->monotonic_now() + chrono::milliseconds(1));
+      ->Schedule(test_event_loop_->monotonic_now() + chrono::milliseconds(1));
 
   // Give it a lot of time to get there.
   RunFor(chrono::seconds(8));
diff --git a/y2020/vision/camera_reader.cc b/y2020/vision/camera_reader.cc
index 9966a5b..a63becd 100644
--- a/y2020/vision/camera_reader.cc
+++ b/y2020/vision/camera_reader.cc
@@ -455,15 +455,15 @@
     if (!FLAGS_skip_sift) {
       LOG(INFO) << "No image, sleeping";
     }
-    read_image_timer_->Setup(event_loop_->monotonic_now() +
-                             std::chrono::milliseconds(10));
+    read_image_timer_->Schedule(event_loop_->monotonic_now() +
+                                std::chrono::milliseconds(10));
     return;
   }
 
   ProcessImage(reader_->LatestImage());
 
   reader_->SendLatestImage();
-  read_image_timer_->Setup(event_loop_->monotonic_now());
+  read_image_timer_->Schedule(event_loop_->monotonic_now());
 }
 
 flatbuffers::Offset<flatbuffers::Vector<flatbuffers::Offset<sift::ImageMatch>>>
diff --git a/y2020/vision/camera_reader.h b/y2020/vision/camera_reader.h
index 37fb5a9..9a8cf6f 100644
--- a/y2020/vision/camera_reader.h
+++ b/y2020/vision/camera_reader.h
@@ -47,8 +47,9 @@
       matcher.train();
     }
 
-    event_loop->OnRun(
-        [this]() { read_image_timer_->Setup(event_loop_->monotonic_now()); });
+    event_loop->OnRun([this]() {
+      read_image_timer_->Schedule(event_loop_->monotonic_now());
+    });
   }
 
  private: