Skip to content

Commit 807bf6f

Browse files
urfeexurmahp
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)
1 parent a32facb commit 807bf6f

File tree

5 files changed

+230
-199
lines changed

5 files changed

+230
-199
lines changed

ur_robot_driver/doc/dashboard_client.rst

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -118,6 +118,12 @@ restart_safety (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv
118118

119119
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).
120120

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+
121127
shutdown (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
122128
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
123129

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)