Skip to content

Commit

Permalink
Changes ros_timer_init for ros_timer_init2 (#508)
Browse files Browse the repository at this point in the history
Signed-off-by: Voldivh <eloyabmfcv@gmail.com>
  • Loading branch information
Voldivh authored Jun 21, 2023
1 parent 419067b commit d587079
Showing 1 changed file with 3 additions and 2 deletions.
5 changes: 3 additions & 2 deletions test_rclcpp/test/test_waitable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,14 @@ class WaitableWithTimer : public rclcpp::Waitable
timer_.reset(new rcl_timer_t);
*timer_ = rcl_get_zero_initialized_timer();
rcl_clock_t * clock_handle = clock->get_clock_handle();
rcl_ret_t ret = rcl_timer_init(
rcl_ret_t ret = rcl_timer_init2(
timer_.get(),
clock_handle,
rclcpp::contexts::get_global_default_context()->get_rcl_context().get(),
period_nanoseconds,
nullptr,
rcl_get_default_allocator());
rcl_get_default_allocator(),
true);
if (RCL_RET_OK != ret) {
throw std::runtime_error("failed to create timer");
}
Expand Down

1 comment on commit d587079

@PhDittmann
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It produces an error in the ubuntu jammy amd64 test:

13:06:31 --- stderr: test_rclcpp
13:06:31 /tmp/ws/src/system_tests/test_rclcpp/test/test_waitable.cpp: In constructor ‘WaitableWithTimer::WaitableWithTimer(rclcpp::Clock::SharedPtr)’:
13:06:31 /tmp/ws/src/system_tests/test_rclcpp/test/test_waitable.cpp:43:21: error: ‘rcl_timer_init2’ was not declared in this scope; did you mean ‘rcl_timer_init’?
13:06:31    43 |     rcl_ret_t ret = rcl_timer_init2(
13:06:31       |                     ^~~~~~~~~~~~~~~
13:06:31       |                     rcl_timer_init
13:06:31 gmake[2]: *** [CMakeFiles/gtest_waitable__rmw_fastrtps_cpp.dir/build.make:76: CMakeFiles/gtest_waitable__rmw_fastrtps_cpp.dir/test/test_waitable.cpp.o] Error 1
13:06:31 gmake[1]: *** [CMakeFiles/Makefile2:1143: CMakeFiles/gtest_waitable__rmw_fastrtps_cpp.dir/all] Error 2
13:06:31 gmake: *** [Makefile:146: all] Error 2
13:06:31 ---

Please sign in to comment.