Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
158 changes: 158 additions & 0 deletions ur_robot_driver/doc/dashboard_client.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,158 @@
:github_url: https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/blob/main/ur_robot_driver/doc/dashboard_client.rst

.. _dashboard_client_ros2:

Dashboard client
================

Advertised Services
-------------------

add_to_log (`ur_dashboard_msgs/AddToLog <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/AddToLog.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Service to add a message to the robot's log

brake_release (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

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

clear_operational_mode (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

If this service is called the operational mode can again be changed from PolyScope, and the user password is enabled.

close_popup (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Close a (non-safety) popup on the teach pendant.

close_safety_popup (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Close a safety popup on the teach pendant.

connect (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Service to reconnect to the dashboard server

get_loaded_program (`ur_dashboard_msgs/GetLoadedProgram <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/GetLoadedProgram.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Load a robot installation from a file

get_robot_mode (`ur_dashboard_msgs/GetRobotMode <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/GetRobotMode.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Service to query the current robot mode

get_safety_mode (`ur_dashboard_msgs/GetSafetyMode <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/GetSafetyMode.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Service to query the current safety mode

load_installation (`ur_dashboard_msgs/Load <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/Load.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Load a robot installation from a file

load_program (`ur_dashboard_msgs/Load <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/Load.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Load a robot program from a file

pause (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Pause a running program.

play (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Start execution of a previously loaded program

popup (`ur_dashboard_msgs/Popup <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/Popup.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Service to show a popup on the UR Teach pendant.

power_off (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Power off the robot motors

power_on (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Power on the robot motors. To fully start the robot, call 'brake_release' afterwards.

program_running (`ur_dashboard_msgs/IsProgramRunning <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/IsProgramRunning.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Query whether there is currently a program running

program_saved (`ur_dashboard_msgs/IsProgramSaved <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/IsProgramSaved.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Query whether the current program is saved

program_state (`ur_dashboard_msgs/GetProgramState <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/GetProgramState.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Service to query the current program state

quit (`ur_dashboard_msgs/GetLoadedProgram <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/GetLoadedProgram.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Disconnect from the dashboard service.

raw_request (`ur_dashboard_msgs/RawRequest <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/RawRequest.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

General purpose service to send arbitrary messages to the dashboard server

restart_safety (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

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

resume (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Resume a paused program on a PolyScope X robot. This service is only available on a PolyScope X
robot.

shutdown (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Shutdown the robot controller

stop (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Stop program execution on the robot

unlock_protective_stop (`std_srvs/Trigger <http://docs.ros.org/en/rolling/p/std_srvs/srv/Trigger.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

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.

is_in_remote_control (`ur_dashboard_msgs/IsInRemoteControl <http://docs.ros.org/en/rolling/p/ur_dashboard_msgs/srv/IsInRemoteControl.html>`_)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Service to query whether the robot is in remote control

Parameters
----------

receive_timeout (Required)
^^^^^^^^^^^^^^^^^^^^^^^^^^

Timeout (in seconds, double) after which a call to the dashboard server will be considered failure if no answer has been received.

robot_ip (Required)
^^^^^^^^^^^^^^^^^^^

The IP address under which the robot is reachable.
74 changes: 66 additions & 8 deletions ur_robot_driver/include/ur_robot_driver/dashboard_client_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,16 +85,19 @@ class DashboardClientROS
virtual ~DashboardClientROS() = default;

private:
inline rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr createDashboardTriggerSrv(const std::string& topic,
const std::string& command,
const std::string& expected)
inline rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr
createDashboardTriggerSrv(const std::string& topic, std::function<urcl::DashboardResponse()> command)
{
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr service = node_->create_service<std_srvs::srv::Trigger>(
topic, [&, command, expected](const std::shared_ptr<std_srvs::srv::Trigger::Request> req,
const std::shared_ptr<std_srvs::srv::Trigger::Response> resp) {
topic, [command](const std::shared_ptr<std_srvs::srv::Trigger::Request> req,
const std::shared_ptr<std_srvs::srv::Trigger::Response> resp) {
try {
resp->message = this->client_.sendAndReceive(command);
resp->success = std::regex_match(resp->message, std::regex(expected));
auto response = command();
resp->message = response.message;
if (response.data.find("status_code") != response.data.end()) {
resp->message += ", status_code: " + std::to_string(std::get<int>(response.data["status_code"]));
}
resp->success = response.ok;
} catch (const urcl::UrException& e) {
RCLCPP_ERROR(rclcpp::get_logger("Dashboard_Client"), "Service Call failed: '%s'", e.what());
resp->message = e.what();
Expand All @@ -104,6 +107,60 @@ class DashboardClientROS
return service;
}

template <class SrvResponseT>
urcl::DashboardResponse dashboardCallWithChecks(std::function<urcl::DashboardResponse()> dashboard_call,
SrvResponseT resp)
{
urcl::DashboardResponse dashboard_response;
try {
dashboard_response = dashboard_call();
resp->success = dashboard_response.ok;
resp->answer = dashboard_response.message;
} catch (const urcl::NotImplementedException& e) {
RCLCPP_ERROR(rclcpp::get_logger("Dashboard_Client"), "This service call seems not to be implemented (for this "
"robot version).");
resp->answer = "Not implemented for this robot software version.";
resp->success = false;
} catch (const urcl::UrException& e) {
RCLCPP_ERROR(rclcpp::get_logger("Dashboard_Client"), "Service Call failed: '%s'", e.what());
resp->answer = e.what();
resp->success = false;
return dashboard_response;
}
return dashboard_response;
}

template <class SrvResponseT>
void handleDashboardResponseData(std::function<void()> fun, SrvResponseT& resp,
const urcl::DashboardResponse& dashboard_response)
{
try {
fun();
} catch (const std::bad_variant_access& e) {
RCLCPP_ERROR(rclcpp::get_logger("Dashboard_Client"), "Service Call failed: '%s'", e.what());
std::ostringstream oss;
for (const auto& [key, value] : dashboard_response.data) {
oss << key << ": ";
std::visit([&oss](const auto& arg) { oss << arg; }, value);
oss << "\n";
}
RCLCPP_INFO(rclcpp::get_logger("Dashboard_Client"), "Available data:\n%s", oss.str().c_str());
resp->answer = e.what();
resp->success = false;
} catch (const std::out_of_range& e) {
RCLCPP_ERROR(rclcpp::get_logger("Dashboard_Client"), "Service Call failed: '%s'", e.what());
std::ostringstream oss;
for (const auto& [key, value] : dashboard_response.data) {
oss << key << ": ";
std::visit([&oss](const auto& arg) { oss << arg; }, value);
oss << "\n";
}
RCLCPP_INFO(rclcpp::get_logger("Dashboard_Client"), "Available data:\n%s", oss.str().c_str());
resp->answer = e.what();
resp->success = false;
}
}

bool handleRunningQuery(ur_dashboard_msgs::srv::IsProgramRunning::Request::SharedPtr req,
ur_dashboard_msgs::srv::IsProgramRunning::Response::SharedPtr resp);

Expand All @@ -122,7 +179,7 @@ class DashboardClientROS
bool connect();

std::shared_ptr<rclcpp::Node> node_;
urcl::DashboardClient client_;
std::unique_ptr<urcl::DashboardClient> client_;

urcl::comm::INotifier notifier_;
urcl::primary_interface::PrimaryClient primary_client_;
Expand All @@ -134,6 +191,7 @@ class DashboardClientROS
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr close_safety_popup_service_;
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr pause_service_;
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr play_service_;
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr resume_service_;
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr power_off_service_;
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr power_on_service_;
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr restart_safety_service_;
Expand Down
Loading