diff --git a/turtlesim/tutorials/teleop_turtle_key.cpp b/turtlesim/tutorials/teleop_turtle_key.cpp index 9e6ac557..bd70fd4f 100644 --- a/turtlesim/tutorials/teleop_turtle_key.cpp +++ b/turtlesim/tutorials/teleop_turtle_key.cpp @@ -305,13 +305,12 @@ class TeleopTurtle final void sendGoal(float theta) { - auto goal = turtlesim::action::RotateAbsolute::Goal(); + using Rotate = turtlesim::action::RotateAbsolute; + auto goal = Rotate::Goal(); goal.theta = theta; - auto send_goal_options = - rclcpp_action::Client::SendGoalOptions(); + auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); send_goal_options.goal_response_callback = - [this](rclcpp_action::ClientGoalHandle::SharedPtr - goal_handle) + [this](rclcpp_action::ClientGoalHandle::SharedPtr goal_handle) { RCLCPP_DEBUG(nh_->get_logger(), "Goal response received"); this->goal_handle_ = goal_handle;