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/y2023/autonomous/autonomous_actor.cc b/y2023/autonomous/autonomous_actor.cc
index e1b4e1d..bedbab7 100644
--- a/y2023/autonomous/autonomous_actor.cc
+++ b/y2023/autonomous/autonomous_actor.cc
@@ -61,8 +61,9 @@
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));
});
// TODO(james): Really need to refactor this code since we keep using it.
@@ -83,12 +84,12 @@
// 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));
}
}
}
@@ -97,7 +98,7 @@
void AutonomousActor::Replan() {
if (!drivetrain_status_fetcher_.Fetch()) {
- replan_timer_->Setup(event_loop()->monotonic_now() + chrono::seconds(1));
+ replan_timer_->Schedule(event_loop()->monotonic_now() + chrono::seconds(1));
AOS_LOG(INFO, "Drivetrain not up, replanning in 1 second");
return;
}
diff --git a/y2023/localizer/localizer_test.cc b/y2023/localizer/localizer_test.cc
index f7efc9c..fb0efa9 100644
--- a/y2023/localizer/localizer_test.cc
+++ b/y2023/localizer/localizer_test.cc
@@ -86,8 +86,8 @@
}
});
roborio_test_event_loop_->OnRun([timer, this]() {
- timer->Setup(roborio_test_event_loop_->monotonic_now(),
- std::chrono::milliseconds(5));
+ timer->Schedule(roborio_test_event_loop_->monotonic_now(),
+ std::chrono::milliseconds(5));
});
}
{
@@ -168,8 +168,8 @@
builder.CheckOk(builder.Send(map_builder.Finish()));
});
camera_test_event_loop_->OnRun([timer, this]() {
- timer->Setup(camera_test_event_loop_->monotonic_now(),
- std::chrono::milliseconds(50));
+ timer->Schedule(camera_test_event_loop_->monotonic_now(),
+ std::chrono::milliseconds(50));
});
}
@@ -203,7 +203,7 @@
localizer_control_x_ = x;
localizer_control_y_ = y;
localizer_control_theta_ = theta;
- localizer_control_send_timer_->Setup(
+ localizer_control_send_timer_->Schedule(
roborio_test_event_loop_->monotonic_now());
}
::testing::AssertionResult IsNear(double expected, double actual,
diff --git a/y2023/vision/camera_monitor_lib.cc b/y2023/vision/camera_monitor_lib.cc
index c4ec0dc..61fd6ed 100644
--- a/y2023/vision/camera_monitor_lib.cc
+++ b/y2023/vision/camera_monitor_lib.cc
@@ -31,7 +31,7 @@
}
void CameraMonitor::SetImageTimeout() {
- image_timeout_->Setup(event_loop_->context().monotonic_event_time +
- kImageTimeout);
+ image_timeout_->Schedule(event_loop_->context().monotonic_event_time +
+ kImageTimeout);
}
} // namespace y2023::vision
diff --git a/y2023/wpilib_interface.cc b/y2023/wpilib_interface.cc
index cc911ab..978d6e5 100644
--- a/y2023/wpilib_interface.cc
+++ b/y2023/wpilib_interface.cc
@@ -297,7 +297,8 @@
timer_handler_->set_name("CANSensorReader Loop");
event_loop->OnRun([this]() {
- timer_handler_->Setup(event_loop_->monotonic_now(), 1 / kCANUpdateFreqHz);
+ timer_handler_->Schedule(event_loop_->monotonic_now(),
+ 1 / kCANUpdateFreqHz);
});
}
@@ -987,7 +988,7 @@
AddLoop(&sensor_reader_event_loop);
// Thread 5.
- // Setup CAN.
+ // Set up CAN.
if (!FLAGS_ctre_diag_server) {
c_Phoenix_Diagnostics_SetSecondsToStart(-1);
c_Phoenix_Diagnostics_Dispose();
@@ -1022,7 +1023,7 @@
AddLoop(&can_output_event_loop);
// Thread 6
- // Setup superstructure output
+ // Set up superstructure output.
::aos::ShmEventLoop output_event_loop(&config.message());
output_event_loop.set_name("PWMOutputWriter");
SuperstructureWriter superstructure_writer(&output_event_loop);
@@ -1039,7 +1040,7 @@
AddLoop(&output_event_loop);
// Thread 7
- // Setup led_indicator
+ // Set up led_indicator.
::aos::ShmEventLoop led_indicator_event_loop(&config.message());
led_indicator_event_loop.set_name("LedIndicator");
control_loops::superstructure::LedIndicator led_indicator(