@@ -96,9 +96,9 @@ bool TrajectoryUntilNode::assign_until_action_client(std::shared_ptr<const Traje
9696 switch (type) {
9797 case TrajectoryUntil::Goal::TOOL_CONTACT:
9898 until_action_client_variant = rclcpp_action::create_client<TCAction>(this ,
99- " /tool_contact_controller/"
100- " detect_tool_contact" ,
101- clients_callback_group);
99+ " /tool_contact_controller/"
100+ " detect_tool_contact" ,
101+ clients_callback_group);
102102 break ;
103103
104104 default :
@@ -118,7 +118,7 @@ rclcpp_action::GoalResponse TrajectoryUntilNode::goal_received_callback(
118118 return rclcpp_action::GoalResponse::REJECT;
119119 }
120120
121- if (!assign_until_action_client (goal)){
121+ if (!assign_until_action_client (goal)) {
122122 RCLCPP_ERROR (this ->get_logger (), " Until type not defined, double check the types in the action "
123123 " definition." );
124124 return rclcpp_action::GoalResponse::REJECT;
@@ -129,17 +129,16 @@ rclcpp_action::GoalResponse TrajectoryUntilNode::goal_received_callback(
129129 }
130130
131131 // Check until action server, send action goal to until-controller and wait for it to be accepted.
132- if (std::holds_alternative<TCClient>(until_action_client_variant)){
132+ if (std::holds_alternative<TCClient>(until_action_client_variant)) {
133133 if (!std::get<TCClient>(until_action_client_variant)->wait_for_action_server (std::chrono::seconds (1 ))) {
134134 RCLCPP_ERROR (this ->get_logger (), " Until action server not available." );
135135 return rclcpp_action::GoalResponse::REJECT;
136136 }
137137 send_until_goal<TCAction, TCClient>(goal);
138- }
139- else {
138+ } else {
140139 throw std::runtime_error (" Until type not implemented. This should not happen." );
141140 }
142-
141+
143142 // If it is not accepted within 1 seconds, it is
144143 // assumed to be rejected.
145144 std::unique_lock<std::mutex> until_lock (mutex_until);
@@ -204,19 +203,19 @@ void TrajectoryUntilNode::send_trajectory_goal(std::shared_ptr<const TrajectoryU
204203}
205204
206205// Send the until goal, using the relevant fields supplied from the action server.
207- template <class ActionType , class ClientType >
206+ template <class ActionType , class ClientType >
208207void TrajectoryUntilNode::send_until_goal (std::shared_ptr<const TrajectoryUntil::Goal> /* goal */ )
209208{
210- // Setup goal
209+ // Setup goal
211210 auto goal_msg = typename ActionType::Goal ();
212211 auto send_goal_options = typename rclcpp_action::Client<ActionType>::SendGoalOptions ();
213212 send_goal_options.goal_response_callback =
214- std::bind (&TrajectoryUntilNode::until_response_callback<ActionType>, this , std::placeholders::_1);
213+ std::bind (&TrajectoryUntilNode::until_response_callback<ActionType>, this , std::placeholders::_1);
215214 send_goal_options.result_callback =
216- std::bind (&TrajectoryUntilNode::until_result_callback<ActionType>, this , std::placeholders::_1);
215+ std::bind (&TrajectoryUntilNode::until_result_callback<ActionType>, this , std::placeholders::_1);
217216
218217 // Send goal
219- std::get<ClientType>(until_action_client_variant) -> async_send_goal (goal_msg, send_goal_options);
218+ std::get<ClientType>(until_action_client_variant)-> async_send_goal (goal_msg, send_goal_options);
220219}
221220
222221void TrajectoryUntilNode::trajectory_response_callback (
@@ -235,7 +234,7 @@ void TrajectoryUntilNode::trajectory_response_callback(
235234 cv_trajectory_.notify_one ();
236235}
237236
238- template <class T >
237+ template <class T >
239238void TrajectoryUntilNode::until_response_callback (
240239 const typename rclcpp_action::ClientGoalHandle<T>::SharedPtr& goal_handle)
241240{
@@ -263,7 +262,7 @@ void TrajectoryUntilNode::trajectory_feedback_callback(
263262 prealloc_fb->error = feedback->error ;
264263 prealloc_fb->header = feedback->header ;
265264 prealloc_fb->joint_names = feedback->joint_names ;
266- if (server_goal_handle_){
265+ if (server_goal_handle_) {
267266 server_goal_handle_->publish_feedback (prealloc_fb);
268267 }
269268 }
@@ -278,8 +277,9 @@ void TrajectoryUntilNode::trajectory_result_callback(
278277 report_goal (result);
279278}
280279
281- template <class T >
282- void TrajectoryUntilNode::until_result_callback (const typename rclcpp_action::ClientGoalHandle<T>::WrappedResult& result)
280+ template <class T >
281+ void TrajectoryUntilNode::until_result_callback (
282+ const typename rclcpp_action::ClientGoalHandle<T>::WrappedResult& result)
283283{
284284 RCLCPP_INFO (this ->get_logger (), " Until result received." );
285285 current_until_goal_handle_.reset ();
@@ -345,8 +345,9 @@ void TrajectoryUntilNode::report_goal(UntilResult result)
345345 break ;
346346
347347 default :
348- prealloc_res->error_string += " Unknown result code received from until action, this should not happen. Aborting "
349- " goal." ;
348+ prealloc_res->error_string += " Unknown result code received from until action, this should not happen. "
349+ " Aborting "
350+ " goal." ;
350351 server_goal_handle_->abort (prealloc_res);
351352
352353 break ;
@@ -380,10 +381,10 @@ void TrajectoryUntilNode::reset_node()
380381}
381382
382383// Cancel the action contained in the variant, regardless of what type it is.
383- void TrajectoryUntilNode::cancel_until_goal (){
384- std::visit ([ this ]( const auto & until_client) {
385- until_client->async_cancel_goal (current_until_goal_handle_);
386- }, until_action_client_variant);
384+ void TrajectoryUntilNode::cancel_until_goal ()
385+ {
386+ std::visit ([ this ]( const auto & until_client) { until_client->async_cancel_goal (current_until_goal_handle_); },
387+ until_action_client_variant);
387388}
388389
389390} // namespace ur_robot_driver
0 commit comments