File tree Expand file tree Collapse file tree 1 file changed +2
-9
lines changed
Expand file tree Collapse file tree 1 file changed +2
-9
lines changed Original file line number Diff line number Diff line change @@ -161,7 +161,6 @@ class TeleopTurtle
161161private:
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-
210203void TeleopTurtle::cancelGoal ()
211204{
212205 if (goal_handle_)
You can’t perform that action at this time.
0 commit comments