File tree Expand file tree Collapse file tree 3 files changed +6
-6
lines changed Expand file tree Collapse file tree 3 files changed +6
-6
lines changed Original file line number Diff line number Diff line change @@ -165,7 +165,7 @@ class WaitResult final
165165 * {nullptr, start_index} if none was found.
166166 */
167167 std::pair<std::shared_ptr<rclcpp::TimerBase>, size_t >
168- peak_next_ready_timer (size_t start_index = 0 )
168+ peek_next_ready_timer (size_t start_index = 0 )
169169 {
170170 check_wait_result_dirty ();
171171 auto ret = std::shared_ptr<rclcpp::TimerBase>{nullptr };
@@ -186,9 +186,9 @@ class WaitResult final
186186 // / Clear the timer at the given index.
187187 /* *
188188 * Clearing a timer from the wait result prevents it from being returned by
189- * the peak_next_ready_timer () on subsequent calls.
189+ * the peek_next_ready_timer () on subsequent calls.
190190 *
191- * The index should come from the peak_next_ready_timer () function, and
191+ * The index should come from the peek_next_ready_timer () function, and
192192 * should only be used with this function if the timer pointer was valid.
193193 *
194194 * \throws std::out_of_range if the given index is out of range
Original file line number Diff line number Diff line change @@ -675,7 +675,7 @@ Executor::get_next_ready_executable(AnyExecutable & any_executable)
675675 if (!valid_executable) {
676676 size_t current_timer_index = 0 ;
677677 while (true ) {
678- auto [timer, timer_index] = wait_result_->peak_next_ready_timer (current_timer_index);
678+ auto [timer, timer_index] = wait_result_->peek_next_ready_timer (current_timer_index);
679679 if (nullptr == timer) {
680680 break ;
681681 }
@@ -688,7 +688,7 @@ Executor::get_next_ready_executable(AnyExecutable & any_executable)
688688 }
689689 // At this point the timer is either ready for execution or was perhaps
690690 // it was canceled, based on the result of call(), but either way it
691- // should not be checked again from peak_next_ready_timer (), so clear
691+ // should not be checked again from peek_next_ready_timer (), so clear
692692 // it from the wait result.
693693 wait_result_->clear_timer_with_index (current_timer_index);
694694 // Check that the timer should be called still, i.e. it wasn't canceled.
Original file line number Diff line number Diff line change @@ -147,7 +147,7 @@ bool StaticSingleThreadedExecutor::execute_ready_executables(
147147
148148 size_t current_timer_index = 0 ;
149149 while (true ) {
150- auto [timer, timer_index] = wait_result.peak_next_ready_timer (current_timer_index);
150+ auto [timer, timer_index] = wait_result.peek_next_ready_timer (current_timer_index);
151151 if (nullptr == timer) {
152152 break ;
153153 }
You can’t perform that action at this time.
0 commit comments