4040
4141#include < ur_robot_driver/trajectory_until_node.hpp>
4242#include < functional>
43- #include < thread>
4443
4544namespace ur_robot_driver
4645{
@@ -60,8 +59,8 @@ TrajectoryUntilNode::TrajectoryUntilNode(const rclcpp::NodeOptions& options)
6059 , trajectory_accepted_(false )
6160 , until_accepted_(false )
6261{
63- prealloc_res = std::make_shared<TrajectoryUntilAction::Result>(TrajectoryUntilAction::Result ());
64- prealloc_fb = std::make_shared<TrajectoryUntilAction::Feedback>(TrajectoryUntilAction::Feedback ());
62+ prealloc_res_ = std::make_shared<TrajectoryUntilAction::Result>(TrajectoryUntilAction::Result ());
63+ prealloc_fb_ = std::make_shared<TrajectoryUntilAction::Feedback>(TrajectoryUntilAction::Feedback ());
6564
6665 // Different callback groups for the server and the clients, so their callbacks can run concurrently.
6766 server_callback_group = create_callback_group (rclcpp::CallbackGroupType::MutuallyExclusive);
@@ -77,7 +76,7 @@ TrajectoryUntilNode::TrajectoryUntilNode(const rclcpp::NodeOptions& options)
7776
7877 // Create action server to advertise the "/trajectory_until_node/execute"
7978 action_server_ = rclcpp_action::create_server<TrajectoryUntilAction>(
80- this , std::string ( this -> get_name ()) + " /execute" ,
79+ this , " ~ /execute" ,
8180 std::bind (&TrajectoryUntilNode::goal_received_callback, this , std::placeholders::_1, std::placeholders::_2),
8281 std::bind (&TrajectoryUntilNode::goal_cancelled_callback, this , std::placeholders::_1),
8382 std::bind (&TrajectoryUntilNode::goal_accepted_callback, this , std::placeholders::_1),
@@ -255,13 +254,13 @@ void TrajectoryUntilNode::trajectory_feedback_callback(
255254 const std::shared_ptr<const FollowJointTrajectory::Feedback> feedback)
256255{
257256 if (server_goal_handle_) {
258- prealloc_fb ->actual = feedback->actual ;
259- prealloc_fb ->desired = feedback->desired ;
260- prealloc_fb ->error = feedback->error ;
261- prealloc_fb ->header = feedback->header ;
262- prealloc_fb ->joint_names = feedback->joint_names ;
257+ prealloc_fb_ ->actual = feedback->actual ;
258+ prealloc_fb_ ->desired = feedback->desired ;
259+ prealloc_fb_ ->error = feedback->error ;
260+ prealloc_fb_ ->header = feedback->header ;
261+ prealloc_fb_ ->joint_names = feedback->joint_names ;
263262 if (server_goal_handle_) {
264- server_goal_handle_->publish_feedback (prealloc_fb );
263+ server_goal_handle_->publish_feedback (prealloc_fb_ );
265264 }
266265 }
267266}
@@ -286,32 +285,32 @@ void TrajectoryUntilNode::until_result_callback(
286285void TrajectoryUntilNode::report_goal (TrajectoryResult result)
287286{
288287 if (server_goal_handle_) {
289- prealloc_res ->until_condition_result = TrajectoryUntilAction::Result::NOT_TRIGGERED;
290- prealloc_res ->error_code = result.result ->error_code ;
291- prealloc_res ->error_string = result.result ->error_string ;
288+ prealloc_res_ ->until_condition_result = TrajectoryUntilAction::Result::NOT_TRIGGERED;
289+ prealloc_res_ ->error_code = result.result ->error_code ;
290+ prealloc_res_ ->error_string = result.result ->error_string ;
292291 switch (result.code ) {
293292 case rclcpp_action::ResultCode::SUCCEEDED:
294- server_goal_handle_->succeed (prealloc_res );
293+ server_goal_handle_->succeed (prealloc_res_ );
295294 break ;
296295
297296 case rclcpp_action::ResultCode::ABORTED:
298- prealloc_res ->error_string += " Trajectory action was aborted. Aborting goal." ;
299- server_goal_handle_->abort (prealloc_res );
297+ prealloc_res_ ->error_string += " Trajectory action was aborted. Aborting goal." ;
298+ server_goal_handle_->abort (prealloc_res_ );
300299 break ;
301300
302301 case rclcpp_action::ResultCode::CANCELED:
303- prealloc_res ->error_string += " Trajectory action was canceled." ;
304- server_goal_handle_->canceled (prealloc_res );
302+ prealloc_res_ ->error_string += " Trajectory action was canceled." ;
303+ server_goal_handle_->canceled (prealloc_res_ );
305304 break ;
306305
307306 default :
308- prealloc_res ->error_string += " Unknown result code received from trajectory action, this should not happen. "
309- " Aborting goal." ;
310- server_goal_handle_->abort (prealloc_res );
307+ prealloc_res_ ->error_string += " Unknown result code received from trajectory action, this should not happen. "
308+ " Aborting goal." ;
309+ server_goal_handle_->abort (prealloc_res_ );
311310 break ;
312311 }
313312 if (result.code != rclcpp_action::ResultCode::SUCCEEDED) {
314- RCLCPP_ERROR (this ->get_logger (), prealloc_res ->error_string .c_str ());
313+ RCLCPP_ERROR (this ->get_logger (), " %s " , prealloc_res_ ->error_string .c_str ());
315314 } else {
316315 RCLCPP_INFO (this ->get_logger (), " Trajectory finished successfully, did not trigger until condition." );
317316 }
@@ -325,32 +324,32 @@ void TrajectoryUntilNode::report_goal(UntilResult result)
325324 if (server_goal_handle_) {
326325 switch (result.code ) {
327326 case rclcpp_action::ResultCode::SUCCEEDED:
328- prealloc_res ->error_code = TrajectoryUntilAction::Result::SUCCESSFUL;
329- prealloc_res ->until_condition_result = TrajectoryUntilAction::Result::TRIGGERED;
330- prealloc_res ->error_string += " Trajectory finished successfully by triggering until condition." ;
331- server_goal_handle_->succeed (prealloc_res );
327+ prealloc_res_ ->error_code = TrajectoryUntilAction::Result::SUCCESSFUL;
328+ prealloc_res_ ->until_condition_result = TrajectoryUntilAction::Result::TRIGGERED;
329+ prealloc_res_ ->error_string += " Trajectory finished successfully by triggering until condition." ;
330+ server_goal_handle_->succeed (prealloc_res_ );
332331 break ;
333332
334333 case rclcpp_action::ResultCode::ABORTED:
335- prealloc_res ->error_string += " Until action was aborted. Aborting goal." ;
336- server_goal_handle_->abort (prealloc_res );
334+ prealloc_res_ ->error_string += " Until action was aborted. Aborting goal." ;
335+ server_goal_handle_->abort (prealloc_res_ );
337336 break ;
338337
339338 case rclcpp_action::ResultCode::CANCELED:
340- prealloc_res ->error_string += " Until action was canceled." ;
341- server_goal_handle_->canceled (prealloc_res );
339+ prealloc_res_ ->error_string += " Until action was canceled." ;
340+ server_goal_handle_->canceled (prealloc_res_ );
342341 break ;
343342
344343 default :
345- prealloc_res ->error_string += " Unknown result code received from until action, this should not happen. "
346- " Aborting "
347- " goal." ;
348- server_goal_handle_->abort (prealloc_res );
344+ prealloc_res_ ->error_string += " Unknown result code received from until action, this should not happen. "
345+ " Aborting "
346+ " goal." ;
347+ server_goal_handle_->abort (prealloc_res_ );
349348
350349 break ;
351350 }
352351 if (result.code != rclcpp_action::ResultCode::SUCCEEDED) {
353- RCLCPP_ERROR (this ->get_logger (), prealloc_res ->error_string .c_str ());
352+ RCLCPP_ERROR (this ->get_logger (), " %s " , prealloc_res_ ->error_string .c_str ());
354353 } else {
355354 RCLCPP_INFO (this ->get_logger (), " Trajectory finished by triggering until condition." );
356355 }
@@ -371,8 +370,8 @@ void TrajectoryUntilNode::reset_node()
371370 current_until_goal_handle_ = nullptr ;
372371 trajectory_accepted_ = false ;
373372 until_accepted_ = false ;
374- prealloc_res = std::make_shared<TrajectoryUntilAction::Result>(TrajectoryUntilAction::Result ());
375- prealloc_fb = std::make_shared<TrajectoryUntilAction::Feedback>(TrajectoryUntilAction::Feedback ());
373+ prealloc_res_ = std::make_shared<TrajectoryUntilAction::Result>(TrajectoryUntilAction::Result ());
374+ prealloc_fb_ = std::make_shared<TrajectoryUntilAction::Feedback>(TrajectoryUntilAction::Feedback ());
376375
377376 server_goal_handle_ = nullptr ;
378377}
0 commit comments