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
4138namespace 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
156162bool 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
248261bool 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
260272void 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 ) {
0 commit comments