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/analysis/in_process_plotter.h b/frc971/analysis/in_process_plotter.h
index 4f05c19..6dab308 100644
--- a/frc971/analysis/in_process_plotter.h
+++ b/frc971/analysis/in_process_plotter.h
@@ -29,7 +29,7 @@
// matplotlib-like interface
// The basic pattern is:
// 1) Call Figure()
- // 2) Setup the lines, labels, etc. for the figure.
+ // 2) Set up the lines, labels, etc. for the figure.
// 3) Repeat 1-2 however many times.
// 4) Call Publish().
// 5) Repeat 1-5 however many times.
diff --git a/frc971/can_logger/can_logger.cc b/frc971/can_logger/can_logger.cc
index ccd9824..3f71b44 100644
--- a/frc971/can_logger/can_logger.cc
+++ b/frc971/can_logger/can_logger.cc
@@ -34,7 +34,7 @@
aos::TimerHandler *timer_handler = event_loop->AddTimer([this]() { Poll(); });
timer_handler->set_name("CAN logging Loop");
- timer_handler->Setup(event_loop->monotonic_now(), kPollPeriod);
+ timer_handler->Schedule(event_loop->monotonic_now(), kPollPeriod);
}
void CanLogger::Poll() {
diff --git a/frc971/control_loops/control_loop_test.h b/frc971/control_loops/control_loop_test.h
index c667568..00062b9 100644
--- a/frc971/control_loops/control_loop_test.h
+++ b/frc971/control_loops/control_loop_test.h
@@ -69,7 +69,7 @@
robot_status_event_loop_->AddTimer([this]() { SendJoystickState(); });
robot_status_event_loop_->OnRun([this]() {
- send_joystick_state_timer_->Setup(
+ send_joystick_state_timer_->Schedule(
robot_status_event_loop_->monotonic_now(), dt_);
});
}
@@ -88,7 +88,7 @@
enabled_ = enabled;
SendJoystickState();
SendRobotState();
- send_joystick_state_timer_->Setup(
+ send_joystick_state_timer_->Schedule(
robot_status_event_loop_->monotonic_now(), dt_);
}
}
diff --git a/frc971/control_loops/drivetrain/localization/puppet_localizer_test.cc b/frc971/control_loops/drivetrain/localization/puppet_localizer_test.cc
index d5f9a31..1a71d5a 100644
--- a/frc971/control_loops/drivetrain/localization/puppet_localizer_test.cc
+++ b/frc971/control_loops/drivetrain/localization/puppet_localizer_test.cc
@@ -100,8 +100,8 @@
output_builder.add_theta(drivetrain_plant_.state()(2));
builder.CheckOk(builder.Send(output_builder.Finish()));
})
- ->Setup(imu_test_event_loop_->monotonic_now(),
- std::chrono::milliseconds(5));
+ ->Schedule(imu_test_event_loop_->monotonic_now(),
+ std::chrono::milliseconds(5));
}
virtual ~LocalizedDrivetrainTest() override {}
diff --git a/frc971/vision/charuco_lib.cc b/frc971/vision/charuco_lib.cc
index b55a493..82cc6b3 100644
--- a/frc971/vision/charuco_lib.cc
+++ b/frc971/vision/charuco_lib.cc
@@ -124,8 +124,8 @@
age_double);
if (FLAGS_disable_delay > 0) {
if (!disabling_) {
- timer_fn_->Setup(event_loop_->monotonic_now() +
- chrono::milliseconds(FLAGS_disable_delay));
+ timer_fn_->Schedule(event_loop_->monotonic_now() +
+ chrono::milliseconds(FLAGS_disable_delay));
disabling_ = true;
}
} else {
diff --git a/frc971/vision/target_mapper.cc b/frc971/vision/target_mapper.cc
index e7a6955..7778da1 100644
--- a/frc971/vision/target_mapper.cc
+++ b/frc971/vision/target_mapper.cc
@@ -367,7 +367,7 @@
std::unique_ptr<ceres::CostFunction>
TargetMapper::BuildMapFittingOptimizationProblem(ceres::Problem *problem) {
- // Setup robot visualization
+ // Set up robot visualization.
vis_robot_.ClearImage();
constexpr int kImageWidth = 1280;
constexpr double kFocalLength = 500.0;
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_);
}
}