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/y2022/actors/autonomous_actor.cc b/y2022/actors/autonomous_actor.cc
index e4e3f9d..19e9edf 100644
--- a/y2022/actors/autonomous_actor.cc
+++ b/y2022/actors/autonomous_actor.cc
@@ -57,8 +57,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]() {
@@ -77,12 +78,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/y2022/localizer/localizer.cc b/y2022/localizer/localizer.cc
index b774e18..ab91db3 100644
--- a/y2022/localizer/localizer.cc
+++ b/y2022/localizer/localizer.cc
@@ -897,8 +897,8 @@
}
});
event_loop_->OnRun([this, superstructure_timer]() {
- superstructure_timer->Setup(event_loop_->monotonic_now(),
- std::chrono::milliseconds(20));
+ superstructure_timer->Schedule(event_loop_->monotonic_now(),
+ std::chrono::milliseconds(20));
});
for (size_t camera_index = 0; camera_index < kPisToUse.size();
@@ -949,8 +949,8 @@
}
});
event_loop_->OnRun([this, estimate_timer]() {
- estimate_timer->Setup(event_loop_->monotonic_now(),
- std::chrono::milliseconds(100));
+ estimate_timer->Schedule(event_loop_->monotonic_now(),
+ std::chrono::milliseconds(100));
});
}
diff --git a/y2022/localizer/localizer_test.cc b/y2022/localizer/localizer_test.cc
index 6083143..0db26b6 100644
--- a/y2022/localizer/localizer_test.cc
+++ b/y2022/localizer/localizer_test.cc
@@ -420,8 +420,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));
});
}
{
@@ -474,8 +474,8 @@
builder.Send(TargetEstimate::Pack(*builder.fbb(), estimate.get())));
});
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));
});
}
@@ -508,7 +508,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/y2022/vision/camera_reader.cc b/y2022/vision/camera_reader.cc
index ba7abaf..012a2db 100644
--- a/y2022/vision/camera_reader.cc
+++ b/y2022/vision/camera_reader.cc
@@ -197,8 +197,8 @@
}
// If we are not reading from the disk, we read the live camera stream.
if (!reader_->ReadLatestImage()) {
- 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;
}
@@ -212,7 +212,7 @@
ProcessImage(image_mat, image.monotonic_timestamp_ns());
reader_->SendLatestImage();
- read_image_timer_->Setup(event_loop_->monotonic_now());
+ read_image_timer_->Schedule(event_loop_->monotonic_now());
// Disable the LEDs based on localizer output
if (localizer_output_fetcher_.Fetch()) {
diff --git a/y2022/vision/camera_reader.h b/y2022/vision/camera_reader.h
index 7f07704..8782886 100644
--- a/y2022/vision/camera_reader.h
+++ b/y2022/vision/camera_reader.h
@@ -109,8 +109,9 @@
gpio_pwm_control_(GPIOPWMControl(GPIO_PIN_SCK_PWM, duty_cycle_)),
gpio_disable_control_(
GPIOControl(GPIO_PIN_MOSI_DISABLE, kGPIOOut, kGPIOLow)) {
- event_loop->OnRun(
- [this]() { read_image_timer_->Setup(event_loop_->monotonic_now()); });
+ event_loop->OnRun([this]() {
+ read_image_timer_->Schedule(event_loop_->monotonic_now());
+ });
}
void SetDutyCycle(double duty_cycle) {
diff --git a/y2022/vision/gpio.h b/y2022/vision/gpio.h
index bc9aa8a..6ed7328 100644
--- a/y2022/vision/gpio.h
+++ b/y2022/vision/gpio.h
@@ -332,13 +332,13 @@
// If the leds are currently off, turn them on for duty_cycle % of
// period If they are currently on, turn them off for 1 -
// duty_cycle % of period
- pwm_timer_->Setup(
+ pwm_timer_->Schedule(
event_loop_->monotonic_now() +
std::chrono::microseconds(leds_on_ ? (period_us - on_time_us)
: on_time_us));
leds_on_ = !leds_on_;
})) {
- pwm_timer_->Setup(event_loop_->monotonic_now());
+ pwm_timer_->Schedule(event_loop_->monotonic_now());
};
void set_duty_cycle(double duty_cycle) { duty_cycle_ = duty_cycle; }
diff --git a/y2022/vision/image_decimator.cc b/y2022/vision/image_decimator.cc
index b3cf2e0..e83659d 100644
--- a/y2022/vision/image_decimator.cc
+++ b/y2022/vision/image_decimator.cc
@@ -23,8 +23,8 @@
}
});
event_loop->OnRun([event_loop, timer]() {
- timer->Setup(event_loop->monotonic_now(),
- std::chrono::milliseconds(1000));
+ timer->Schedule(event_loop->monotonic_now(),
+ std::chrono::milliseconds(1000));
});
}