Skip to content

Commit d9d6922

Browse files
committed
Fix: creating the dashboard client outside the try/catch block
Otherwise it will go out of scope afterwards and it will not be usable.
1 parent 56fe942 commit d9d6922

File tree

1 file changed

+5
-2
lines changed

1 file changed

+5
-2
lines changed

ur_robot_driver/src/dashboard_client_node.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -37,9 +37,10 @@
3737

3838
#include "ur_robot_driver/dashboard_client_ros.hpp"
3939

40+
#include <memory>
4041
#include <string>
4142

42-
#include "rclcpp/rclcpp.hpp"
43+
#include <rclcpp/logging.hpp>
4344
#include "ur_robot_driver/urcl_log_handler.hpp"
4445

4546
int main(int argc, char** argv)
@@ -53,13 +54,15 @@ int main(int argc, char** argv)
5354

5455
ur_robot_driver::registerUrclLogHandler(""); // Set empty tf_prefix at the moment
5556

57+
std::shared_ptr<ur_robot_driver::DashboardClientROS> client;
5658
try {
57-
ur_robot_driver::DashboardClientROS client(node, robot_ip);
59+
client = std::make_shared<ur_robot_driver::DashboardClientROS>(node, robot_ip);
5860
} catch (const urcl::UrException& e) {
5961
RCLCPP_WARN(rclcpp::get_logger("Dashboard_Client"),
6062
"%s This warning is expected on a PolyScopeX robot. If you don't want to see this warning, "
6163
"please don't start the dashboard client. Exiting dashboard client now.",
6264
e.what());
65+
return 0;
6366
}
6467

6568
rclcpp::spin(node);

0 commit comments

Comments
 (0)