Skip to content

Commit ff4d520

Browse files
committed
Update goal response callback signature
The signature changed in ros2/rclcpp#1311 Also remove related dead code. Signed-off-by: Jacob Perron <[email protected]>
1 parent 45e8a3b commit ff4d520

File tree

1 file changed

+2
-9
lines changed

1 file changed

+2
-9
lines changed

turtlesim/tutorials/teleop_turtle_key.cpp

Lines changed: 2 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -161,7 +161,6 @@ class TeleopTurtle
161161
private:
162162
void spin();
163163
void sendGoal(float theta);
164-
void goalResponseCallback(std::shared_future<rclcpp_action::ClientGoalHandle<turtlesim::action::RotateAbsolute>::SharedPtr> future);
165164
void cancelGoal();
166165

167166
rclcpp::Node::SharedPtr nh_;
@@ -193,20 +192,14 @@ void TeleopTurtle::sendGoal(float theta)
193192
goal.theta = theta;
194193
auto send_goal_options = rclcpp_action::Client<turtlesim::action::RotateAbsolute>::SendGoalOptions();
195194
send_goal_options.goal_response_callback =
196-
[this](std::shared_future<rclcpp_action::ClientGoalHandle<turtlesim::action::RotateAbsolute>::SharedPtr> future)
195+
[this](rclcpp_action::ClientGoalHandle<turtlesim::action::RotateAbsolute>::SharedPtr goal_handle)
197196
{
198197
RCLCPP_DEBUG(nh_->get_logger(), "Goal response received");
199-
this->goal_handle_ = future.get();
198+
this->goal_handle_ = goal_handle
200199
};
201200
rotate_absolute_client_->async_send_goal(goal, send_goal_options);
202201
}
203202

204-
void TeleopTurtle::goalResponseCallback(std::shared_future<rclcpp_action::ClientGoalHandle<turtlesim::action::RotateAbsolute>::SharedPtr> future)
205-
{
206-
RCLCPP_DEBUG(nh_->get_logger(), "Goal response received");
207-
this->goal_handle_ = future.get();
208-
}
209-
210203
void TeleopTurtle::cancelGoal()
211204
{
212205
if (goal_handle_)

0 commit comments

Comments
 (0)