diff --git a/rclcpp/test/test_time_source.cpp b/rclcpp/test/test_time_source.cpp index 8f2e723..b5fa4f4 100644 --- a/rclcpp/test/test_time_source.cpp +++ b/rclcpp/test/test_time_source.cpp @@ -193,7 +193,7 @@ TEST_F(TestTimeSource, callbacks) { // Change callbacks - callback_holder = ros_clock->create_jump_callback( + rclcpp::JumpHandler::SharedPtr callback_holder2 = ros_clock->create_jump_callback( std::bind(&CallbackObject::pre_callback, &cbo, 2), std::bind(&CallbackObject::post_callback, &cbo, std::placeholders::_1, 2), jump_threshold);