Skip to content

Commit 282d111

Browse files
urfeexmergify[bot]
authored andcommitted
Dashboard client polyscopex (#1546)
* Support PolyScopeX Robot API through the dashboard client * Add resume service to docs Co-authored-by: Mads Holm Peters <[email protected]> (cherry picked from commit f247c0b) # Conflicts: # ur_robot_driver/doc/dashboard_client.rst
1 parent 13b4e4f commit 282d111

File tree

5 files changed

+382
-199
lines changed

5 files changed

+382
-199
lines changed
Lines changed: 158 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,158 @@
1+
:github_url: https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/blob/main/ur_robot_driver/doc/dashboard_client.rst
2+
3+
.. _dashboard_client_ros2:
4+
5+
Dashboard client
6+
================
7+
8+
Advertised Services
9+
-------------------
10+
11+
add_to_log (`ur_dashboard_msgs/AddToLog <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/AddToLog.html>`_)
12+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
13+
14+
Service to add a message to the robot's log
15+
16+
brake_release (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
17+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
18+
19+
Service to release the brakes. If the robot is currently powered off, it will get powered on the fly.
20+
21+
clear_operational_mode (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
22+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
23+
24+
If this service is called the operational mode can again be changed from PolyScope, and the user password is enabled.
25+
26+
close_popup (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
27+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
28+
29+
Close a (non-safety) popup on the teach pendant.
30+
31+
close_safety_popup (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
32+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
33+
34+
Close a safety popup on the teach pendant.
35+
36+
connect (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
37+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
38+
39+
Service to reconnect to the dashboard server
40+
41+
get_loaded_program (`ur_dashboard_msgs/GetLoadedProgram <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/GetLoadedProgram.html>`_)
42+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
43+
44+
Load a robot installation from a file
45+
46+
get_robot_mode (`ur_dashboard_msgs/GetRobotMode <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/GetRobotMode.html>`_)
47+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
48+
49+
Service to query the current robot mode
50+
51+
get_safety_mode (`ur_dashboard_msgs/GetSafetyMode <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/GetSafetyMode.html>`_)
52+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
53+
54+
Service to query the current safety mode
55+
56+
load_installation (`ur_dashboard_msgs/Load <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/Load.html>`_)
57+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
58+
59+
Load a robot installation from a file
60+
61+
load_program (`ur_dashboard_msgs/Load <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/Load.html>`_)
62+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
63+
64+
Load a robot program from a file
65+
66+
pause (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
67+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
68+
69+
Pause a running program.
70+
71+
play (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
72+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
73+
74+
Start execution of a previously loaded program
75+
76+
popup (`ur_dashboard_msgs/Popup <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/Popup.html>`_)
77+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
78+
79+
Service to show a popup on the UR Teach pendant.
80+
81+
power_off (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
82+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
83+
84+
Power off the robot motors
85+
86+
power_on (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
87+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
88+
89+
Power on the robot motors. To fully start the robot, call 'brake_release' afterwards.
90+
91+
program_running (`ur_dashboard_msgs/IsProgramRunning <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/IsProgramRunning.html>`_)
92+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
93+
94+
Query whether there is currently a program running
95+
96+
program_saved (`ur_dashboard_msgs/IsProgramSaved <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/IsProgramSaved.html>`_)
97+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
98+
99+
Query whether the current program is saved
100+
101+
program_state (`ur_dashboard_msgs/GetProgramState <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/GetProgramState.html>`_)
102+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
103+
104+
Service to query the current program state
105+
106+
quit (`ur_dashboard_msgs/GetLoadedProgram <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/GetLoadedProgram.html>`_)
107+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
108+
109+
Disconnect from the dashboard service.
110+
111+
raw_request (`ur_dashboard_msgs/RawRequest <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/RawRequest.html>`_)
112+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
113+
114+
General purpose service to send arbitrary messages to the dashboard server
115+
116+
restart_safety (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
117+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
118+
119+
Used when robot gets a safety fault or violation to restart the safety. After safety has been rebooted the robot will be in Power Off. NOTE: You should always ensure it is okay to restart the system. It is highly recommended to check the error log before using this command (either via PolyScope or e.g. ssh connection).
120+
121+
resume (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
122+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
123+
124+
Resume a paused program on a PolyScope X robot. This service is only available on a PolyScope X
125+
robot.
126+
127+
shutdown (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
128+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
129+
130+
Shutdown the robot controller
131+
132+
stop (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
133+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
134+
135+
Stop program execution on the robot
136+
137+
unlock_protective_stop (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
138+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
139+
140+
Dismiss a protective stop to continue robot movements. NOTE: It is the responsibility of the user to ensure the cause of the protective stop is resolved before calling this service.
141+
142+
is_in_remote_control (`ur_dashboard_msgs/IsInRemoteControl <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/IsInRemoteControl.html>`_)
143+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
144+
145+
Service to query whether the robot is in remote control
146+
147+
Parameters
148+
----------
149+
150+
receive_timeout (Required)
151+
^^^^^^^^^^^^^^^^^^^^^^^^^^
152+
153+
Timeout (in seconds, double) after which a call to the dashboard server will be considered failure if no answer has been received.
154+
155+
robot_ip (Required)
156+
^^^^^^^^^^^^^^^^^^^
157+
158+
The IP address under which the robot is reachable.

ur_robot_driver/include/ur_robot_driver/dashboard_client_ros.hpp

Lines changed: 66 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -85,16 +85,19 @@ class DashboardClientROS
8585
virtual ~DashboardClientROS() = default;
8686

8787
private:
88-
inline rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr createDashboardTriggerSrv(const std::string& topic,
89-
const std::string& command,
90-
const std::string& expected)
88+
inline rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr
89+
createDashboardTriggerSrv(const std::string& topic, std::function<urcl::DashboardResponse()> command)
9190
{
9291
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr service = node_->create_service<std_srvs::srv::Trigger>(
93-
topic, [&, command, expected](const std::shared_ptr<std_srvs::srv::Trigger::Request> req,
94-
const std::shared_ptr<std_srvs::srv::Trigger::Response> resp) {
92+
topic, [command](const std::shared_ptr<std_srvs::srv::Trigger::Request> req,
93+
const std::shared_ptr<std_srvs::srv::Trigger::Response> resp) {
9594
try {
96-
resp->message = this->client_.sendAndReceive(command);
97-
resp->success = std::regex_match(resp->message, std::regex(expected));
95+
auto response = command();
96+
resp->message = response.message;
97+
if (response.data.find("status_code") != response.data.end()) {
98+
resp->message += ", status_code: " + std::to_string(std::get<int>(response.data["status_code"]));
99+
}
100+
resp->success = response.ok;
98101
} catch (const urcl::UrException& e) {
99102
RCLCPP_ERROR(rclcpp::get_logger("Dashboard_Client"), "Service Call failed: '%s'", e.what());
100103
resp->message = e.what();
@@ -104,6 +107,60 @@ class DashboardClientROS
104107
return service;
105108
}
106109

110+
template <class SrvResponseT>
111+
urcl::DashboardResponse dashboardCallWithChecks(std::function<urcl::DashboardResponse()> dashboard_call,
112+
SrvResponseT resp)
113+
{
114+
urcl::DashboardResponse dashboard_response;
115+
try {
116+
dashboard_response = dashboard_call();
117+
resp->success = dashboard_response.ok;
118+
resp->answer = dashboard_response.message;
119+
} catch (const urcl::NotImplementedException& e) {
120+
RCLCPP_ERROR(rclcpp::get_logger("Dashboard_Client"), "This service call seems not to be implemented (for this "
121+
"robot version).");
122+
resp->answer = "Not implemented for this robot software version.";
123+
resp->success = false;
124+
} catch (const urcl::UrException& e) {
125+
RCLCPP_ERROR(rclcpp::get_logger("Dashboard_Client"), "Service Call failed: '%s'", e.what());
126+
resp->answer = e.what();
127+
resp->success = false;
128+
return dashboard_response;
129+
}
130+
return dashboard_response;
131+
}
132+
133+
template <class SrvResponseT>
134+
void handleDashboardResponseData(std::function<void()> fun, SrvResponseT& resp,
135+
const urcl::DashboardResponse& dashboard_response)
136+
{
137+
try {
138+
fun();
139+
} catch (const std::bad_variant_access& e) {
140+
RCLCPP_ERROR(rclcpp::get_logger("Dashboard_Client"), "Service Call failed: '%s'", e.what());
141+
std::ostringstream oss;
142+
for (const auto& [key, value] : dashboard_response.data) {
143+
oss << key << ": ";
144+
std::visit([&oss](const auto& arg) { oss << arg; }, value);
145+
oss << "\n";
146+
}
147+
RCLCPP_INFO(rclcpp::get_logger("Dashboard_Client"), "Available data:\n%s", oss.str().c_str());
148+
resp->answer = e.what();
149+
resp->success = false;
150+
} catch (const std::out_of_range& e) {
151+
RCLCPP_ERROR(rclcpp::get_logger("Dashboard_Client"), "Service Call failed: '%s'", e.what());
152+
std::ostringstream oss;
153+
for (const auto& [key, value] : dashboard_response.data) {
154+
oss << key << ": ";
155+
std::visit([&oss](const auto& arg) { oss << arg; }, value);
156+
oss << "\n";
157+
}
158+
RCLCPP_INFO(rclcpp::get_logger("Dashboard_Client"), "Available data:\n%s", oss.str().c_str());
159+
resp->answer = e.what();
160+
resp->success = false;
161+
}
162+
}
163+
107164
bool handleRunningQuery(ur_dashboard_msgs::srv::IsProgramRunning::Request::SharedPtr req,
108165
ur_dashboard_msgs::srv::IsProgramRunning::Response::SharedPtr resp);
109166

@@ -122,7 +179,7 @@ class DashboardClientROS
122179
bool connect();
123180

124181
std::shared_ptr<rclcpp::Node> node_;
125-
urcl::DashboardClient client_;
182+
std::unique_ptr<urcl::DashboardClient> client_;
126183

127184
urcl::comm::INotifier notifier_;
128185
urcl::primary_interface::PrimaryClient primary_client_;
@@ -134,6 +191,7 @@ class DashboardClientROS
134191
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr close_safety_popup_service_;
135192
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr pause_service_;
136193
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr play_service_;
194+
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr resume_service_;
137195
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr power_off_service_;
138196
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr power_on_service_;
139197
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr restart_safety_service_;

0 commit comments

Comments
 (0)