Skip to content

Commit 81c380b

Browse files
authored
Support PolyScopeX robots (backport of #1318) (#1333)
* Shutdown dashboard client when connected to PolyScopeX robot Before trying to establish a connection to the dashboard server, check the version of the connected robot. If it is a PolyScopeX robot, shutdown the dashboard client. * Make robot_state_helper use primary_client whenever possible
1 parent 5ba9b5c commit 81c380b

File tree

8 files changed

+110
-59
lines changed

8 files changed

+110
-59
lines changed

ur_robot_driver/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -113,6 +113,7 @@ ament_target_dependencies(controller_stopper_node ${${PROJECT_NAME}_EXPORTED_TAR
113113
add_executable(robot_state_helper
114114
src/robot_state_helper.cpp
115115
src/robot_state_helper_node.cpp
116+
src/urcl_log_handler.cpp
116117
)
117118
target_link_libraries(robot_state_helper ur_client_library::urcl)
118119
ament_target_dependencies(robot_state_helper ${${PROJECT_NAME}_EXPORTED_TARGETS} ${THIS_PACKAGE_INCLUDE_DEPENDS})

ur_robot_driver/include/ur_robot_driver/dashboard_client_ros.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@
5151
// UR client library
5252
#include "ur_client_library/ur/dashboard_client.h"
5353
#include "ur_client_library/exceptions.h"
54-
#include "ur_dashboard_msgs/msg/program_state.hpp"
54+
#include "ur_client_library/primary/primary_client.h"
5555
#include "ur_dashboard_msgs/srv/add_to_log.hpp"
5656
#include "ur_dashboard_msgs/srv/get_loaded_program.hpp"
5757
#include "ur_dashboard_msgs/srv/get_program_state.hpp"
@@ -120,6 +120,9 @@ class DashboardClientROS
120120
std::shared_ptr<rclcpp::Node> node_;
121121
urcl::DashboardClient client_;
122122

123+
urcl::comm::INotifier notifier_;
124+
urcl::primary_interface::PrimaryClient primary_client_;
125+
123126
// Commanding services
124127
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr brake_release_service_;
125128
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr clear_operational_mode_service_;

ur_robot_driver/include/ur_robot_driver/robot_state_helper.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929
#ifndef UR_ROBOT_DRIVER__ROBOT_STATE_HELPER_HPP_
3030
#define UR_ROBOT_DRIVER__ROBOT_STATE_HELPER_HPP_
3131

32-
#include <chrono>
32+
#include <string>
3333
#include <memory>
3434

3535
#include "rclcpp/rclcpp.hpp"
@@ -41,6 +41,7 @@
4141
#include "ur_dashboard_msgs/msg/safety_mode.hpp"
4242
#include "ur_dashboard_msgs/msg/robot_mode.hpp"
4343
#include "ur_client_library/ur/datatypes.h"
44+
#include "ur_client_library/primary/primary_client.h"
4445

4546
namespace ur_robot_driver
4647
{
@@ -90,6 +91,10 @@ class RobotStateHelper
9091
std::atomic<bool> program_running_;
9192
std::mutex goal_mutex_;
9293

94+
std::string robot_ip_;
95+
urcl::comm::INotifier notifier_;
96+
std::shared_ptr<urcl::primary_interface::PrimaryClient> primary_client_;
97+
9398
rclcpp_action::Server<ur_dashboard_msgs::action::SetMode>::SharedPtr set_mode_as_;
9499

95100
rclcpp::CallbackGroup::SharedPtr robot_mode_sub_cb_;
@@ -100,12 +105,7 @@ class RobotStateHelper
100105

101106
rclcpp::CallbackGroup::SharedPtr service_cb_grp_;
102107

103-
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr unlock_protective_stop_srv_;
104108
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr restart_safety_srv_;
105-
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr power_on_srv_;
106-
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr power_off_srv_;
107-
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr brake_release_srv_;
108-
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr stop_program_srv_;
109109
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr play_program_srv_;
110110
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr resend_robot_program_srv_;
111111
};

ur_robot_driver/launch/ur_control.launch.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -262,8 +262,10 @@ def launch_setup(context, *args, **kwargs):
262262
executable="robot_state_helper",
263263
name="ur_robot_state_helper",
264264
output="screen",
265+
condition=UnlessCondition(use_fake_hardware),
265266
parameters=[
266267
{"headless_mode": headless_mode},
268+
{"robot_ip": robot_ip},
267269
],
268270
)
269271

ur_robot_driver/src/dashboard_client_node.cpp

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -37,9 +37,10 @@
3737

3838
#include "ur_robot_driver/dashboard_client_ros.hpp"
3939

40+
#include <memory>
4041
#include <string>
4142

42-
#include "rclcpp/rclcpp.hpp"
43+
#include <rclcpp/logging.hpp>
4344
#include "ur_robot_driver/urcl_log_handler.hpp"
4445

4546
int main(int argc, char** argv)
@@ -53,7 +54,16 @@ int main(int argc, char** argv)
5354

5455
ur_robot_driver::registerUrclLogHandler(""); // Set empty tf_prefix at the moment
5556

56-
ur_robot_driver::DashboardClientROS client(node, robot_ip);
57+
std::shared_ptr<ur_robot_driver::DashboardClientROS> client;
58+
try {
59+
client = std::make_shared<ur_robot_driver::DashboardClientROS>(node, robot_ip);
60+
} catch (const urcl::UrException& e) {
61+
RCLCPP_WARN(rclcpp::get_logger("Dashboard_Client"),
62+
"%s This warning is expected on a PolyScopeX robot. If you don't want to see this warning, "
63+
"please don't start the dashboard client. Exiting dashboard client now.",
64+
e.what());
65+
return 0;
66+
}
5767

5868
rclcpp::spin(node);
5969

ur_robot_driver/src/dashboard_client_ros.cpp

Lines changed: 13 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -37,16 +37,27 @@
3737
*/
3838
//----------------------------------------------------------------------
3939

40-
#include <ur_robot_driver/dashboard_client_ros.hpp>
40+
#include <ur_client_library/exceptions.h>
41+
#include <ur_client_library/primary/primary_client.h>
4142

4243
#include <string>
4344

45+
#include <ur_robot_driver/dashboard_client_ros.hpp>
46+
4447
namespace ur_robot_driver
4548
{
4649
DashboardClientROS::DashboardClientROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip)
47-
: node_(node), client_(robot_ip)
50+
: node_(node), client_(robot_ip), primary_client_(robot_ip, notifier_)
4851
{
4952
node_->declare_parameter<double>("receive_timeout", 1);
53+
54+
primary_client_.start(10, std::chrono::seconds(10));
55+
auto robot_version = primary_client_.getRobotVersion();
56+
57+
if (robot_version->major > 5) {
58+
throw(urcl::UrException("The dashboard server is only available for CB3 and e-Series robots."));
59+
}
60+
5061
connect();
5162

5263
// Service to release the brakes. If the robot is currently powered off, it will get powered on on the fly.

ur_robot_driver/src/robot_state_helper.cpp

Lines changed: 64 additions & 47 deletions
Original file line numberDiff line numberDiff line change
@@ -27,15 +27,12 @@
2727
// POSSIBILITY OF SUCH DAMAGE.
2828

2929
#include <mutex>
30+
#include <rclcpp/logger.hpp>
31+
#include <rclcpp/logging.hpp>
3032
#include <ur_robot_driver/robot_state_helper.hpp>
3133

3234
#include "rclcpp/rclcpp.hpp"
3335
#include "rclcpp_action/create_server.hpp"
34-
#include "std_srvs/srv/trigger.hpp"
35-
36-
#include "ur_dashboard_msgs/action/set_mode.hpp"
37-
#include "ur_dashboard_msgs/msg/safety_mode.hpp"
38-
#include "ur_dashboard_msgs/msg/robot_mode.hpp"
3936
#include "ur_client_library/ur/datatypes.h"
4037

4138
namespace ur_robot_driver
@@ -66,28 +63,27 @@ RobotStateHelper::RobotStateHelper(const rclcpp::Node::SharedPtr& node)
6663
node->declare_parameter("headless_mode", false);
6764
headless_mode_ = node->get_parameter("headless_mode").as_bool();
6865

69-
// Service to unlock protective stop
70-
unlock_protective_stop_srv_ = node_->create_client<std_srvs::srv::Trigger>(
71-
"dashboard_client/unlock_protective_stop", rmw_qos_profile_services_default, service_cb_grp_);
72-
// Service to restart safety
73-
restart_safety_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/restart_safety",
66+
node->declare_parameter("robot_ip", "192.168.56.101");
67+
robot_ip_ = node->get_parameter("robot_ip").as_string();
68+
69+
primary_client_ = std::make_shared<urcl::primary_interface::PrimaryClient>(robot_ip_, notifier_);
70+
71+
primary_client_->start(0, std::chrono::seconds(10));
72+
auto robot_version = primary_client_->getRobotVersion();
73+
74+
if (robot_version->major > 5) {
75+
RCLCPP_WARN(rclcpp::get_logger("robot_state_helper"), "Running on a PolyScopeX robot. The dashboard server is not "
76+
"available, therefore the robot_state_helper cannot start "
77+
"PolyScope programs and restart the safety.");
78+
} else {
79+
// Service to restart safety
80+
restart_safety_srv_ = node_->create_client<std_srvs::srv::Trigger>(
81+
"dashboard_client/restart_safety", rmw_qos_profile_services_default, service_cb_grp_);
82+
// Service to start UR program execution on the robot
83+
play_program_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/play",
7484
rmw_qos_profile_services_default, service_cb_grp_);
75-
// Service to power on the robot
76-
power_on_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/power_on",
77-
rmw_qos_profile_services_default, service_cb_grp_);
78-
// Service to power off the robot
79-
power_off_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/power_off",
80-
rmw_qos_profile_services_default, service_cb_grp_);
81-
// Service to release the robot's brakes
82-
brake_release_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/brake_release",
83-
rmw_qos_profile_services_default, service_cb_grp_);
84-
// Service to stop UR program execution on the robot
85-
stop_program_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/stop",
86-
rmw_qos_profile_services_default, service_cb_grp_);
87-
// Service to start UR program execution on the robot
88-
play_program_srv_ = node_->create_client<std_srvs::srv::Trigger>("dashboard_client/play",
89-
rmw_qos_profile_services_default, service_cb_grp_);
90-
play_program_srv_->wait_for_service();
85+
play_program_srv_->wait_for_service();
86+
}
9187

9288
resend_robot_program_srv_ = node_->create_client<std_srvs::srv::Trigger>(
9389
"io_and_status_controller/resend_robot_program", rmw_qos_profile_services_default, service_cb_grp_);
@@ -136,7 +132,13 @@ bool RobotStateHelper::recoverFromSafety()
136132
{
137133
switch (safety_mode_) {
138134
case urcl::SafetyMode::PROTECTIVE_STOP:
139-
return safeDashboardTrigger(this->unlock_protective_stop_srv_);
135+
try {
136+
primary_client_->commandUnlockProtectiveStop();
137+
} catch (const urcl::UrException& e) {
138+
RCLCPP_WARN_STREAM(rclcpp::get_logger("robot_state_helper"), e.what());
139+
return false;
140+
}
141+
return true;
140142
case urcl::SafetyMode::SYSTEM_EMERGENCY_STOP:;
141143
case urcl::SafetyMode::ROBOT_EMERGENCY_STOP:
142144
RCLCPP_WARN_STREAM(rclcpp::get_logger("robot_state_helper"), "The robot is currently in safety mode."
@@ -145,7 +147,11 @@ bool RobotStateHelper::recoverFromSafety()
145147
return false;
146148
case urcl::SafetyMode::VIOLATION:;
147149
case urcl::SafetyMode::FAULT:
148-
return safeDashboardTrigger(this->restart_safety_srv_);
150+
if (restart_safety_srv_ != nullptr) {
151+
return safeDashboardTrigger(this->restart_safety_srv_);
152+
} else {
153+
return false;
154+
}
149155
default:
150156
// nothing to do
151157
RCLCPP_DEBUG_STREAM(rclcpp::get_logger("robot_state_helper"), "No safety recovery needed.");
@@ -155,15 +161,22 @@ bool RobotStateHelper::recoverFromSafety()
155161

156162
bool RobotStateHelper::jumpToRobotMode(const urcl::RobotMode target_mode)
157163
{
158-
switch (target_mode) {
159-
case urcl::RobotMode::POWER_OFF:
160-
return safeDashboardTrigger(this->power_off_srv_);
161-
case urcl::RobotMode::IDLE:
162-
return safeDashboardTrigger(this->power_on_srv_);
163-
case urcl::RobotMode::RUNNING:
164-
return safeDashboardTrigger(this->brake_release_srv_);
165-
default:
166-
RCLCPP_ERROR_STREAM(rclcpp::get_logger("robot_state_helper"), "Unreachable target robot mode.");
164+
try {
165+
switch (target_mode) {
166+
case urcl::RobotMode::POWER_OFF:
167+
primary_client_->commandPowerOff();
168+
return true;
169+
case urcl::RobotMode::IDLE:
170+
primary_client_->commandPowerOn();
171+
return true;
172+
case urcl::RobotMode::RUNNING:
173+
primary_client_->commandBrakeRelease();
174+
return true;
175+
default:
176+
RCLCPP_ERROR_STREAM(rclcpp::get_logger("robot_state_helper"), "Unreachable target robot mode.");
177+
}
178+
} catch (const urcl::UrException& e) {
179+
RCLCPP_ERROR_STREAM(rclcpp::get_logger("robot_state_helper"), e.what());
167180
}
168181
return false;
169182
}
@@ -247,14 +260,13 @@ void RobotStateHelper::setModeAcceptCallback(const std::shared_ptr<RobotStateHel
247260

248261
bool RobotStateHelper::stopProgram()
249262
{
250-
if (safeDashboardTrigger(this->stop_program_srv_)) {
251-
auto start = std::chrono::steady_clock::now();
252-
while (program_running_ && std::chrono::steady_clock::now() - start < std::chrono::seconds(1)) {
253-
std::this_thread::sleep_for(std::chrono::milliseconds(2));
254-
return true;
255-
}
263+
try {
264+
primary_client_->commandStop();
265+
} catch (const urcl::UrException& e) {
266+
RCLCPP_ERROR_STREAM(rclcpp::get_logger("robot_state_helper"), e.what());
267+
return false;
256268
}
257-
return false;
269+
return true;
258270
}
259271

260272
void RobotStateHelper::setModeExecute(const std::shared_ptr<RobotStateHelper::SetModeGoalHandle> goal_handle)
@@ -344,9 +356,14 @@ void RobotStateHelper::setModeExecute(const std::shared_ptr<RobotStateHelper::Se
344356
if (headless_mode_) {
345357
result_->success = safeDashboardTrigger(this->resend_robot_program_srv_);
346358
} else {
347-
// The dashboard denies playing immediately after switching the mode to RUNNING
348-
sleep(1);
349-
result_->success = safeDashboardTrigger(this->play_program_srv_);
359+
if (play_program_srv_ == nullptr) {
360+
result_->success = false;
361+
result_->message = "Play program service not available on this robot.";
362+
} else {
363+
// The dashboard denies playing immediately after switching the mode to RUNNING
364+
sleep(1);
365+
result_->success = safeDashboardTrigger(this->play_program_srv_);
366+
}
350367
}
351368
}
352369
if (result_->success) {

ur_robot_driver/src/robot_state_helper_node.cpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,12 +27,19 @@
2727
// POSSIBILITY OF SUCH DAMAGE.
2828

2929
#include "ur_robot_driver/robot_state_helper.hpp"
30+
#include "ur_robot_driver/urcl_log_handler.hpp"
3031

3132
int main(int argc, char** argv)
3233
{
3334
rclcpp::init(argc, argv);
3435
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("robot_state_helper");
35-
ur_robot_driver::RobotStateHelper state_helper(node);
36+
ur_robot_driver::registerUrclLogHandler(""); // Set empty tf_prefix at the moment
37+
std::shared_ptr<ur_robot_driver::RobotStateHelper> robot_state_helper;
38+
try {
39+
robot_state_helper = std::make_shared<ur_robot_driver::RobotStateHelper>(node);
40+
} catch (const urcl::UrException& e) {
41+
RCLCPP_ERROR(rclcpp::get_logger("robot_state_helper"), "%s", e.what());
42+
}
3643

3744
rclcpp::executors::MultiThreadedExecutor executor;
3845
executor.add_node(node);

0 commit comments

Comments
 (0)