Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 2 additions & 9 deletions turtlesim/tutorials/teleop_turtle_key.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,6 @@ class TeleopTurtle
private:
void spin();
void sendGoal(float theta);
void goalResponseCallback(std::shared_future<rclcpp_action::ClientGoalHandle<turtlesim::action::RotateAbsolute>::SharedPtr> future);
void cancelGoal();

rclcpp::Node::SharedPtr nh_;
Expand Down Expand Up @@ -193,20 +192,14 @@ void TeleopTurtle::sendGoal(float theta)
goal.theta = theta;
auto send_goal_options = rclcpp_action::Client<turtlesim::action::RotateAbsolute>::SendGoalOptions();
send_goal_options.goal_response_callback =
[this](std::shared_future<rclcpp_action::ClientGoalHandle<turtlesim::action::RotateAbsolute>::SharedPtr> future)
[this](rclcpp_action::ClientGoalHandle<turtlesim::action::RotateAbsolute>::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<rclcpp_action::ClientGoalHandle<turtlesim::action::RotateAbsolute>::SharedPtr> future)
{
RCLCPP_DEBUG(nh_->get_logger(), "Goal response received");
this->goal_handle_ = future.get();
}

void TeleopTurtle::cancelGoal()
{
if (goal_handle_)
Expand Down