diff --git a/ur_robot_driver/CMakeLists.txt b/ur_robot_driver/CMakeLists.txt index f8ac46f39..34b300e93 100644 --- a/ur_robot_driver/CMakeLists.txt +++ b/ur_robot_driver/CMakeLists.txt @@ -102,6 +102,7 @@ ament_target_dependencies(controller_stopper_node ${${PROJECT_NAME}_EXPORTED_TAR add_executable(robot_state_helper src/robot_state_helper.cpp src/robot_state_helper_node.cpp + src/urcl_log_handler.cpp ) target_link_libraries(robot_state_helper ur_client_library::urcl) ament_target_dependencies(robot_state_helper ${${PROJECT_NAME}_EXPORTED_TARGETS} ${THIS_PACKAGE_INCLUDE_DEPENDS}) diff --git a/ur_robot_driver/include/ur_robot_driver/dashboard_client_ros.hpp b/ur_robot_driver/include/ur_robot_driver/dashboard_client_ros.hpp index 8349ec692..6c493246f 100644 --- a/ur_robot_driver/include/ur_robot_driver/dashboard_client_ros.hpp +++ b/ur_robot_driver/include/ur_robot_driver/dashboard_client_ros.hpp @@ -51,7 +51,7 @@ // UR client library #include "ur_client_library/ur/dashboard_client.h" #include "ur_client_library/exceptions.h" -#include "ur_dashboard_msgs/msg/program_state.hpp" +#include "ur_client_library/primary/primary_client.h" #include "ur_dashboard_msgs/srv/add_to_log.hpp" #include "ur_dashboard_msgs/srv/get_loaded_program.hpp" #include "ur_dashboard_msgs/srv/get_program_state.hpp" @@ -120,6 +120,9 @@ class DashboardClientROS std::shared_ptr node_; urcl::DashboardClient client_; + urcl::comm::INotifier notifier_; + urcl::primary_interface::PrimaryClient primary_client_; + // Commanding services rclcpp::Service::SharedPtr brake_release_service_; rclcpp::Service::SharedPtr clear_operational_mode_service_; diff --git a/ur_robot_driver/include/ur_robot_driver/robot_state_helper.hpp b/ur_robot_driver/include/ur_robot_driver/robot_state_helper.hpp index d3c03189b..5b7393457 100644 --- a/ur_robot_driver/include/ur_robot_driver/robot_state_helper.hpp +++ b/ur_robot_driver/include/ur_robot_driver/robot_state_helper.hpp @@ -29,7 +29,7 @@ #ifndef UR_ROBOT_DRIVER__ROBOT_STATE_HELPER_HPP_ #define UR_ROBOT_DRIVER__ROBOT_STATE_HELPER_HPP_ -#include +#include #include #include "rclcpp/rclcpp.hpp" @@ -41,6 +41,7 @@ #include "ur_dashboard_msgs/msg/safety_mode.hpp" #include "ur_dashboard_msgs/msg/robot_mode.hpp" #include "ur_client_library/ur/datatypes.h" +#include "ur_client_library/primary/primary_client.h" namespace ur_robot_driver { @@ -90,6 +91,10 @@ class RobotStateHelper std::atomic program_running_; std::mutex goal_mutex_; + std::string robot_ip_; + urcl::comm::INotifier notifier_; + std::shared_ptr primary_client_; + rclcpp_action::Server::SharedPtr set_mode_as_; rclcpp::CallbackGroup::SharedPtr robot_mode_sub_cb_; @@ -100,12 +105,7 @@ class RobotStateHelper rclcpp::CallbackGroup::SharedPtr service_cb_grp_; - rclcpp::Client::SharedPtr unlock_protective_stop_srv_; rclcpp::Client::SharedPtr restart_safety_srv_; - rclcpp::Client::SharedPtr power_on_srv_; - rclcpp::Client::SharedPtr power_off_srv_; - rclcpp::Client::SharedPtr brake_release_srv_; - rclcpp::Client::SharedPtr stop_program_srv_; rclcpp::Client::SharedPtr play_program_srv_; rclcpp::Client::SharedPtr resend_robot_program_srv_; }; diff --git a/ur_robot_driver/launch/ur_control.launch.py b/ur_robot_driver/launch/ur_control.launch.py index 4c317808b..6c026194c 100644 --- a/ur_robot_driver/launch/ur_control.launch.py +++ b/ur_robot_driver/launch/ur_control.launch.py @@ -96,8 +96,10 @@ def launch_setup(context): executable="robot_state_helper", name="ur_robot_state_helper", output="screen", + condition=UnlessCondition(use_mock_hardware), parameters=[ {"headless_mode": headless_mode}, + {"robot_ip": robot_ip}, ], ) diff --git a/ur_robot_driver/src/dashboard_client_node.cpp b/ur_robot_driver/src/dashboard_client_node.cpp index 91cdf9f97..da9156b5e 100644 --- a/ur_robot_driver/src/dashboard_client_node.cpp +++ b/ur_robot_driver/src/dashboard_client_node.cpp @@ -37,9 +37,10 @@ #include "ur_robot_driver/dashboard_client_ros.hpp" +#include #include -#include "rclcpp/rclcpp.hpp" +#include #include "ur_robot_driver/urcl_log_handler.hpp" int main(int argc, char** argv) @@ -53,7 +54,16 @@ int main(int argc, char** argv) ur_robot_driver::registerUrclLogHandler(""); // Set empty tf_prefix at the moment - ur_robot_driver::DashboardClientROS client(node, robot_ip); + std::shared_ptr client; + try { + client = std::make_shared(node, robot_ip); + } catch (const urcl::UrException& e) { + RCLCPP_WARN(rclcpp::get_logger("Dashboard_Client"), + "%s This warning is expected on a PolyScopeX robot. If you don't want to see this warning, " + "please don't start the dashboard client. Exiting dashboard client now.", + e.what()); + return 0; + } rclcpp::spin(node); diff --git a/ur_robot_driver/src/dashboard_client_ros.cpp b/ur_robot_driver/src/dashboard_client_ros.cpp index d4b866aef..77068fdc1 100644 --- a/ur_robot_driver/src/dashboard_client_ros.cpp +++ b/ur_robot_driver/src/dashboard_client_ros.cpp @@ -37,16 +37,27 @@ */ //---------------------------------------------------------------------- -#include +#include +#include #include +#include + namespace ur_robot_driver { DashboardClientROS::DashboardClientROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip) - : node_(node), client_(robot_ip) + : node_(node), client_(robot_ip), primary_client_(robot_ip, notifier_) { node_->declare_parameter("receive_timeout", 1); + + primary_client_.start(10, std::chrono::seconds(10)); + auto robot_version = primary_client_.getRobotVersion(); + + if (robot_version->major > 5) { + throw(urcl::UrException("The dashboard server is only available for CB3 and e-Series robots.")); + } + connect(); // Service to release the brakes. If the robot is currently powered off, it will get powered on on the fly. diff --git a/ur_robot_driver/src/robot_state_helper.cpp b/ur_robot_driver/src/robot_state_helper.cpp index cd3d4ef29..c422ae951 100755 --- a/ur_robot_driver/src/robot_state_helper.cpp +++ b/ur_robot_driver/src/robot_state_helper.cpp @@ -27,6 +27,8 @@ // POSSIBILITY OF SUCH DAMAGE. #include +#include +#include #include #include "rclcpp/rclcpp.hpp" @@ -66,28 +68,27 @@ RobotStateHelper::RobotStateHelper(const rclcpp::Node::SharedPtr& node) node->declare_parameter("headless_mode", false); headless_mode_ = node->get_parameter("headless_mode").as_bool(); - // Service to unlock protective stop - unlock_protective_stop_srv_ = node_->create_client( - "dashboard_client/unlock_protective_stop", rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_); - // Service to restart safety - restart_safety_srv_ = node_->create_client( - "dashboard_client/restart_safety", rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_); - // Service to power on the robot - power_on_srv_ = node_->create_client("dashboard_client/power_on", - rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_); - // Service to power off the robot - power_off_srv_ = node_->create_client("dashboard_client/power_off", - rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_); - // Service to release the robot's brakes - brake_release_srv_ = node_->create_client("dashboard_client/brake_release", - rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_); - // Service to stop UR program execution on the robot - stop_program_srv_ = node_->create_client("dashboard_client/stop", - rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_); - // Service to start UR program execution on the robot - play_program_srv_ = node_->create_client("dashboard_client/play", - rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_); - play_program_srv_->wait_for_service(); + node->declare_parameter("robot_ip", "192.168.56.101"); + robot_ip_ = node->get_parameter("robot_ip").as_string(); + + primary_client_ = std::make_shared(robot_ip_, notifier_); + + primary_client_->start(0, std::chrono::seconds(10)); + auto robot_version = primary_client_->getRobotVersion(); + + if (robot_version->major > 5) { + RCLCPP_WARN(rclcpp::get_logger("robot_state_helper"), "Running on a PolyScopeX robot. The dashboard server is not " + "available, therefore the robot_state_helper cannot start " + "PolyScope programs and restart the safety."); + } else { + // Service to restart safety + restart_safety_srv_ = node_->create_client( + "dashboard_client/restart_safety", rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_); + // Service to start UR program execution on the robot + play_program_srv_ = node_->create_client( + "dashboard_client/play", rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_); + play_program_srv_->wait_for_service(); + } resend_robot_program_srv_ = node_->create_client( "io_and_status_controller/resend_robot_program", rclcpp::QoS(rclcpp::KeepLast(10)), service_cb_grp_); @@ -136,7 +137,13 @@ bool RobotStateHelper::recoverFromSafety() { switch (safety_mode_) { case urcl::SafetyMode::PROTECTIVE_STOP: - return safeDashboardTrigger(this->unlock_protective_stop_srv_); + try { + primary_client_->commandUnlockProtectiveStop(); + } catch (const urcl::UrException& e) { + RCLCPP_WARN_STREAM(rclcpp::get_logger("robot_state_helper"), e.what()); + return false; + } + return true; case urcl::SafetyMode::SYSTEM_EMERGENCY_STOP:; case urcl::SafetyMode::ROBOT_EMERGENCY_STOP: RCLCPP_WARN_STREAM(rclcpp::get_logger("robot_state_helper"), "The robot is currently in safety mode." @@ -145,7 +152,11 @@ bool RobotStateHelper::recoverFromSafety() return false; case urcl::SafetyMode::VIOLATION:; case urcl::SafetyMode::FAULT: - return safeDashboardTrigger(this->restart_safety_srv_); + if (restart_safety_srv_ != nullptr) { + return safeDashboardTrigger(this->restart_safety_srv_); + } else { + return false; + } default: // nothing to do RCLCPP_DEBUG_STREAM(rclcpp::get_logger("robot_state_helper"), "No safety recovery needed."); @@ -155,15 +166,22 @@ bool RobotStateHelper::recoverFromSafety() bool RobotStateHelper::jumpToRobotMode(const urcl::RobotMode target_mode) { - switch (target_mode) { - case urcl::RobotMode::POWER_OFF: - return safeDashboardTrigger(this->power_off_srv_); - case urcl::RobotMode::IDLE: - return safeDashboardTrigger(this->power_on_srv_); - case urcl::RobotMode::RUNNING: - return safeDashboardTrigger(this->brake_release_srv_); - default: - RCLCPP_ERROR_STREAM(rclcpp::get_logger("robot_state_helper"), "Unreachable target robot mode."); + try { + switch (target_mode) { + case urcl::RobotMode::POWER_OFF: + primary_client_->commandPowerOff(); + return true; + case urcl::RobotMode::IDLE: + primary_client_->commandPowerOn(); + return true; + case urcl::RobotMode::RUNNING: + primary_client_->commandBrakeRelease(); + return true; + default: + RCLCPP_ERROR_STREAM(rclcpp::get_logger("robot_state_helper"), "Unreachable target robot mode."); + } + } catch (const urcl::UrException& e) { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("robot_state_helper"), e.what()); } return false; } @@ -247,14 +265,13 @@ void RobotStateHelper::setModeAcceptCallback(const std::shared_ptrstop_program_srv_)) { - auto start = std::chrono::steady_clock::now(); - while (program_running_ && std::chrono::steady_clock::now() - start < std::chrono::seconds(1)) { - std::this_thread::sleep_for(std::chrono::milliseconds(2)); - return true; - } + try { + primary_client_->commandStop(); + } catch (const urcl::UrException& e) { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("robot_state_helper"), e.what()); + return false; } - return false; + return true; } void RobotStateHelper::setModeExecute(const std::shared_ptr goal_handle) @@ -344,9 +361,14 @@ void RobotStateHelper::setModeExecute(const std::shared_ptrsuccess = safeDashboardTrigger(this->resend_robot_program_srv_); } else { - // The dashboard denies playing immediately after switching the mode to RUNNING - sleep(1); - result_->success = safeDashboardTrigger(this->play_program_srv_); + if (play_program_srv_ == nullptr) { + result_->success = false; + result_->message = "Play program service not available on this robot."; + } else { + // The dashboard denies playing immediately after switching the mode to RUNNING + sleep(1); + result_->success = safeDashboardTrigger(this->play_program_srv_); + } } } if (result_->success) { diff --git a/ur_robot_driver/src/robot_state_helper_node.cpp b/ur_robot_driver/src/robot_state_helper_node.cpp index 37bf9a902..331d7075f 100755 --- a/ur_robot_driver/src/robot_state_helper_node.cpp +++ b/ur_robot_driver/src/robot_state_helper_node.cpp @@ -27,12 +27,19 @@ // POSSIBILITY OF SUCH DAMAGE. #include "ur_robot_driver/robot_state_helper.hpp" +#include "ur_robot_driver/urcl_log_handler.hpp" int main(int argc, char** argv) { rclcpp::init(argc, argv); rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("robot_state_helper"); - ur_robot_driver::RobotStateHelper state_helper(node); + ur_robot_driver::registerUrclLogHandler(""); // Set empty tf_prefix at the moment + std::shared_ptr robot_state_helper; + try { + robot_state_helper = std::make_shared(node); + } catch (const urcl::UrException& e) { + RCLCPP_ERROR(rclcpp::get_logger("robot_state_helper"), "%s", e.what()); + } rclcpp::executors::MultiThreadedExecutor executor; executor.add_node(node);