@@ -38,60 +38,60 @@ DashboardClientROS::DashboardClientROS(const rclcpp::Node::SharedPtr& node, cons
3838 connect ();
3939
4040 // Service to release the brakes. If the robot is currently powered off, it will get powered on on the fly.
41- brake_release_service_ = createDashboardTriggerSrv (" brake_release" , " brake release\n " , " Brake releasing" );
41+ brake_release_service_ = createDashboardTriggerSrv (" ~/ brake_release" , " brake release\n " , " Brake releasing" );
4242
4343 // If this service is called the operational mode can again be changed from PolyScope, and the user password is
4444 // enabled.
45- clear_operational_mode_service_ = createDashboardTriggerSrv (" clear_operational_mode" , " clear operational mode\n " ,
45+ clear_operational_mode_service_ = createDashboardTriggerSrv (" ~/ clear_operational_mode" , " clear operational mode\n " ,
4646 " No longer controlling the operational mode\\ . "
4747 " Current "
4848 " operational mode: "
4949 " '(MANUAL|AUTOMATIC)'\\ ." );
5050
5151 // Close a (non-safety) popup on the teach pendant.
52- close_popup_service_ = createDashboardTriggerSrv (" close_popup" , " close popup\n " , " closing popup" );
52+ close_popup_service_ = createDashboardTriggerSrv (" ~/ close_popup" , " close popup\n " , " closing popup" );
5353
5454 // Close a safety popup on the teach pendant.
5555 close_safety_popup_service_ =
56- createDashboardTriggerSrv (" close_safety_popup" , " close safety popup\n " , " closing safety popup" );
56+ createDashboardTriggerSrv (" ~/ close_safety_popup" , " close safety popup\n " , " closing safety popup" );
5757
5858 // Pause a running program.
59- pause_service_ = createDashboardTriggerSrv (" pause" , " pause\n " , " Pausing program" );
59+ pause_service_ = createDashboardTriggerSrv (" ~/ pause" , " pause\n " , " Pausing program" );
6060
6161 // Start execution of a previously loaded program
62- play_service_ = createDashboardTriggerSrv (" play" , " play\n " , " Starting program" );
62+ play_service_ = createDashboardTriggerSrv (" ~/ play" , " play\n " , " Starting program" );
6363
6464 // Power off the robot motors
65- power_off_service_ = createDashboardTriggerSrv (" power_off" , " power off\n " , " Powering off" );
65+ power_off_service_ = createDashboardTriggerSrv (" ~/ power_off" , " power off\n " , " Powering off" );
6666
6767 // Power on the robot motors. To fully start the robot, call 'brake_release' afterwards.
68- power_on_service_ = createDashboardTriggerSrv (" power_on" , " power on\n " , " Powering on" );
68+ power_on_service_ = createDashboardTriggerSrv (" ~/ power_on" , " power on\n " , " Powering on" );
6969
7070 // Used when robot gets a safety fault or violation to restart the safety. After safety has been rebooted the robot
7171 // will be in Power Off. NOTE: You should always ensure it is okay to restart the system. It is highly recommended to
7272 // check the error log before using this command (either via PolyScope or e.g. ssh connection).
73- restart_safety_service_ = createDashboardTriggerSrv (" restart_safety" , " restart safety\n " , " Restarting safety" );
73+ restart_safety_service_ = createDashboardTriggerSrv (" ~/ restart_safety" , " restart safety\n " , " Restarting safety" );
7474
7575 // Shutdown the robot controller
76- shutdown_service_ = createDashboardTriggerSrv (" shutdown" , " shutdown\n " , " Shutting down" );
76+ shutdown_service_ = createDashboardTriggerSrv (" ~/ shutdown" , " shutdown\n " , " Shutting down" );
7777
7878 // Stop program execution on the robot
79- stop_service_ = createDashboardTriggerSrv (" stop" , " stop\n " , " Stopped" );
79+ stop_service_ = createDashboardTriggerSrv (" ~/ stop" , " stop\n " , " Stopped" );
8080
8181 // Dismiss a protective stop to continue robot movements. NOTE: It is the responsibility of the user to ensure the
8282 // cause of the protective stop is resolved before calling this service.
8383 unlock_protective_stop_service_ =
84- createDashboardTriggerSrv (" unlock_protective_stop" , " unlock protective stop\n " , " Protective stop releasing" );
84+ createDashboardTriggerSrv (" ~/ unlock_protective_stop" , " unlock protective stop\n " , " Protective stop releasing" );
8585
8686 // Query whether there is currently a program running
8787 running_service_ = node_->create_service <ur_dashboard_msgs::srv::IsProgramRunning>(
88- " program_running" ,
88+ " ~/ program_running" ,
8989 std::bind (&DashboardClientROS::handleRunningQuery, this , std::placeholders::_1, std::placeholders::_2));
9090
9191 // Load a robot installation from a file
9292 get_loaded_program_service_ = node_->create_service <ur_dashboard_msgs::srv::GetLoadedProgram>(
93- " get_loaded_program" , [&](const ur_dashboard_msgs::srv::GetLoadedProgram::Request::SharedPtr req,
94- ur_dashboard_msgs::srv::GetLoadedProgram::Response::SharedPtr resp) {
93+ " ~/ get_loaded_program" , [&](const ur_dashboard_msgs::srv::GetLoadedProgram::Request::SharedPtr req,
94+ ur_dashboard_msgs::srv::GetLoadedProgram::Response::SharedPtr resp) {
9595 try
9696 {
9797 resp->answer = this ->client_ .sendAndReceive (" get loaded program\n " );
@@ -114,8 +114,8 @@ DashboardClientROS::DashboardClientROS(const rclcpp::Node::SharedPtr& node, cons
114114
115115 // Load a robot installation from a file
116116 load_installation_service_ = node_->create_service <ur_dashboard_msgs::srv::Load>(
117- " load_installation" , [&](const ur_dashboard_msgs::srv::Load::Request::SharedPtr req,
118- ur_dashboard_msgs::srv::Load::Response::SharedPtr resp) {
117+ " ~/ load_installation" , [&](const ur_dashboard_msgs::srv::Load::Request::SharedPtr req,
118+ ur_dashboard_msgs::srv::Load::Response::SharedPtr resp) {
119119 try
120120 {
121121 resp->answer = this ->client_ .sendAndReceive (" load installation " + req->filename + " \n " );
@@ -132,8 +132,8 @@ DashboardClientROS::DashboardClientROS(const rclcpp::Node::SharedPtr& node, cons
132132
133133 // Load a robot program from a file
134134 load_program_service_ = node->create_service <ur_dashboard_msgs::srv::Load>(
135- " load_program" , [&](const ur_dashboard_msgs::srv::Load::Request::SharedPtr req,
136- ur_dashboard_msgs::srv::Load::Response::SharedPtr resp) {
135+ " ~/ load_program" , [&](const ur_dashboard_msgs::srv::Load::Request::SharedPtr req,
136+ ur_dashboard_msgs::srv::Load::Response::SharedPtr resp) {
137137 try
138138 {
139139 resp->answer = this ->client_ .sendAndReceive (" load " + req->filename + " \n " );
@@ -150,13 +150,13 @@ DashboardClientROS::DashboardClientROS(const rclcpp::Node::SharedPtr& node, cons
150150
151151 // // Query whether the current program is saved
152152 is_program_saved_service_ = node_->create_service <ur_dashboard_msgs::srv::IsProgramSaved>(
153- " program_saved" ,
153+ " ~/ program_saved" ,
154154 std::bind (&DashboardClientROS::handleSavedQuery, this , std::placeholders::_1, std::placeholders::_2));
155155
156156 // Service to show a popup on the UR Teach pendant.
157157 popup_service_ = node_->create_service <ur_dashboard_msgs::srv::Popup>(
158- " popup" , [&](ur_dashboard_msgs::srv::Popup::Request::SharedPtr req,
159- ur_dashboard_msgs::srv::Popup::Response::SharedPtr resp) {
158+ " ~/ popup" , [&](ur_dashboard_msgs::srv::Popup::Request::SharedPtr req,
159+ ur_dashboard_msgs::srv::Popup::Response::SharedPtr resp) {
160160 try
161161 {
162162 resp->answer = this ->client_ .sendAndReceive (" popup " + req->message + " \n " );
@@ -173,8 +173,8 @@ DashboardClientROS::DashboardClientROS(const rclcpp::Node::SharedPtr& node, cons
173173
174174 // Service to query the current program state
175175 program_state_service_ = node_->create_service <ur_dashboard_msgs::srv::GetProgramState>(
176- " program_state" , [&](const ur_dashboard_msgs::srv::GetProgramState::Request::SharedPtr /* unused*/ ,
177- ur_dashboard_msgs::srv::GetProgramState::Response::SharedPtr resp) {
176+ " ~/ program_state" , [&](const ur_dashboard_msgs::srv::GetProgramState::Request::SharedPtr /* unused*/ ,
177+ ur_dashboard_msgs::srv::GetProgramState::Response::SharedPtr resp) {
178178 try
179179 {
180180 resp->answer = this ->client_ .sendAndReceive (" programState\n " );
@@ -198,18 +198,18 @@ DashboardClientROS::DashboardClientROS(const rclcpp::Node::SharedPtr& node, cons
198198
199199 // Service to query the current safety mode
200200 safety_mode_service_ = node_->create_service <ur_dashboard_msgs::srv::GetSafetyMode>(
201- " get_safety_mode" ,
201+ " ~/ get_safety_mode" ,
202202 std::bind (&DashboardClientROS::handleSafetyModeQuery, this , std::placeholders::_1, std::placeholders::_2));
203203
204204 // Service to query the current robot mode
205205 robot_mode_service_ = node_->create_service <ur_dashboard_msgs::srv::GetRobotMode>(
206- " get_robot_mode" ,
206+ " ~/ get_robot_mode" ,
207207 std::bind (&DashboardClientROS::handleRobotModeQuery, this , std::placeholders::_1, std::placeholders::_2));
208208
209209 // Service to add a message to the robot's log
210210 add_to_log_service_ = node->create_service <ur_dashboard_msgs::srv::AddToLog>(
211- " add_to_log" , [&](const ur_dashboard_msgs::srv::AddToLog::Request::SharedPtr req,
212- ur_dashboard_msgs::srv::AddToLog::Response::SharedPtr resp) {
211+ " ~/ add_to_log" , [&](const ur_dashboard_msgs::srv::AddToLog::Request::SharedPtr req,
212+ ur_dashboard_msgs::srv::AddToLog::Response::SharedPtr resp) {
213213 try
214214 {
215215 resp->answer = this ->client_ .sendAndReceive (" addToLog " + req->message + " \n " );
@@ -226,8 +226,8 @@ DashboardClientROS::DashboardClientROS(const rclcpp::Node::SharedPtr& node, cons
226226
227227 // General purpose service to send arbitrary messages to the dashboard server
228228 raw_request_service_ = node_->create_service <ur_dashboard_msgs::srv::RawRequest>(
229- " raw_request" , [&](const ur_dashboard_msgs::srv::RawRequest::Request::SharedPtr req,
230- ur_dashboard_msgs::srv::RawRequest::Response::SharedPtr resp) {
229+ " ~/ raw_request" , [&](const ur_dashboard_msgs::srv::RawRequest::Request::SharedPtr req,
230+ ur_dashboard_msgs::srv::RawRequest::Response::SharedPtr resp) {
231231 try
232232 {
233233 resp->answer = this ->client_ .sendAndReceive (req->query + " \n " );
@@ -241,9 +241,9 @@ DashboardClientROS::DashboardClientROS(const rclcpp::Node::SharedPtr& node, cons
241241 });
242242
243243 // Service to reconnect to the dashboard server
244- reconnect_service_ =
245- node_-> create_service <std_srvs::srv::Trigger>( " connect" , [&]( const std_srvs::srv::Trigger::Request::SharedPtr req ,
246- std_srvs::srv::Trigger::Response::SharedPtr resp) {
244+ reconnect_service_ = node_-> create_service <std_srvs::srv::Trigger>(
245+ " ~/ connect" ,
246+ [&]( const std_srvs::srv::Trigger::Request::SharedPtr req, std_srvs::srv::Trigger::Response::SharedPtr resp) {
247247 try
248248 {
249249 resp->success = connect ();
@@ -259,8 +259,8 @@ DashboardClientROS::DashboardClientROS(const rclcpp::Node::SharedPtr& node, cons
259259
260260 // Disconnect from the dashboard service.
261261 quit_service_ =
262- node_->create_service <std_srvs::srv::Trigger>(" quit" , [&](const std_srvs::srv::Trigger::Request::SharedPtr req,
263- std_srvs::srv::Trigger::Response::SharedPtr resp) {
262+ node_->create_service <std_srvs::srv::Trigger>(" ~/ quit" , [&](const std_srvs::srv::Trigger::Request::SharedPtr req,
263+ std_srvs::srv::Trigger::Response::SharedPtr resp) {
264264 try
265265 {
266266 resp->message = this ->client_ .sendAndReceive (" quit\n " );
0 commit comments