diff --git a/src/dummy_cgv_controller.cpp b/src/dummy_cgv_controller.cpp index a05133b0cfa3dcc651b910f6aaf954dce29a7db0..191078a3c69c06df4293600bcae37c63fbfb7c3c 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 296b943d8b94300fd3279bf33ac0db95db3973a8..58cb6597bad21dfd0c0f1555a9f6d30e4186f358 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};