diff --git a/turtlesim/tutorials/teleop_turtle_key.cpp b/turtlesim/tutorials/teleop_turtle_key.cpp index a8779f58..ebf30762 100644 --- a/turtlesim/tutorials/teleop_turtle_key.cpp +++ b/turtlesim/tutorials/teleop_turtle_key.cpp @@ -161,7 +161,6 @@ class TeleopTurtle private: void spin(); void sendGoal(float theta); - void goalResponseCallback(std::shared_future::SharedPtr> future); void cancelGoal(); rclcpp::Node::SharedPtr nh_; @@ -193,20 +192,14 @@ void TeleopTurtle::sendGoal(float theta) goal.theta = theta; auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); send_goal_options.goal_response_callback = - [this](std::shared_future::SharedPtr> future) + [this](rclcpp_action::ClientGoalHandle::SharedPtr goal_handle) { RCLCPP_DEBUG(nh_->get_logger(), "Goal response received"); - this->goal_handle_ = future.get(); + this->goal_handle_ = goal_handle; }; rotate_absolute_client_->async_send_goal(goal, send_goal_options); } -void TeleopTurtle::goalResponseCallback(std::shared_future::SharedPtr> future) -{ - RCLCPP_DEBUG(nh_->get_logger(), "Goal response received"); - this->goal_handle_ = future.get(); -} - void TeleopTurtle::cancelGoal() { if (goal_handle_)