Skip to content

Commit 769f6b5

Browse files
committed
Use only one service callback group
1 parent bb6aa1c commit 769f6b5

File tree

2 files changed

+12
-24
lines changed

2 files changed

+12
-24
lines changed

ur_robot_driver/include/ur_robot_driver/robot_state_helper.hpp

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -92,13 +92,7 @@ class RobotStateHelper
9292
rclcpp::Subscription<ur_dashboard_msgs::msg::RobotMode>::SharedPtr robot_mode_sub_;
9393
rclcpp::Subscription<ur_dashboard_msgs::msg::SafetyMode>::SharedPtr safety_mode_sub_;
9494

95-
rclcpp::CallbackGroup::SharedPtr unlock_cb_;
96-
rclcpp::CallbackGroup::SharedPtr restart_cb_;
97-
rclcpp::CallbackGroup::SharedPtr power_on_cb_;
98-
rclcpp::CallbackGroup::SharedPtr power_off_cb_;
99-
rclcpp::CallbackGroup::SharedPtr brake_release_cb_;
100-
rclcpp::CallbackGroup::SharedPtr stop_program_cb_;
101-
rclcpp::CallbackGroup::SharedPtr play_program_cb_;
95+
rclcpp::CallbackGroup::SharedPtr service_cb_grp_;
10296

10397
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr unlock_protective_stop_srv_;
10498
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr restart_safety_srv_;

ur_robot_driver/src/robot_state_helper.cpp

Lines changed: 11 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -58,42 +58,36 @@ RobotStateHelper::RobotStateHelper(const rclcpp::Node::SharedPtr& node)
5858
"io_and_status_controller/safety_mode", 1,
5959
std::bind(&RobotStateHelper::safetyModeCallback, this, std::placeholders::_1));
6060

61-
unlock_cb_ = node_->create_callback_group(rclcpp::CallbackGroupType::Reentrant);
62-
restart_cb_ = unlock_cb_;
63-
power_on_cb_ = unlock_cb_;
64-
power_off_cb_ = unlock_cb_;
65-
brake_release_cb_ = unlock_cb_;
66-
stop_program_cb_ = unlock_cb_;
67-
play_program_cb_ = unlock_cb_;
61+
service_cb_grp_ = node_->create_callback_group(rclcpp::CallbackGroupType::Reentrant);
6862

6963
node->declare_parameter("headless_mode", false);
7064
headless_mode_ = node->get_parameter("headless_mode").as_bool();
7165

7266
// Service to unlock protective stop
7367
unlock_protective_stop_srv_ = node_->create_client<std_srvs::srv::Trigger>(
74-
"dashboard_client/unlock_protective_stop", rclcpp::QoS(rclcpp::KeepLast(10)), unlock_cb_);
68+
"dashboard_client/unlock_protective_stop", rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
7569
// Service to restart safety
76-
restart_safety_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/restart_safety",
77-
rclcpp::QoS(rclcpp::KeepLast(10)), restart_cb_);
70+
restart_safety_srv_ = node_->create_client<std_srvs::srv::Trigger>(
71+
"dashboard_client/restart_safety", rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
7872
// Service to power on the robot
7973
power_on_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/power_on",
80-
rclcpp::QoS(rclcpp::KeepLast(10)), power_on_cb_);
74+
rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
8175
// Service to power off the robot
8276
power_off_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/power_off",
83-
rclcpp::QoS(rclcpp::KeepLast(10)), power_off_cb_);
77+
rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
8478
// Service to release the robot's brakes
85-
brake_release_srv_ = node_->create_client<std_srvs::srv::Trigger>(
86-
"dashboard_client/brake_release", rclcpp::QoS(rclcpp::KeepLast(10)), brake_release_cb_);
79+
brake_release_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/brake_release",
80+
rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
8781
// Service to stop UR program execution on the robot
8882
stop_program_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/stop",
89-
rclcpp::QoS(rclcpp::KeepLast(10)), stop_program_cb_);
83+
rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
9084
// Service to start UR program execution on the robot
9185
play_program_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/play",
92-
rclcpp::QoS(rclcpp::KeepLast(10)), play_program_cb_);
86+
rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
9387
play_program_srv_->wait_for_service();
9488

9589
resend_robot_program_srv_ = node_->create_client<std_srvs::srv::Trigger>(
96-
"io_and_status_controller/resend_robot_program", rclcpp::QoS(rclcpp::KeepLast(10)), unlock_cb_);
90+
"io_and_status_controller/resend_robot_program", rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_);
9791
resend_robot_program_srv_->wait_for_service();
9892

9993
feedback_ = std::make_shared<ur_dashboard_msgs::action::SetMode::Feedback>();

0 commit comments

Comments
 (0)