diff --git a/launch/dummy_selector.launch b/launch/dummy_selector.launch
index 045d026f4592e15b036cc49142fd51714de71202..8d761344b2488284f6f1c9b33da89e2c083b36e7 100644
--- a/launch/dummy_selector.launch
+++ b/launch/dummy_selector.launch
@@ -1,3 +1,8 @@
 <launch>
-    <node pkg="ccf_immersive_sorting" type="dummy_selection_provider" name="my_dummy_selection_provider" output="screen"/>
+    <arg name="autoselect" default="true" />
+    <arg name="prefix" default="selector" />
+    <node pkg="ccf_immersive_sorting" type="dummy_selection_provider" name="my_dummy_selection_provider" output="screen">
+        <param name="autoselect" type="bool" value="$(arg autoselect)" />
+        <param name="prefix" type="string" value="$(arg prefix)" />
+    </node>
 </launch>
diff --git a/launch/dummy_selector_manual.launch b/launch/dummy_selector_manual.launch
new file mode 100644
index 0000000000000000000000000000000000000000..5b6d080ceeb5ac10e5bf331a9797e9a1a6be0fd5
--- /dev/null
+++ b/launch/dummy_selector_manual.launch
@@ -0,0 +1,8 @@
+<launch>
+    <arg name="autoselect" default="false" />
+    <arg name="prefix" default="selector" />
+    <node pkg="ccf_immersive_sorting" type="dummy_selection_provider" name="my_dummy_selection_provider" output="screen">
+        <param name="autoselect" type="bool" value="$(arg autoselect)" />
+        <param name="prefix" type="string" value="$(arg prefix)" />
+    </node>
+</launch>
diff --git a/src/dummy_selection_provider.cpp b/src/dummy_selection_provider.cpp
index 3725ed31450df508465e195f1f085b3ed18c8f86..d2ec35cf556c087822873659e720610a6db1ab27 100644
--- a/src/dummy_selection_provider.cpp
+++ b/src/dummy_selection_provider.cpp
@@ -28,6 +28,7 @@ nng_socket sock;
 int rv;
 
 void sendSelection(const std::string &object) {
+    ROS_INFO_STREAM("Selecting random object: " << object);
     Selection selection;
     selection.set_id(object);
     int length = selection.ByteSize();
@@ -145,7 +146,6 @@ int main(int argc, char **argv) {
                     pause_rate.sleep();
                     std::string object{objects[distribution(rng)]};
 
-                    ROS_INFO_STREAM("Selecting random object: " << object);
                     sendSelection(object);
 
                     // wait again, then send the bin object