Skip to content

Commit 99987db

Browse files
committed
Added try catch blocks for service calls
1 parent 2154824 commit 99987db

File tree

2 files changed

+262
-134
lines changed

2 files changed

+262
-134
lines changed

ur_robot_driver/include/ur_robot_driver/dashboard_client_ros.h

Lines changed: 14 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,8 @@
2121
*
2222
* \author Felix Exner [email protected]
2323
* \date 2019-10-21
24+
* \author Marvin Große Besselmann [email protected]
25+
* \date 2021-03-22
2426
*
2527
*/
2628
//----------------------------------------------------------------------
@@ -36,6 +38,7 @@
3638

3739
// UR client library
3840
#include <ur_client_library/ur/dashboard_client.h>
41+
#include <ur_client_library/exceptions.h>
3942
#include <ur_dashboard_msgs/msg/program_state.hpp>
4043
#include <ur_dashboard_msgs/srv/add_to_log.hpp>
4144
#include <ur_dashboard_msgs/srv/get_loaded_program.hpp>
@@ -76,10 +79,18 @@ class DashboardClientROS
7679
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr service = node_->create_service<std_srvs::srv::Trigger>(
7780
topic, [&, command, expected](const std::shared_ptr<std_srvs::srv::Trigger::Request> req,
7881
const std::shared_ptr<std_srvs::srv::Trigger::Response> resp) {
79-
resp->message = this->client_.sendAndReceive(command);
80-
resp->success = std::regex_match(resp->message, std::regex(expected));
82+
try
83+
{
84+
resp->message = this->client_.sendAndReceive(command);
85+
resp->success = std::regex_match(resp->message, std::regex(expected));
86+
}
87+
catch (const urcl::UrException& e)
88+
{
89+
RCLCPP_ERROR(rclcpp::get_logger("Dashboard_Client"), "Service Call failed: '%s'", e.what());
90+
resp->message = e.what();
91+
resp->success = false;
92+
}
8193
});
82-
8394
return service;
8495
}
8596

0 commit comments

Comments
 (0)