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/aos/actions/action_test.cc b/aos/actions/action_test.cc
index e7a3c53..ea46ed8 100644
--- a/aos/actions/action_test.cc
+++ b/aos/actions/action_test.cc
@@ -107,7 +107,8 @@
 
   void RunAt(monotonic_clock::time_point exec_time, std::function<void()> fn) {
     TimerHandler *timer = test_event_loop_->AddTimer(fn);
-    test_event_loop_->OnRun([timer, exec_time]() { timer->Setup(exec_time); });
+    test_event_loop_->OnRun(
+        [timer, exec_time]() { timer->Schedule(exec_time); });
   }
 
   FlatbufferDetachedBuffer<Configuration> configuration_;
diff --git a/aos/aos_dump.cc b/aos/aos_dump.cc
index ad50b0b..1dbcd44 100644
--- a/aos/aos_dump.cc
+++ b/aos/aos_dump.cc
@@ -114,8 +114,8 @@
 
     cli_info.event_loop->OnRun(
         [handle, event_loop = &cli_info.event_loop.value()]() {
-          handle->Setup(event_loop->monotonic_now() +
-                        std::chrono::milliseconds(FLAGS_timeout));
+          handle->Schedule(event_loop->monotonic_now() +
+                           std::chrono::milliseconds(FLAGS_timeout));
         });
   }
 
diff --git a/aos/aos_send.cc b/aos/aos_send.cc
index 210a2af..980ebc7 100644
--- a/aos/aos_send.cc
+++ b/aos/aos_send.cc
@@ -67,9 +67,9 @@
         ->AddTimer([&fbb, &sender]() {
           sender->CheckOk(sender->Send(fbb.GetBufferPointer(), fbb.GetSize()));
         })
-        ->Setup(cli_info.event_loop->monotonic_now(),
-                std::chrono::duration_cast<std::chrono::nanoseconds>(
-                    std::chrono::duration<double>(1.0 / FLAGS_rate)));
+        ->Schedule(cli_info.event_loop->monotonic_now(),
+                   std::chrono::duration_cast<std::chrono::nanoseconds>(
+                       std::chrono::duration<double>(1.0 / FLAGS_rate)));
     cli_info.event_loop->Run();
   }
 
diff --git a/aos/events/README.md b/aos/events/README.md
index 875e1b7..a8d94af 100644
--- a/aos/events/README.md
+++ b/aos/events/README.md
@@ -2,7 +2,7 @@
 
 Running ping<->pong is a nice way to test that you can run some basic code and shows how messaging can work between two nodes
 
-### Setup real-time niceties:
+### Set up real-time niceties:
   1. Add the following lines to `/etc/security/limits.d/rt.conf`, replacing "USERNAME" with the username you're running under.  You'll probably need to do this as root, e.g., `sudo nano /etc/security/limits.d/rt.conf`
 ```
 USERNAME - nice -20
diff --git a/aos/events/event_loop.cc b/aos/events/event_loop.cc
index 8a5774f..e84763e 100644
--- a/aos/events/event_loop.cc
+++ b/aos/events/event_loop.cc
@@ -562,7 +562,7 @@
     // Set it up to send once per second.
     timing_reports_timer->set_name("timing_reports");
     OnRun([this, timing_reports_timer]() {
-      timing_reports_timer->Setup(
+      timing_reports_timer->Schedule(
           monotonic_now() + std::chrono::milliseconds(FLAGS_timing_report_ms),
           std::chrono::milliseconds(FLAGS_timing_report_ms));
     });
diff --git a/aos/events/event_loop.h b/aos/events/event_loop.h
index 5eaaf22..e6e5499 100644
--- a/aos/events/event_loop.h
+++ b/aos/events/event_loop.h
@@ -497,9 +497,9 @@
   // Timer should sleep until base, base + offset, base + offset * 2, ...
   // If repeat_offset isn't set, the timer only expires once.
   // base must be greater than or equal to zero.
-  virtual void Setup(monotonic_clock::time_point base,
-                     monotonic_clock::duration repeat_offset =
-                         ::aos::monotonic_clock::zero()) = 0;
+  virtual void Schedule(monotonic_clock::time_point base,
+                        monotonic_clock::duration repeat_offset =
+                            ::aos::monotonic_clock::zero()) = 0;
 
   // Stop future calls to callback().
   virtual void Disable() = 0;
diff --git a/aos/events/event_loop_param_test.cc b/aos/events/event_loop_param_test.cc
index beb5e78..7e79a8b 100644
--- a/aos/events/event_loop_param_test.cc
+++ b/aos/events/event_loop_param_test.cc
@@ -394,7 +394,8 @@
   // Add a timer to actually quit.
   auto test_timer = loop2->AddTimer([this]() { this->Exit(); });
   loop2->OnRun([&test_timer, &loop2]() {
-    test_timer->Setup(loop2->monotonic_now(), ::std::chrono::milliseconds(100));
+    test_timer->Schedule(loop2->monotonic_now(),
+                         ::std::chrono::milliseconds(100));
   });
 
   Run();
@@ -433,7 +434,8 @@
   });
 
   loop2->OnRun([&test_timer, &loop2]() {
-    test_timer->Setup(loop2->monotonic_now(), ::std::chrono::milliseconds(100));
+    test_timer->Schedule(loop2->monotonic_now(),
+                         ::std::chrono::milliseconds(100));
   });
 
   Run();
@@ -473,7 +475,8 @@
   });
 
   loop2->OnRun([&test_timer, &loop2]() {
-    test_timer->Setup(loop2->monotonic_now(), ::std::chrono::milliseconds(100));
+    test_timer->Schedule(loop2->monotonic_now(),
+                         ::std::chrono::milliseconds(100));
   });
 
   Run();
@@ -518,7 +521,8 @@
   });
 
   loop2->OnRun([&test_timer, &loop2]() {
-    test_timer->Setup(loop2->monotonic_now(), ::std::chrono::milliseconds(100));
+    test_timer->Schedule(loop2->monotonic_now(),
+                         ::std::chrono::milliseconds(100));
   });
 
   Run();
@@ -537,7 +541,7 @@
 
   loop->OnRun([&loop, timer]() {
     EXPECT_TRUE(timer->IsDisabled());
-    timer->Setup(loop->monotonic_now() + chrono::milliseconds(100));
+    timer->Schedule(loop->monotonic_now() + chrono::milliseconds(100));
     EXPECT_FALSE(timer->IsDisabled());
   });
 
@@ -556,11 +560,11 @@
   });
 
   auto timer = loop->AddTimer([&loop, timer2]() {
-    timer2->Setup(loop->monotonic_now() - chrono::nanoseconds(1));
+    timer2->Schedule(loop->monotonic_now() - chrono::nanoseconds(1));
   });
 
   loop->OnRun([&loop, timer]() {
-    timer->Setup(loop->monotonic_now() + chrono::seconds(1));
+    timer->Schedule(loop->monotonic_now() + chrono::seconds(1));
     EXPECT_FALSE(timer->IsDisabled());
   });
 
@@ -583,8 +587,8 @@
   });
 
   loop->OnRun([&loop, timer]() {
-    timer->Setup(loop->monotonic_now() + chrono::seconds(1),
-                 chrono::seconds(1));
+    timer->Schedule(loop->monotonic_now() + chrono::seconds(1),
+                    chrono::seconds(1));
     EXPECT_FALSE(timer->IsDisabled());
   });
   Run();
@@ -610,8 +614,8 @@
   auto timer = loop->AddTimer([]() { LOG(INFO) << "timer called"; });
 
   loop->OnRun([&loop, timer]() {
-    timer->Setup(loop->monotonic_now() + chrono::seconds(1),
-                 chrono::seconds(1));
+    timer->Schedule(loop->monotonic_now() + chrono::seconds(1),
+                    chrono::seconds(1));
     EXPECT_FALSE(timer->IsDisabled());
   });
 
@@ -684,7 +688,8 @@
   });
 
   loop2->OnRun([&test_timer, &loop2]() {
-    test_timer->Setup(loop2->monotonic_now(), ::std::chrono::milliseconds(100));
+    test_timer->Schedule(loop2->monotonic_now(),
+                         ::std::chrono::milliseconds(100));
   });
 
   Run();
@@ -855,8 +860,9 @@
 TEST_P(AbstractEventLoopDeathTest, NegativeTimeTimer) {
   auto loop = Make();
   TimerHandler *time = loop->AddTimer([]() {});
-  EXPECT_DEATH(time->Setup(monotonic_clock::epoch() - std::chrono::seconds(1)),
-               "-1.000");
+  EXPECT_DEATH(
+      time->Schedule(monotonic_clock::epoch() - std::chrono::seconds(1)),
+      "-1.000");
 }
 
 // Verify that registering a watcher twice for "/test" fails.
@@ -1132,7 +1138,7 @@
     this->Exit();
   });
 
-  loop2->OnRun([&]() { test_timer->Setup(loop2->monotonic_now()); });
+  loop2->OnRun([&]() { test_timer->Schedule(loop2->monotonic_now()); });
 
   Run();
   EXPECT_TRUE(fetcher.Fetch());
@@ -1176,7 +1182,7 @@
 
   const monotonic_clock::time_point start_time = loop->monotonic_now();
   // TODO(austin): This should be an error...  Should be done in OnRun only.
-  test_timer->Setup(start_time + chrono::seconds(1), chrono::seconds(1));
+  test_timer->Schedule(start_time + chrono::seconds(1), chrono::seconds(1));
 
   Run();
 
@@ -1278,13 +1284,13 @@
 
   monotonic_clock::time_point s;
   auto modifier_timer = loop->AddTimer([&test_timer, &s]() {
-    test_timer->Setup(s + chrono::milliseconds(1750),
-                      chrono::milliseconds(600));
+    test_timer->Schedule(s + chrono::milliseconds(1750),
+                         chrono::milliseconds(600));
   });
 
   s = loop->monotonic_now();
-  test_timer->Setup(s, chrono::milliseconds(500));
-  modifier_timer->Setup(s + chrono::milliseconds(1250));
+  test_timer->Schedule(s, chrono::milliseconds(500));
+  modifier_timer->Schedule(s + chrono::milliseconds(1250));
   EndEventLoop(loop.get(), chrono::milliseconds(3950));
   Run();
 
@@ -1310,8 +1316,8 @@
   auto ender_timer = loop->AddTimer([&test_timer]() { test_timer->Disable(); });
 
   monotonic_clock::time_point s = loop->monotonic_now();
-  test_timer->Setup(s, ::std::chrono::milliseconds(500));
-  ender_timer->Setup(s + ::std::chrono::milliseconds(1250));
+  test_timer->Schedule(s, ::std::chrono::milliseconds(500));
+  ender_timer->Schedule(s + ::std::chrono::milliseconds(1250));
   EndEventLoop(loop.get(), ::std::chrono::milliseconds(2000));
   Run();
 
@@ -1335,7 +1341,7 @@
     test_timer->Disable();
   });
 
-  test_timer->Setup(loop->monotonic_now(), ::std::chrono::milliseconds(20));
+  test_timer->Schedule(loop->monotonic_now(), ::std::chrono::milliseconds(20));
   EndEventLoop(loop.get(), ::std::chrono::milliseconds(80));
   Run();
 
@@ -1367,15 +1373,16 @@
         const auto start = loop->monotonic_now();
 
         for (int i = 0; i < shuffle_events; ++i) {
-          loop->AddTimer([]() {})->Setup(start + std::chrono::milliseconds(10));
+          loop->AddTimer([]() {})->Schedule(start +
+                                            std::chrono::milliseconds(10));
         }
 
         if (setup_order) {
-          test_timer->Setup(start + ::std::chrono::milliseconds(20));
-          ender_timer->Setup(start + ::std::chrono::milliseconds(20));
+          test_timer->Schedule(start + ::std::chrono::milliseconds(20));
+          ender_timer->Schedule(start + ::std::chrono::milliseconds(20));
         } else {
-          ender_timer->Setup(start + ::std::chrono::milliseconds(20));
-          test_timer->Setup(start + ::std::chrono::milliseconds(20));
+          ender_timer->Schedule(start + ::std::chrono::milliseconds(20));
+          test_timer->Schedule(start + ::std::chrono::milliseconds(20));
         }
         EndEventLoop(loop.get(), ::std::chrono::milliseconds(40));
         Run();
@@ -1557,7 +1564,7 @@
     triggered = true;
   });
 
-  test_timer->Setup(loop1->monotonic_now() + ::std::chrono::seconds(1));
+  test_timer->Schedule(loop1->monotonic_now() + ::std::chrono::seconds(1));
 
   EndEventLoop(loop1.get(), ::std::chrono::seconds(2));
   Run();
@@ -1646,7 +1653,7 @@
     triggered = true;
   });
 
-  test_timer->Setup(loop1->monotonic_now() + ::std::chrono::seconds(1));
+  test_timer->Schedule(loop1->monotonic_now() + ::std::chrono::seconds(1));
 
   EndEventLoop(loop1.get(), ::std::chrono::seconds(2));
   Run();
@@ -2011,7 +2018,7 @@
         EXPECT_EQ(count, expected_count);
         expected_times.push_back(loop1->context().monotonic_event_time);
 
-        manager_timer->Setup(loop1->context().monotonic_event_time);
+        manager_timer->Schedule(loop1->context().monotonic_event_time);
       },
       kInterval, kOffset);
   phased_loop->set_name("Test loop");
@@ -2056,7 +2063,7 @@
         EXPECT_EQ(count, 1);
         expected_times.push_back(loop1->context().monotonic_event_time);
 
-        manager_timer->Setup(loop1->context().monotonic_event_time);
+        manager_timer->Schedule(loop1->context().monotonic_event_time);
       },
       kInterval, kOffset);
   phased_loop->set_name("Test loop");
@@ -2103,7 +2110,7 @@
         EXPECT_EQ(count, expected_count);
         expected_times.push_back(loop1->context().monotonic_event_time);
 
-        manager_timer->Setup(loop1->context().monotonic_event_time);
+        manager_timer->Schedule(loop1->context().monotonic_event_time);
       },
       kInterval, kOffset);
   phased_loop->set_name("Test loop");
@@ -2152,7 +2159,7 @@
         EXPECT_EQ(1, count);
         expected_times.push_back(loop1->context().monotonic_event_time);
 
-        manager_timer->Setup(loop1->context().monotonic_event_time);
+        manager_timer->Schedule(loop1->context().monotonic_event_time);
       },
       kInterval, kOffset);
   phased_loop->set_name("Test loop");
@@ -2202,7 +2209,7 @@
         EXPECT_EQ(1, count);
         expected_times.push_back(loop1->context().monotonic_event_time);
 
-        manager_timer->Setup(loop1->context().monotonic_event_time);
+        manager_timer->Schedule(loop1->context().monotonic_event_time);
       },
       kInterval, kOffset);
   phased_loop->set_name("Test loop");
@@ -2258,7 +2265,7 @@
   EndEventLoop(loop1.get(), chrono::milliseconds(2500));
 
   loop1->OnRun([&test_timer, &loop1]() {
-    test_timer->Setup(loop1->monotonic_now() + chrono::milliseconds(1500));
+    test_timer->Schedule(loop1->monotonic_now() + chrono::milliseconds(1500));
   });
 
   Run();
@@ -2482,7 +2489,7 @@
   EndEventLoop(loop1.get(), chrono::milliseconds(2500));
 
   loop1->OnRun([&test_timer, &loop1]() {
-    test_timer->Setup(loop1->monotonic_now() + chrono::milliseconds(1500));
+    test_timer->Schedule(loop1->monotonic_now() + chrono::milliseconds(1500));
   });
 
   Run();
@@ -2557,8 +2564,8 @@
   EndEventLoop(loop1.get(), chrono::milliseconds(2500));
 
   loop1->OnRun([test_timer, test_timer2, &loop1]() {
-    test_timer->Setup(loop1->monotonic_now() + chrono::milliseconds(1400));
-    test_timer2->Setup(loop1->monotonic_now() + chrono::milliseconds(1600));
+    test_timer->Schedule(loop1->monotonic_now() + chrono::milliseconds(1400));
+    test_timer2->Schedule(loop1->monotonic_now() + chrono::milliseconds(1600));
   });
 
   Run();
@@ -2888,7 +2895,8 @@
 
   loop1->OnRun([&test_timer, &loop1]() {
     CheckNotRealtime();
-    test_timer->Setup(loop1->monotonic_now(), ::std::chrono::milliseconds(100));
+    test_timer->Schedule(loop1->monotonic_now(),
+                         ::std::chrono::milliseconds(100));
   });
 
   Run();
@@ -2930,7 +2938,8 @@
 
   loop1->OnRun([&test_timer, &loop1]() {
     CheckRealtime();
-    test_timer->Setup(loop1->monotonic_now(), ::std::chrono::milliseconds(100));
+    test_timer->Schedule(loop1->monotonic_now(),
+                         ::std::chrono::milliseconds(100));
   });
 
   Run();
@@ -3240,7 +3249,7 @@
           event_loop->configuration()->channel_storage_duration()) -
       (kRepeatOffset * (queue_size / 2));
   event_loop->OnRun([&event_loop, &timer, &base_offset, &kRepeatOffset]() {
-    timer->Setup(event_loop->monotonic_now() + base_offset, kRepeatOffset);
+    timer->Schedule(event_loop->monotonic_now() + base_offset, kRepeatOffset);
   });
 
   Run();
diff --git a/aos/events/event_loop_param_test.h b/aos/events/event_loop_param_test.h
index d795a13..fe85732 100644
--- a/aos/events/event_loop_param_test.h
+++ b/aos/events/event_loop_param_test.h
@@ -349,7 +349,7 @@
   // Ends the given event loop at the given time from now.
   void EndEventLoop(EventLoop *loop, ::std::chrono::milliseconds duration) {
     auto end_timer = loop->AddTimer([this]() { this->Exit(); });
-    end_timer->Setup(loop->monotonic_now() + duration);
+    end_timer->Schedule(loop->monotonic_now() + duration);
     end_timer->set_name("end");
   }
 
diff --git a/aos/events/event_loop_runtime_test.cc b/aos/events/event_loop_runtime_test.cc
index 7a49fe1..6bd4c70 100644
--- a/aos/events/event_loop_runtime_test.cc
+++ b/aos/events/event_loop_runtime_test.cc
@@ -40,7 +40,7 @@
             builder.CheckOk(builder.Send(ping.Finish()));
           }
         })
-        ->Setup(
+        ->Schedule(
             ping_event_loop->monotonic_now() + std::chrono::milliseconds(10),
             std::chrono::milliseconds(10));
     ASSERT_EQ(starting_count, started_test_count());
diff --git a/aos/events/glib_main_loop.cc b/aos/events/glib_main_loop.cc
index 6bac983..bee8a81 100644
--- a/aos/events/glib_main_loop.cc
+++ b/aos/events/glib_main_loop.cc
@@ -178,8 +178,8 @@
   if (timeout_ms == -1) {
     timeout_timer_->Disable();
   } else {
-    timeout_timer_->Setup(event_loop_->monotonic_now() +
-                          std::chrono::milliseconds(timeout_ms));
+    timeout_timer_->Schedule(event_loop_->monotonic_now() +
+                             std::chrono::milliseconds(timeout_ms));
   }
 }
 
diff --git a/aos/events/glib_main_loop_test.cc b/aos/events/glib_main_loop_test.cc
index 43f7c7a..aabab68 100644
--- a/aos/events/glib_main_loop_test.cc
+++ b/aos/events/glib_main_loop_test.cc
@@ -37,7 +37,7 @@
         event_loop.Exit();
         ran = true;
       })
-      ->Setup(event_loop.monotonic_now() + std::chrono::milliseconds(100));
+      ->Schedule(event_loop.monotonic_now() + std::chrono::milliseconds(100));
   event_loop.Run();
   EXPECT_TRUE(ran);
 }
@@ -122,7 +122,7 @@
         event_loop.Exit();
         ran = true;
       })
-      ->Setup(event_loop.monotonic_now() + std::chrono::milliseconds(100));
+      ->Schedule(event_loop.monotonic_now() + std::chrono::milliseconds(100));
   event_loop.Run();
   EXPECT_TRUE(ran);
   EXPECT_EQ(runs, 1);
diff --git a/aos/events/logging/log_reader.cc b/aos/events/logging/log_reader.cc
index f805c66..0e346a0 100644
--- a/aos/events/logging/log_reader.cc
+++ b/aos/events/logging/log_reader.cc
@@ -210,7 +210,7 @@
       // Whops, time went backwards.  Just do it now.
       HandleTime();
     } else {
-      event_timer_->Setup(candidate_monotonic + clock_offset_);
+      event_timer_->Schedule(candidate_monotonic + clock_offset_);
     }
   }
 
@@ -1197,7 +1197,7 @@
       }
       // TODO(james): This can result in negative times getting passed-through
       // in realtime replay.
-      state->Setup(next_time.time);
+      state->Schedule(next_time.time);
     } else {
       VLOG(1) << MaybeNodeName(state->event_loop()->node())
               << "No next message, scheduling shutdown";
@@ -1208,8 +1208,8 @@
       // Doesn't apply to single-EventLoop replay since the watchers in question
       // are not under our control.
       if (event_loop_factory_ != nullptr) {
-        state->Setup(monotonic_now + event_loop_factory_->send_delay() +
-                     std::chrono::nanoseconds(1));
+        state->Schedule(monotonic_now + event_loop_factory_->send_delay() +
+                        std::chrono::nanoseconds(1));
       }
     }
 
@@ -1241,8 +1241,8 @@
                           std::chrono::duration<double>(
                               FLAGS_threaded_look_ahead_seconds)));
       state->MaybeSetClockOffset();
-      state->Setup(next_time.time);
-      state->SetupStartupTimer();
+      state->Schedule(next_time.time);
+      state->SetUpStartupTimer();
     });
   }
 }
@@ -2101,7 +2101,7 @@
 
   if (scheduled_time_ != remote_timestamps_.front().monotonic_timestamp_time) {
     CHECK_NOTNULL(timer_);
-    timer_->Setup(remote_timestamps_.front().monotonic_timestamp_time);
+    timer_->Schedule(remote_timestamps_.front().monotonic_timestamp_time);
     scheduled_time_ = remote_timestamps_.front().monotonic_timestamp_time;
     CHECK_GE(scheduled_time_, event_loop_->monotonic_now())
         << event_loop_->node()->name()->string_view();
diff --git a/aos/events/logging/log_reader.h b/aos/events/logging/log_reader.h
index 3bdfca4..fb6d6f9 100644
--- a/aos/events/logging/log_reader.h
+++ b/aos/events/logging/log_reader.h
@@ -471,7 +471,7 @@
     // OldestMessageTime.
     void SeedSortedMessages();
 
-    void SetupStartupTimer() {
+    void SetUpStartupTimer() {
       const monotonic_clock::time_point start_time =
           monotonic_start_time(boot_count());
       if (start_time == monotonic_clock::min_time) {
@@ -483,7 +483,7 @@
       if (node_event_loop_factory_) {
         CHECK_GE(start_time + clock_offset(), event_loop_->monotonic_now());
       }
-      startup_timer_->Setup(start_time + clock_offset());
+      startup_timer_->Schedule(start_time + clock_offset());
     }
 
     void set_startup_timer(TimerHandler *timer_handler) {
@@ -653,8 +653,8 @@
     void ClearTimeFlags();
 
     // Sets the next wakeup time on the replay callback.
-    void Setup(monotonic_clock::time_point next_time) {
-      timer_handler_->Setup(
+    void Schedule(monotonic_clock::time_point next_time) {
+      timer_handler_->Schedule(
           std::max(monotonic_now(), next_time + clock_offset()));
     }
 
diff --git a/aos/events/logging/log_writer.cc b/aos/events/logging/log_writer.cc
index 17c8da2..d129073 100644
--- a/aos/events/logging/log_writer.cc
+++ b/aos/events/logging/log_writer.cc
@@ -328,8 +328,8 @@
   // logged without ordering concerns.
   LogUntil(last_synchronized_time_);
 
-  timer_handler_->Setup(event_loop_->monotonic_now() + polling_period_,
-                        polling_period_);
+  timer_handler_->Schedule(event_loop_->monotonic_now() + polling_period_,
+                           polling_period_);
 }
 
 std::unique_ptr<LogNamer> Logger::RestartLogging(
diff --git a/aos/events/logging/logger_test.cc b/aos/events/logging/logger_test.cc
index 8b1b7fa..1c48d2c 100644
--- a/aos/events/logging/logger_test.cc
+++ b/aos/events/logging/logger_test.cc
@@ -434,8 +434,8 @@
 
     // 100 ms / 0.05 ms -> 2000 messages.  Should be enough to crash it.
     ping_spammer_event_loop->OnRun([&ping_spammer_event_loop, timer_handler]() {
-      timer_handler->Setup(ping_spammer_event_loop->monotonic_now(),
-                           chrono::microseconds(50));
+      timer_handler->Schedule(ping_spammer_event_loop->monotonic_now(),
+                              chrono::microseconds(50));
     });
 
     Logger logger(logger_event_loop.get());
@@ -496,7 +496,7 @@
 
     ping_spammer_event_loop->OnRun(
         [&ping_spammer_event_loop, kSendPeriod, timer_handler]() {
-          timer_handler->Setup(
+          timer_handler->Schedule(
               ping_spammer_event_loop->monotonic_now() + kSendPeriod / 2,
               kSendPeriod);
         });
diff --git a/aos/events/logging/realtime_replay_test.cc b/aos/events/logging/realtime_replay_test.cc
index a04da49..8c7751e 100644
--- a/aos/events/logging/realtime_replay_test.cc
+++ b/aos/events/logging/realtime_replay_test.cc
@@ -110,7 +110,7 @@
       shm_event_loop.MakeFetcher<examples::Ping>("/test");
 
   shm_event_loop.AddTimer([]() { LOG(INFO) << "Hello, World!"; })
-      ->Setup(shm_event_loop.monotonic_now(), std::chrono::seconds(1));
+      ->Schedule(shm_event_loop.monotonic_now(), std::chrono::seconds(1));
 
   shm_event_loop.Run();
   reader.Deregister();
@@ -149,7 +149,7 @@
       shm_event_loop.MakeFetcher<examples::Pong>("/test");
 
   shm_event_loop.AddTimer([]() { LOG(INFO) << "Hello, World!"; })
-      ->Setup(shm_event_loop.monotonic_now(), std::chrono::seconds(1));
+      ->Schedule(shm_event_loop.monotonic_now(), std::chrono::seconds(1));
 
   // End timer should not be called in this case, it should automatically quit
   // the event loop and check for number of fetches messages
@@ -165,8 +165,8 @@
       });
   shm_event_loop.OnRun([&shm_event_loop, end_timer, run_seconds]() {
     LOG(INFO) << "Quitting in: " << run_seconds;
-    end_timer->Setup(shm_event_loop.monotonic_now() +
-                     std::chrono::seconds(run_seconds));
+    end_timer->Schedule(shm_event_loop.monotonic_now() +
+                        std::chrono::seconds(run_seconds));
   });
 
   shm_event_loop.Run();
@@ -213,7 +213,7 @@
       shm_event_loop.MakeFetcher<examples::Ping>("/test");
 
   shm_event_loop.AddTimer([]() { LOG(INFO) << "Hello, World!"; })
-      ->Setup(shm_event_loop.monotonic_now(), std::chrono::seconds(1));
+      ->Schedule(shm_event_loop.monotonic_now(), std::chrono::seconds(1));
 
   shm_event_loop.Run();
   reader.Deregister();
@@ -262,7 +262,7 @@
       shm_event_loop.MakeFetcher<examples::Ping>("/test");
 
   shm_event_loop.AddTimer([]() { LOG(INFO) << "Hello, World!"; })
-      ->Setup(shm_event_loop.monotonic_now(), std::chrono::seconds(1));
+      ->Schedule(shm_event_loop.monotonic_now(), std::chrono::seconds(1));
 
   shm_event_loop.Run();
   reader.Deregister();
@@ -321,8 +321,8 @@
   size_t run_seconds = 3;
   shm_event_loop.OnRun([&shm_event_loop, end_timer, run_seconds]() {
     LOG(INFO) << "Quitting in: " << run_seconds;
-    end_timer->Setup(shm_event_loop.monotonic_now() +
-                     std::chrono::seconds(run_seconds));
+    end_timer->Schedule(shm_event_loop.monotonic_now() +
+                        std::chrono::seconds(run_seconds));
   });
 
   shm_event_loop.Run();
diff --git a/aos/events/ping_lib.cc b/aos/events/ping_lib.cc
index 8e7136d..a7a8dd4 100644
--- a/aos/events/ping_lib.cc
+++ b/aos/events/ping_lib.cc
@@ -25,8 +25,8 @@
   }
 
   event_loop_->OnRun([this]() {
-    timer_handle_->Setup(event_loop_->monotonic_now(),
-                         chrono::milliseconds(FLAGS_sleep_ms));
+    timer_handle_->Schedule(event_loop_->monotonic_now(),
+                            chrono::milliseconds(FLAGS_sleep_ms));
   });
 
   event_loop_->SetRuntimeRealtimePriority(5);
diff --git a/aos/events/shm_event_loop.cc b/aos/events/shm_event_loop.cc
index 3e1be99..09cd488 100644
--- a/aos/events/shm_event_loop.cc
+++ b/aos/events/shm_event_loop.cc
@@ -588,8 +588,8 @@
     disabled_ = false;
     const auto monotonic_now = Call(monotonic_clock::now, base_);
     if (event_.valid()) {
-      // If someone called Setup inside Call, rescheduling is already taken care
-      // of.  Bail.
+      // If someone called Schedule inside Call, rescheduling is already taken
+      // care of. Bail.
       return;
     }
     if (disabled_) {
@@ -618,8 +618,8 @@
     }
   }
 
-  void Setup(monotonic_clock::time_point base,
-             monotonic_clock::duration repeat_offset) override {
+  void Schedule(monotonic_clock::time_point base,
+                monotonic_clock::duration repeat_offset) override {
     shm_event_loop_->CheckCurrentThread();
     if (event_.valid()) {
       shm_event_loop_->RemoveEvent(&event_);
diff --git a/aos/events/shm_event_loop_test.cc b/aos/events/shm_event_loop_test.cc
index 55c4f03..5d58c29 100644
--- a/aos/events/shm_event_loop_test.cc
+++ b/aos/events/shm_event_loop_test.cc
@@ -144,7 +144,7 @@
           factory()->Exit();
           ran = true;
         })
-        ->Setup(loop1->monotonic_now() + std::chrono::seconds(4));
+        ->Schedule(loop1->monotonic_now() + std::chrono::seconds(4));
     factory()->Run();
     EXPECT_TRUE(ran);
   }
@@ -234,7 +234,7 @@
   loop->OnRun([&loop, &did_onrun, &sender, timer]() {
     EXPECT_TRUE(IsRealtime());
     did_onrun = true;
-    timer->Setup(loop->monotonic_now() + chrono::milliseconds(100));
+    timer->Schedule(loop->monotonic_now() + chrono::milliseconds(100));
 
     aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
     TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
diff --git a/aos/events/simulated_event_loop.cc b/aos/events/simulated_event_loop.cc
index 44b30f1..b17e5ff 100644
--- a/aos/events/simulated_event_loop.cc
+++ b/aos/events/simulated_event_loop.cc
@@ -478,8 +478,8 @@
                                  ::std::function<void()> fn);
   ~SimulatedTimerHandler() { Disable(); }
 
-  void Setup(monotonic_clock::time_point base,
-             monotonic_clock::duration repeat_offset) override;
+  void Schedule(monotonic_clock::time_point base,
+                monotonic_clock::duration repeat_offset) override;
 
   void HandleEvent() noexcept;
 
@@ -1155,8 +1155,8 @@
       scheduler_(scheduler),
       token_(scheduler_->InvalidToken()) {}
 
-void SimulatedTimerHandler::Setup(monotonic_clock::time_point base,
-                                  monotonic_clock::duration repeat_offset) {
+void SimulatedTimerHandler::Schedule(monotonic_clock::time_point base,
+                                     monotonic_clock::duration repeat_offset) {
   CHECK_GE(base, monotonic_clock::epoch());
   // The allocations in here are due to infrastructure and don't count in the no
   // mallocs in RT code.
diff --git a/aos/events/simulated_event_loop_test.cc b/aos/events/simulated_event_loop_test.cc
index c5daa7e..14e0a08 100644
--- a/aos/events/simulated_event_loop_test.cc
+++ b/aos/events/simulated_event_loop_test.cc
@@ -339,7 +339,7 @@
   });
 
   event_loop->OnRun([&event_loop, &timer] {
-    timer->Setup(event_loop->monotonic_now() + chrono::milliseconds(50));
+    timer->Schedule(event_loop->monotonic_now() + chrono::milliseconds(50));
   });
 
   simulated_event_loop_factory.Run();
@@ -400,8 +400,8 @@
   int counter = 0;
   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));
+    timer->Schedule(event_loop->monotonic_now() + chrono::milliseconds(50),
+                    chrono::milliseconds(100));
   });
 
   simulated_event_loop_factory.RunFor(chrono::seconds(1));
@@ -444,12 +444,12 @@
   // Quit after 1 timing report, mid way through the next cycle.
   {
     auto end_timer = loop1->AddTimer([&factory]() { factory.Exit(); });
-    end_timer->Setup(loop1->monotonic_now() + chrono::milliseconds(2500));
+    end_timer->Schedule(loop1->monotonic_now() + chrono::milliseconds(2500));
     end_timer->set_name("end");
   }
 
   loop1->OnRun([&test_timer, &loop1]() {
-    test_timer->Setup(loop1->monotonic_now() + chrono::milliseconds(1500));
+    test_timer->Schedule(loop1->monotonic_now() + chrono::milliseconds(1500));
   });
 
   factory.Run();
diff --git a/aos/events/simulated_network_bridge.cc b/aos/events/simulated_network_bridge.cc
index 682ec7b..acf439e 100644
--- a/aos/events/simulated_network_bridge.cc
+++ b/aos/events/simulated_network_bridge.cc
@@ -155,7 +155,7 @@
     if (timer_) {
       server_connection_->mutate_sent_packets(
           server_connection_->sent_packets() + 1);
-      timer_->Setup(monotonic_delivered_time);
+      timer_->Schedule(monotonic_delivered_time);
       timer_scheduled_ = true;
     } else {
       server_connection_->mutate_dropped_packets(
@@ -194,7 +194,7 @@
     if (timer_) {
       server_connection_->mutate_sent_packets(
           server_connection_->sent_packets() + 1);
-      timer_->Setup(monotonic_delivered_time);
+      timer_->Schedule(monotonic_delivered_time);
       timer_scheduled_ = true;
     } else {
       server_connection_->mutate_dropped_packets(
@@ -328,7 +328,7 @@
 
     if (scheduled_time_ !=
         remote_timestamps_.front().monotonic_timestamp_time) {
-      timestamp_timer_->Setup(
+      timestamp_timer_->Schedule(
           remote_timestamps_.front().monotonic_timestamp_time);
       scheduled_time_ = remote_timestamps_.front().monotonic_timestamp_time;
       return;
diff --git a/aos/logging/dynamic_logging_test.cc b/aos/logging/dynamic_logging_test.cc
index 2d051a8..9b78113 100644
--- a/aos/logging/dynamic_logging_test.cc
+++ b/aos/logging/dynamic_logging_test.cc
@@ -52,18 +52,18 @@
         CHECK_EQ(message.Send(builder.Finish()), RawSender::Error::kOk);
         --log_level;
         if (log_level >= 0) {
-          timer_handler->Setup(event_loop_send_->monotonic_now() +
-                               chrono::microseconds(100));
+          timer_handler->Schedule(event_loop_send_->monotonic_now() +
+                                  chrono::microseconds(100));
         }
       });
-  timer_handler->Setup(event_loop_send_->monotonic_now() +
-                       chrono::microseconds(50));
+  timer_handler->Schedule(event_loop_send_->monotonic_now() +
+                          chrono::microseconds(50));
 
   // VLOG(1) at t=0us, t=100us, t=200us
   aos::TimerHandler *vlog_timer_handler =
       event_loop_main_->AddTimer([]() { VLOG(1) << "VLOG 1"; });
-  vlog_timer_handler->Setup(event_loop_main_->monotonic_now(),
-                            chrono::microseconds(100));
+  vlog_timer_handler->Schedule(event_loop_main_->monotonic_now(),
+                               chrono::microseconds(100));
 
   DynamicLogging dynamic_logging(event_loop_main_.get());
 
diff --git a/aos/network/log_web_proxy_main.cc b/aos/network/log_web_proxy_main.cc
index 7833808..f93c5a2 100644
--- a/aos/network/log_web_proxy_main.cc
+++ b/aos/network/log_web_proxy_main.cc
@@ -57,7 +57,7 @@
 
   if (FLAGS_monotonic_start_time > 0) {
     event_loop->AddTimer([&reader]() { reader.event_loop_factory()->Exit(); })
-        ->Setup(aos::monotonic_clock::time_point(
+        ->Schedule(aos::monotonic_clock::time_point(
             std::chrono::duration_cast<std::chrono::nanoseconds>(
                 std::chrono::duration<double>(FLAGS_monotonic_start_time))));
 
@@ -72,7 +72,7 @@
 
   if (FLAGS_monotonic_end_time > 0) {
     event_loop->AddTimer([&web_proxy]() { web_proxy.StopRecording(); })
-        ->Setup(aos::monotonic_clock::time_point(
+        ->Schedule(aos::monotonic_clock::time_point(
             std::chrono::duration_cast<std::chrono::nanoseconds>(
                 std::chrono::duration<double>(FLAGS_monotonic_end_time))));
   }
diff --git a/aos/network/message_bridge_client_lib.cc b/aos/network/message_bridge_client_lib.cc
index 38512c4..a340553 100644
--- a/aos/network/message_bridge_client_lib.cc
+++ b/aos/network/message_bridge_client_lib.cc
@@ -127,7 +127,7 @@
   connect_timer_->set_name(std::string("connect_") +
                            remote_node_->name()->str());
   event_loop_->OnRun(
-      [this]() { connect_timer_->Setup(event_loop_->monotonic_now()); });
+      [this]() { connect_timer_->Schedule(event_loop_->monotonic_now()); });
 
   size_t max_write_size =
       std::max(kHeaderSizeOverhead(), connect_message_.span().size());
@@ -248,7 +248,7 @@
 void SctpClientConnection::NodeDisconnected() {
   client_.SetAssociationId(0);
 
-  connect_timer_->Setup(
+  connect_timer_->Schedule(
       event_loop_->monotonic_now() + chrono::milliseconds(100),
       chrono::milliseconds(100));
   client_status_->Disconnect(client_index_);
diff --git a/aos/network/message_bridge_client_lib.h b/aos/network/message_bridge_client_lib.h
index 6e108df..a5a69e3 100644
--- a/aos/network/message_bridge_client_lib.h
+++ b/aos/network/message_bridge_client_lib.h
@@ -59,8 +59,8 @@
   // gets dropped, the server might be waiting for this, so if we don't hear
   // from the server for a while we'll try sending it again.
   void ScheduleConnectTimeout() {
-    connect_timer_->Setup(event_loop_->context().monotonic_event_time +
-                          kReconnectTimeout);
+    connect_timer_->Schedule(event_loop_->context().monotonic_event_time +
+                             kReconnectTimeout);
   }
 
   // Event loop to register the server on.
diff --git a/aos/network/message_bridge_client_status.cc b/aos/network/message_bridge_client_status.cc
index f3511a0..2ba2ae0 100644
--- a/aos/network/message_bridge_client_status.cc
+++ b/aos/network/message_bridge_client_status.cc
@@ -67,8 +67,8 @@
   statistics_timer_->set_name("statistics");
   event_loop_->OnRun([this]() {
     if (send_) {
-      statistics_timer_->Setup(event_loop_->monotonic_now() + kStatisticsPeriod,
-                               kStatisticsPeriod);
+      statistics_timer_->Schedule(
+          event_loop_->monotonic_now() + kStatisticsPeriod, kStatisticsPeriod);
     }
   });
 }
@@ -230,8 +230,8 @@
 void MessageBridgeClientStatus::EnableStatistics() {
   CHECK(sender_.valid());
   send_ = true;
-  statistics_timer_->Setup(event_loop_->monotonic_now() + kStatisticsPeriod,
-                           kStatisticsPeriod);
+  statistics_timer_->Schedule(event_loop_->monotonic_now() + kStatisticsPeriod,
+                              kStatisticsPeriod);
 }
 
 }  // namespace message_bridge
diff --git a/aos/network/message_bridge_server_status.cc b/aos/network/message_bridge_server_status.cc
index df87134..96917f1 100644
--- a/aos/network/message_bridge_server_status.cc
+++ b/aos/network/message_bridge_server_status.cc
@@ -131,8 +131,8 @@
       event_loop_->node()->name()->string_view(), "_server_statistics"));
   event_loop_->OnRun([this]() {
     if (send_) {
-      statistics_timer_->Setup(event_loop_->monotonic_now() + kPingPeriod,
-                               kPingPeriod);
+      statistics_timer_->Schedule(event_loop_->monotonic_now() + kPingPeriod,
+                                  kPingPeriod);
     }
   });
 }
@@ -433,8 +433,8 @@
   send_ = true;
   CHECK(sender_.valid());
   CHECK(timestamp_sender_.valid());
-  statistics_timer_->Setup(event_loop_->monotonic_now() + kPingPeriod,
-                           kPingPeriod);
+  statistics_timer_->Schedule(event_loop_->monotonic_now() + kPingPeriod,
+                              kPingPeriod);
 }
 
 }  // namespace message_bridge
diff --git a/aos/network/message_bridge_test.cc b/aos/network/message_bridge_test.cc
index 153f1e5..07a56f0 100644
--- a/aos/network/message_bridge_test.cc
+++ b/aos/network/message_bridge_test.cc
@@ -89,12 +89,12 @@
   }
 
   void RunPi1Server(chrono::nanoseconds duration) {
-    // Setup a shutdown callback.
+    // Set up a shutdown callback.
     aos::TimerHandler *const quit = pi1_server_event_loop->AddTimer(
         [this]() { pi1_server_event_loop->Exit(); });
     pi1_server_event_loop->OnRun([this, quit, duration]() {
       // Stop between timestamps, not exactly on them.
-      quit->Setup(pi1_server_event_loop->monotonic_now() + duration);
+      quit->Schedule(pi1_server_event_loop->monotonic_now() + duration);
     });
 
     pi1_server_event_loop->Run();
@@ -193,12 +193,12 @@
   }
 
   void RunPi2Server(chrono::nanoseconds duration) {
-    // Setup a shutdown callback.
+    // Set up a shutdown callback.
     aos::TimerHandler *const quit = pi2_server_event_loop->AddTimer(
         [this]() { pi2_server_event_loop->Exit(); });
     pi2_server_event_loop->OnRun([this, quit, duration]() {
       // Stop between timestamps, not exactly on them.
-      quit->Setup(pi2_server_event_loop->monotonic_now() + duration);
+      quit->Schedule(pi2_server_event_loop->monotonic_now() + duration);
     });
 
     pi2_server_event_loop->Run();
@@ -237,7 +237,7 @@
         [this]() { pi2_client_event_loop->Exit(); });
     pi2_client_event_loop->OnRun([this, quit, duration]() {
       // Stop between timestamps, not exactly on them.
-      quit->Setup(pi2_client_event_loop->monotonic_now() + duration);
+      quit->Schedule(pi2_client_event_loop->monotonic_now() + duration);
     });
 
     // And go!
@@ -594,7 +594,8 @@
       [&ping_event_loop]() { ping_event_loop.Exit(); });
   ping_event_loop.OnRun([quit, &ping_event_loop]() {
     // Stop between timestamps, not exactly on them.
-    quit->Setup(ping_event_loop.monotonic_now() + chrono::milliseconds(5050));
+    quit->Schedule(ping_event_loop.monotonic_now() +
+                   chrono::milliseconds(5050));
   });
 
   // Find the channel index for both the /pi1/aos Timestamp channel and Ping
diff --git a/aos/network/multinode_timestamp_filter_test.cc b/aos/network/multinode_timestamp_filter_test.cc
index 1446e77..9b37806 100644
--- a/aos/network/multinode_timestamp_filter_test.cc
+++ b/aos/network/multinode_timestamp_filter_test.cc
@@ -431,7 +431,7 @@
   const BootTimestamp e{0, monotonic_clock::epoch()};
   const BootTimestamp ta = e + chrono::milliseconds(500);
 
-  // Setup a time problem with an interesting shape that isn't simple and
+  // Set up a time problem with an interesting shape that isn't simple and
   // parallel.
   NoncausalTimestampFilter a(node_a, node_b);
   a.Sample(e, {0, chrono::milliseconds(1000)});
diff --git a/aos/network/web_proxy.cc b/aos/network/web_proxy.cc
index d7ab418..7f52611 100644
--- a/aos/network/web_proxy.cc
+++ b/aos/network/web_proxy.cc
@@ -65,7 +65,8 @@
   });
 
   event_loop_->OnRun([this, timer]() {
-    timer->Setup(event_loop_->monotonic_now(), std::chrono::milliseconds(100));
+    timer->Schedule(event_loop_->monotonic_now(),
+                    std::chrono::milliseconds(100));
   });
 }
 
@@ -189,7 +190,8 @@
     });
 
     event_loop->OnRun([timer, event_loop]() {
-      timer->Setup(event_loop->monotonic_now(), std::chrono::milliseconds(10));
+      timer->Schedule(event_loop->monotonic_now(),
+                      std::chrono::milliseconds(10));
     });
   }
 }
@@ -237,7 +239,7 @@
           fbb.Finish(message_offset);
 
           // Now, the flatbuffer is built from the back to the front.  So any
-          // extra memory will be at the front.  Setup the end and start
+          // extra memory will be at the front.  Set up the end and start
           // pointers on the mbuf.
           mbuf_set_end(mbuffer, packet_size);
           mbuf_set_pos(mbuffer, packet_size - fbb.GetSize());
diff --git a/aos/network/www/demo_plot.ts b/aos/network/www/demo_plot.ts
index b586411..19bb4a5 100644
--- a/aos/network/www/demo_plot.ts
+++ b/aos/network/www/demo_plot.ts
@@ -33,7 +33,7 @@
   const aosPlotter = new AosPlotter(conn);
 
   {
-    // Setup a plot that shows some arbitrary PDP current values.
+    // Set up a plot that shows some arbitrary PDP current values.
     const pdpValues =
         aosPlotter.addMessageSource('/aos', 'frc971.PDPValues');
     const timingPlot = aosPlotter.addPlot(parentDiv);
@@ -55,7 +55,7 @@
   {
     const timingReport =
         aosPlotter.addMessageSource('/aos', 'aos.timing.Report');
-    // Setup a plot that just shows some arbitrary timing data.
+    // Set up a plot that just shows some arbitrary timing data.
     const timingPlot = aosPlotter.addPlot(parentDiv);
     timingPlot.plot.getAxisLabels().setTitle('Timing Report Wakeups');
     timingPlot.plot.getAxisLabels().setYLabel('PID');
diff --git a/aos/starter/mock_starter.cc b/aos/starter/mock_starter.cc
index 1e06758..9f9a2b5 100644
--- a/aos/starter/mock_starter.cc
+++ b/aos/starter/mock_starter.cc
@@ -59,7 +59,7 @@
   }
 
   event_loop_->OnRun([this, send_timer]() {
-    send_timer->Setup(event_loop_->monotonic_now(), std::chrono::seconds(1));
+    send_timer->Schedule(event_loop_->monotonic_now(), std::chrono::seconds(1));
 
     for (const aos::Application *application :
          *event_loop_->configuration()->applications()) {
diff --git a/aos/starter/starter_rpc_lib.cc b/aos/starter/starter_rpc_lib.cc
index 7f8f53c..4e9ceef 100644
--- a/aos/starter/starter_rpc_lib.cc
+++ b/aos/starter/starter_rpc_lib.cc
@@ -176,7 +176,7 @@
     builder.CheckOk(builder.Send(command_builder.Finish()));
   }
 
-  timeout_timer_->Setup(event_loop_->monotonic_now() + timeout);
+  timeout_timer_->Schedule(event_loop_->monotonic_now() + timeout);
 }
 
 bool StarterClient::CheckCommandsSucceeded() {
diff --git a/aos/starter/starter_test.cc b/aos/starter/starter_test.cc
index 37efa98..fcbf287 100644
--- a/aos/starter/starter_test.cc
+++ b/aos/starter/starter_test.cc
@@ -35,8 +35,8 @@
             starter->Cleanup();
           }
         })
-        ->Setup(starter->event_loop()->monotonic_now(),
-                std::chrono::milliseconds(100));
+        ->Schedule(starter->event_loop()->monotonic_now(),
+                   std::chrono::milliseconds(100));
   }
 
   gflags::FlagSaver flag_saver_;
@@ -109,7 +109,7 @@
         watcher_loop.Exit();
         FAIL();
       })
-      ->Setup(watcher_loop.monotonic_now() + std::chrono::seconds(7));
+      ->Schedule(watcher_loop.monotonic_now() + std::chrono::seconds(7));
 
   std::atomic<int> test_stage = 0;
   // Watch on the client loop since we need to interact with the StarterClient.
@@ -228,7 +228,7 @@
         watcher_loop.Exit();
         FAIL();
       })
-      ->Setup(watcher_loop.monotonic_now() + std::chrono::seconds(11));
+      ->Schedule(watcher_loop.monotonic_now() + std::chrono::seconds(11));
 
   int test_stage = 0;
   uint64_t id;
@@ -323,7 +323,7 @@
         watcher_loop.Exit();
         FAIL();
       })
-      ->Setup(watcher_loop.monotonic_now() + std::chrono::seconds(7));
+      ->Schedule(watcher_loop.monotonic_now() + std::chrono::seconds(7));
 
   int pong_running_count = 0;
   watcher_loop.MakeWatcher("/aos", [&watcher_loop, &pong_running_count](
@@ -420,7 +420,7 @@
         watcher_loop.Exit();
         SUCCEED();
       })
-      ->Setup(watcher_loop.monotonic_now() + std::chrono::seconds(11));
+      ->Schedule(watcher_loop.monotonic_now() + std::chrono::seconds(11));
 
   int test_stage = 0;
   uint64_t id;
@@ -521,7 +521,7 @@
                   "The chain of stages defined below did not complete "
                   "within the time limit.";
       })
-      ->Setup(client_loop.monotonic_now() + std::chrono::seconds(20));
+      ->Schedule(client_loop.monotonic_now() + std::chrono::seconds(20));
 
   // variables have been defined, here we define the body of the test.
   // We want stage1 to succeed, triggering stage2.
@@ -570,8 +570,8 @@
     LOG(INFO) << "End stage1";
   };
   // start the test body
-  client_loop.AddTimer(stage1)->Setup(client_loop.monotonic_now() +
-                                      std::chrono::milliseconds(1));
+  client_loop.AddTimer(stage1)->Schedule(client_loop.monotonic_now() +
+                                         std::chrono::milliseconds(1));
 
   // prepare the cleanup for starter. This will finish when we call
   // `test_done_ = true;`.
diff --git a/aos/starter/starterd_lib.cc b/aos/starter/starterd_lib.cc
index 949c8a7..7c94863 100644
--- a/aos/starter/starterd_lib.cc
+++ b/aos/starter/starterd_lib.cc
@@ -50,8 +50,8 @@
   event_loop_.SkipAosLog();
 
   event_loop_.OnRun([this] {
-    status_timer_->Setup(event_loop_.monotonic_now(),
-                         std::chrono::milliseconds(1000));
+    status_timer_->Schedule(event_loop_.monotonic_now(),
+                            std::chrono::milliseconds(1000));
   });
 
   if (!aos::configuration::MultiNode(config_msg_)) {
@@ -172,8 +172,8 @@
   for (auto &application : applications_) {
     application.second.Terminate();
   }
-  cleanup_timer_->Setup(event_loop_.monotonic_now() +
-                        std::chrono::milliseconds(1500));
+  cleanup_timer_->Schedule(event_loop_.monotonic_now() +
+                           std::chrono::milliseconds(1500));
 }
 
 void Starter::OnSignal(signalfd_siginfo info) {
diff --git a/aos/starter/subprocess.cc b/aos/starter/subprocess.cc
index b86b12d..d907d3f 100644
--- a/aos/starter/subprocess.cc
+++ b/aos/starter/subprocess.cc
@@ -125,8 +125,8 @@
     // Every second poll to check if the child is dead. This is used as a
     // default for the case where the user is not directly catching SIGCHLD and
     // calling MaybeHandleSignal for us.
-    child_status_handler_->Setup(event_loop_->monotonic_now(),
-                                 std::chrono::seconds(1));
+    child_status_handler_->Schedule(event_loop_->monotonic_now(),
+                                    std::chrono::seconds(1));
   });
 }
 
@@ -172,8 +172,8 @@
     stderr_.clear();
   }
 
-  pipe_timer_->Setup(event_loop_->monotonic_now(),
-                     std::chrono::milliseconds(100));
+  pipe_timer_->Schedule(event_loop_->monotonic_now(),
+                        std::chrono::milliseconds(100));
 
   const pid_t pid = fork();
 
@@ -189,10 +189,10 @@
       status_ = aos::starter::State::STARTING;
       LOG(INFO) << "Starting '" << name_ << "' pid " << pid_;
 
-      // Setup timer which moves application to RUNNING state if it is still
+      // Set up timer which moves application to RUNNING state if it is still
       // alive in 1 second.
-      start_timer_->Setup(event_loop_->monotonic_now() +
-                          std::chrono::seconds(1));
+      start_timer_->Schedule(event_loop_->monotonic_now() +
+                             std::chrono::seconds(1));
       // Since we are the parent process, clear our write-side of all the pipes.
       status_pipes_.write.reset();
       stdout_pipes_.write.reset();
@@ -331,8 +331,8 @@
 
       // Watchdog timer to SIGKILL application if it is still running 1 second
       // after SIGINT
-      stop_timer_->Setup(event_loop_->monotonic_now() +
-                         std::chrono::seconds(1));
+      stop_timer_->Schedule(event_loop_->monotonic_now() +
+                            std::chrono::seconds(1));
       queue_restart_ = restart;
       on_change_();
       break;
@@ -370,7 +370,8 @@
   status_ = aos::starter::State::WAITING;
 
   LOG(INFO) << "Restarting " << name_ << " in 3 seconds";
-  restart_timer_->Setup(event_loop_->monotonic_now() + std::chrono::seconds(3));
+  restart_timer_->Schedule(event_loop_->monotonic_now() +
+                           std::chrono::seconds(3));
   start_timer_->Disable();
   stop_timer_->Disable();
   on_change_();
diff --git a/aos/starter/subprocess_test.cc b/aos/starter/subprocess_test.cc
index d7f8be4..3633d1f 100644
--- a/aos/starter/subprocess_test.cc
+++ b/aos/starter/subprocess_test.cc
@@ -47,8 +47,8 @@
   event_loop.OnRun([&event_loop, exit_timer]() {
     // Note: we are using the backup poll in this test to capture SIGCHLD.  This
     // runs at 1 hz, so make sure we let it run at least once.
-    exit_timer->Setup(event_loop.monotonic_now() +
-                      std::chrono::milliseconds(1500));
+    exit_timer->Schedule(event_loop.monotonic_now() +
+                         std::chrono::milliseconds(1500));
   });
 
   event_loop.Run();
@@ -90,7 +90,7 @@
   // Note: we are using the backup poll in this test to capture SIGCHLD.  This
   // runs at 1 hz, so make sure we let it run at least once.
   event_loop.AddTimer([&event_loop]() { event_loop.Exit(); })
-      ->Setup(event_loop.monotonic_now() + std::chrono::milliseconds(1500));
+      ->Schedule(event_loop.monotonic_now() + std::chrono::milliseconds(1500));
 
   event_loop.Run();
 
diff --git a/aos/util/clock_publisher.cc b/aos/util/clock_publisher.cc
index 93102f6..f8c731f 100644
--- a/aos/util/clock_publisher.cc
+++ b/aos/util/clock_publisher.cc
@@ -8,8 +8,8 @@
   aos::TimerHandler *timer_handler =
       event_loop->AddTimer([this]() { SendTimepoints(); });
   event_loop->OnRun([timer_handler, event_loop]() {
-    timer_handler->Setup(event_loop->context().monotonic_event_time,
-                         std::chrono::seconds(1));
+    timer_handler->Schedule(event_loop->context().monotonic_event_time,
+                            std::chrono::seconds(1));
   });
 }
 
diff --git a/aos/util/foxglove_websocket_lib.cc b/aos/util/foxglove_websocket_lib.cc
index ab99400..fd2cfd4 100644
--- a/aos/util/foxglove_websocket_lib.cc
+++ b/aos/util/foxglove_websocket_lib.cc
@@ -154,7 +154,7 @@
   });
 
   event_loop_->OnRun([timer, this]() {
-    timer->Setup(event_loop_->monotonic_now(), kPollPeriod);
+    timer->Schedule(event_loop_->monotonic_now(), kPollPeriod);
   });
 }
 FoxgloveWebsocketServer::~FoxgloveWebsocketServer() { server_.stop(); }
diff --git a/aos/util/mcap_logger.cc b/aos/util/mcap_logger.cc
index 4fb727c..cdac928 100644
--- a/aos/util/mcap_logger.cc
+++ b/aos/util/mcap_logger.cc
@@ -122,7 +122,7 @@
       canonical_channels_(canonical_channels),
       compression_(compression),
       configuration_channel_([]() {
-        // Setup a fake Channel for providing the configuration in the MCAP
+        // Set up a fake Channel for providing the configuration in the MCAP
         // file. This is included for convenience so that consumers of the MCAP
         // file can actually dereference things like the channel indices in AOS
         // timing reports.
diff --git a/aos/util/top.cc b/aos/util/top.cc
index 852bb79..a74b019 100644
--- a/aos/util/top.cc
+++ b/aos/util/top.cc
@@ -131,7 +131,7 @@
       track_threads_(track_threads) {
   TimerHandler *timer = event_loop_->AddTimer([this]() { UpdateReadings(); });
   event_loop_->OnRun([timer, this]() {
-    timer->Setup(event_loop_->monotonic_now(), kSamplePeriod);
+    timer->Schedule(event_loop_->monotonic_now(), kSamplePeriod);
   });
 }
 
diff --git a/aos/util/top_test.cc b/aos/util/top_test.cc
index 7d413a4..6888457 100644
--- a/aos/util/top_test.cc
+++ b/aos/util/top_test.cc
@@ -63,7 +63,7 @@
   Top top(&event_loop_);
   top.set_track_pids({pid});
   event_loop_.AddTimer([this]() { event_loop_.Exit(); })
-      ->Setup(event_loop_.monotonic_now() + std::chrono::seconds(2));
+      ->Schedule(event_loop_.monotonic_now() + std::chrono::seconds(2));
   event_loop_.Run();
   flatbuffers::FlatBufferBuilder fbb;
   fbb.ForceDefaults(true);
@@ -111,7 +111,7 @@
   Top top(&event_loop_);
   top.set_track_top_processes(true);
   event_loop_.AddTimer([this]() { event_loop_.Exit(); })
-      ->Setup(event_loop_.monotonic_now() + std::chrono::seconds(2));
+      ->Schedule(event_loop_.monotonic_now() + std::chrono::seconds(2));
   event_loop_.SkipTimingReport();
   event_loop_.SkipAosLog();
   event_loop_.Run();
@@ -155,7 +155,7 @@
   Top top(&event_loop_);
   top.set_track_top_processes(true);
   event_loop_.AddTimer([this]() { event_loop_.Exit(); })
-      ->Setup(event_loop_.monotonic_now() + std::chrono::seconds(2));
+      ->Schedule(event_loop_.monotonic_now() + std::chrono::seconds(2));
   event_loop_.Run();
   flatbuffers::FlatBufferBuilder fbb;
   fbb.ForceDefaults(true);