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/frc971/wpilib/ADIS16470.cc b/frc971/wpilib/ADIS16470.cc
index 95d5baf..1612ee8 100644
--- a/frc971/wpilib/ADIS16470.cc
+++ b/frc971/wpilib/ADIS16470.cc
@@ -283,8 +283,8 @@
state_ = State::kWaitForReset;
// Datasheet says it takes 193 ms to come out of reset, so give it some
// margin on top of that.
- initialize_timer_->Setup(event_loop_->monotonic_now() +
- chrono::milliseconds(250));
+ initialize_timer_->Schedule(event_loop_->monotonic_now() +
+ chrono::milliseconds(250));
} break;
case State::kWaitForReset: {
diff --git a/frc971/wpilib/ADIS16470.h b/frc971/wpilib/ADIS16470.h
index a87ca1b..35bcb06 100644
--- a/frc971/wpilib/ADIS16470.h
+++ b/frc971/wpilib/ADIS16470.h
@@ -71,8 +71,8 @@
void BeginInitialization() {
state_ = State::kUninitialized;
- initialize_timer_->Setup(event_loop_->monotonic_now() +
- std::chrono::milliseconds(25));
+ initialize_timer_->Schedule(event_loop_->monotonic_now() +
+ std::chrono::milliseconds(25));
}
aos::EventLoop *const event_loop_;
diff --git a/frc971/wpilib/loop_output_handler.h b/frc971/wpilib/loop_output_handler.h
index 46e78fc..5f66a4c 100644
--- a/frc971/wpilib/loop_output_handler.h
+++ b/frc971/wpilib/loop_output_handler.h
@@ -30,7 +30,7 @@
// TODO(austin): Name thread.
event_loop_->MakeWatcher(name, [this](const T &t) {
// Push the watchdog out a bit further.
- timer_handler_->Setup(event_loop_->monotonic_now() + timeout_);
+ timer_handler_->Schedule(event_loop_->monotonic_now() + timeout_);
Write(t);
});
@@ -38,7 +38,7 @@
timer_handler_ = event_loop_->AddTimer([this]() { Stop(); });
event_loop_->OnRun([this]() {
- timer_handler_->Setup(event_loop_->monotonic_now() + timeout_);
+ timer_handler_->Schedule(event_loop_->monotonic_now() + timeout_);
});
}
diff --git a/frc971/wpilib/loop_output_handler_test.cc b/frc971/wpilib/loop_output_handler_test.cc
index 0701bf5..b3fbb0d 100644
--- a/frc971/wpilib/loop_output_handler_test.cc
+++ b/frc971/wpilib/loop_output_handler_test.cc
@@ -107,8 +107,8 @@
// Kick off the ping timer handler.
test_event_loop_->OnRun([this, &timer_handle]() {
- timer_handle->Setup(test_event_loop_->monotonic_now(),
- chrono::milliseconds(5));
+ timer_handle->Schedule(test_event_loop_->monotonic_now(),
+ chrono::milliseconds(5));
});
event_loop_factory_.RunFor(chrono::seconds(2));
diff --git a/frc971/wpilib/sensor_reader.cc b/frc971/wpilib/sensor_reader.cc
index f8bfb5a..bbcc3b5 100644
--- a/frc971/wpilib/sensor_reader.cc
+++ b/frc971/wpilib/sensor_reader.cc
@@ -99,7 +99,7 @@
}
// Now that we are configured, actually fill in the defaults.
- timer_handler_->Setup(
+ timer_handler_->Schedule(
event_loop_->monotonic_now() +
(pwm_trigger_ ? chrono::milliseconds(3) : chrono::milliseconds(4)),
period_);
@@ -153,7 +153,7 @@
// PWM pulse.
const auto next_time = last_tick_timepoint + period_;
- timer_handler_->Setup(next_time, period_);
+ timer_handler_->Schedule(next_time, period_);
}
}