diff --git a/src/moveit_sorting_controller.cpp b/src/moveit_sorting_controller.cpp
index e5ba294a303d324bc487dd832a61fcbd426a1740..dc1bcc544d72c00128f7e54067a179efefcd2f96 100644
--- a/src/moveit_sorting_controller.cpp
+++ b/src/moveit_sorting_controller.cpp
@@ -32,7 +32,7 @@ int main(int argc, char** argv)
 
   ros::NodeHandle n("connector_node_ros_ccf");  // namespace where the connection_address is
 
-  auto robotName = getPrivateParameter<std::string>("arm", "arm1");
+  auto robotName = getPrivateParameter<std::string>("arm", "arm");
   ROS_INFO_STREAM("This cell controls arm " << robotName);
 
   MoveItRobotArmController controller{ n, NODE_NAME, robotName };
@@ -72,20 +72,7 @@ int main(int argc, char** argv)
     controller.sendScene();
   });  // send a scene every three seconds
 
-  controller.loadScene(getPrivateParameter<std::string>("scene", ros::package::getPath("ccf_immersive_sorting") + "/con"
-                                                                                                                  "fig/"
-                                                                                                                  "conf"
-                                                                                                                  "ig_"
-                                                                                                                  "scen"
-                                                                                                                  "e_"
-                                                                                                                  "ceti"
-                                                                                                                  "-tab"
-                                                                                                                  "le-"
-                                                                                                                  "1-"
-                                                                                                                  "empt"
-                                                                                                                  "y."
-                                                                                                                  "jso"
-                                                                                                                  "n"));
+  controller.loadScene(getPrivateParameter<std::string>("scene", ros::package::getPath("ccf_immersive_sorting") + "/config/config_scene_ceti-table-1-empty-grey.json"));
 
   // only add the scene observer after the base scene has been loaded
   controller.addCallback(scene_observer_topic, [&controller](auto msg) {