From ae40e919e4a3ff8f0ab22708b7ab3802010fc54f Mon Sep 17 00:00:00 2001
From: Johannes Mey <johannes.mey@tu-dresden.de>
Date: Mon, 30 Aug 2021 12:58:43 +0200
Subject: [PATCH] use getParameter

---
 src/dummy_cgv_controller.cpp  | 10 +++-------
 src/moveit_cgv_controller.cpp |  8 ++------
 2 files changed, 5 insertions(+), 13 deletions(-)

diff --git a/src/dummy_cgv_controller.cpp b/src/dummy_cgv_controller.cpp
index a05133b..191078a 100644
--- a/src/dummy_cgv_controller.cpp
+++ b/src/dummy_cgv_controller.cpp
@@ -29,13 +29,9 @@ int main(int argc, char **argv) {
 
     ros::init(argc, argv, NODE_NAME);
 
-    ros::NodeHandle n("connector_node_ros_cgv"); // namespace where the cgv_address is
+    ros::NodeHandle n("connector_node_ros_cgv"); // namespace where the connection_address is
 
-    std::string cgv_address = "tcp://*:6576";
-    if (!n.getParam("cgv_address", cgv_address)) {
-        ROS_WARN_STREAM("[" << NODE_NAME << "] Could not get string value for " << n.getNamespace()
-                            << "/cgv_address from param server, using default " << cgv_address);
-    }
+    std::string cgv_address = getParameter<std::string>(n, "connection_address", "tcp://*:6576");
 
     DummyRobotArmController connector{n, NODE_NAME};
 
@@ -118,4 +114,4 @@ int main(int argc, char **argv) {
     ros::spin();
 
     return 0;
-}
\ No newline at end of file
+}
diff --git a/src/moveit_cgv_controller.cpp b/src/moveit_cgv_controller.cpp
index 296b943..58cb659 100644
--- a/src/moveit_cgv_controller.cpp
+++ b/src/moveit_cgv_controller.cpp
@@ -28,13 +28,9 @@ int main(int argc, char **argv) {
 
     ros::init(argc, argv, NODE_NAME);
 
-    ros::NodeHandle n("connector_node_ros_cgv"); // namespace where the cgv_address is
+    ros::NodeHandle n("connector_node_ros_cgv"); // namespace where the connection_address is
 
-    std::string cgv_address = "tcp://*:6576";
-    if (!n.getParam("cgv_address", cgv_address)) {
-        ROS_WARN_STREAM("[" << NODE_NAME << "] Could not get string value for " << n.getNamespace()
-                            << "/cgv_address from param server, using default " << cgv_address);
-    }
+    std::string cgv_address = getParameter<std::string>(n, "connection_address", "tcp://*:6576");
 
     MoveItRobotArmController connector{n, NODE_NAME};
 
-- 
GitLab