From e3342f98e5bcaf624090cc816ee6f5c0ade70c3d Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Tue, 15 Sep 2020 14:28:50 -0700 Subject: [PATCH] Update goal response callback signature The signature changed in https://github.com/ros2/rclcpp/pull/1311 Signed-off-by: Jacob Perron --- tf2_ros/test/test_buffer_server.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/tf2_ros/test/test_buffer_server.cpp b/tf2_ros/test/test_buffer_server.cpp index b91960e19..bdb85fdca 100644 --- a/tf2_ros/test/test_buffer_server.cpp +++ b/tf2_ros/test/test_buffer_server.cpp @@ -82,8 +82,7 @@ class MockBufferClient : public rclcpp::Node auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); send_goal_options.goal_response_callback = - [this](std::shared_future future) { - auto goal_handle = future.get(); + [this](GoalHandle::SharedPtr goal_handle) { if (!goal_handle) { this->accepted_ = false; } else {