diff --git a/src/dummy_cgv_controller.cpp b/src/dummy_cgv_controller.cpp
index 5714c2f3f7d1784db5e53b22dd05ba6dda478bac..8e03d60c03825c6ee3e5b7794ece422641b0ac53 100644
--- a/src/dummy_cgv_controller.cpp
+++ b/src/dummy_cgv_controller.cpp
@@ -19,7 +19,7 @@
 #include "ccf/connection/NngConnection.h"
 #include "ccf/util/NodeUtil.h"
 
-std::string NODE_NAME;
+std::string NODE_NAME = "dummy_cgv_controller";
 
 using CetiRosToolbox::getParameter;
 using CetiRosToolbox::getPrivateParameter;
@@ -28,8 +28,8 @@ int main(int argc, char **argv) {
 
     GOOGLE_PROTOBUF_VERIFY_VERSION;
 
-    NODE_NAME = ros::this_node::getName();
     ros::init(argc, argv, NODE_NAME);
+    NODE_NAME = ros::this_node::getName();
 
     ros::NodeHandle n("connector_node_ros_cgv"); // namespace where the connection_address is
 
@@ -50,6 +50,7 @@ int main(int argc, char **argv) {
         ROS_INFO_STREAM("[" << NODE_NAME << "] Connecting to client at " << client << ".");
         std::unique_ptr<NngConnection> client_connection = std::make_unique<NngConnection>(client, false);
         client_connection->setSendTopic(getParameter<std::string>(n, "topics/selection", "selection"));
+        client_connection->setReceiveTopic("client_scene");
         connector.addConnection(std::move(client_connection));
     }
 
diff --git a/src/moveit_cgv_controller.cpp b/src/moveit_cgv_controller.cpp
index d38f637b50df1580e83bf013b676ff9c9c53b322..c8b548cd4aaaec5042e6aa101f6140bbed225ff8 100644
--- a/src/moveit_cgv_controller.cpp
+++ b/src/moveit_cgv_controller.cpp
@@ -18,7 +18,7 @@
 #include "ccf/connection/NngConnection.h"
 #include "ccf/util/NodeUtil.h"
 
-std::string NODE_NAME;
+std::string NODE_NAME = "moveit_cgv_controller";
 
 using CetiRosToolbox::getParameter;
 using CetiRosToolbox::getPrivateParameter;
@@ -27,8 +27,8 @@ int main(int argc, char **argv) {
 
     GOOGLE_PROTOBUF_VERIFY_VERSION;
 
-    NODE_NAME = ros::this_node::getName();
     ros::init(argc, argv, NODE_NAME);
+    NODE_NAME = ros::this_node::getName();
 
     ros::NodeHandle n("connector_node_ros_cgv"); // namespace where the connection_address is
 
@@ -49,6 +49,7 @@ int main(int argc, char **argv) {
         ROS_INFO_STREAM("[" << NODE_NAME << "] Connecting to client at " << client << ".");
         std::unique_ptr<NngConnection> client_connection = std::make_unique<NngConnection>(client, false);
         client_connection->setSendTopic(getParameter<std::string>(n, "topics/selection", "selection"));
+        client_connection->setReceiveTopic("client_scene");
         connector.addConnection(std::move(client_connection));
     }