diff --git a/launch/ivo_arm_client_sim.launch b/launch/ivo_arm_client_sim.launch
new file mode 100644
index 0000000000000000000000000000000000000000..a33c0146c70b68a37b30ee12598b794d8c7fce1b
--- /dev/null
+++ b/launch/ivo_arm_client_sim.launch
@@ -0,0 +1,29 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<launch>
+  <arg name="node_name" default="arm_client" />
+  <arg name="output" default="log" />
+  <arg name="launch_prefix" default="" />
+  <arg name="config_file" default="$(find tiago_arm_module)/config/ivo_arm_module_default.yaml" />
+  <arg name="move_groups_file" default="$(find tiago_arm_module)/config/ivo_move_groups.yaml" />
+  <arg name="joint_states_topic" default="/joint_states"/>
+  <arg name="arm_action" default="/move_group"/>
+  <arg name="planning_scene_topic" default="/planning_scene"/>
+  <arg name="get_planning_scene_service" default="/get_planning_scene"/>
+
+  <include file="$(find ivo_1_gazebo)/launch/ivo_gazebo.launch">
+  </include>
+
+  <include file="$(find tiago_arm_module)/launch/tiago_arm_client.launch">
+    <arg name="node_name"                  value="$(arg node_name)" />
+    <arg name="output"                     value="$(arg output)" />
+    <arg name="launch_prefix"              value="$(arg launch_prefix)" />
+    <arg name="config_file"                value="$(arg config_file)" />
+    <arg name="move_groups_file"           value="$(arg move_groups_file)" />
+    <arg name="joint_states_topic"         value="$(arg joint_states_topic)"/>
+    <arg name="arm_action"                 value="$(arg arm_action)"/>
+    <arg name="planning_scene_topic"       value="$(arg planning_scene_topic)"/>
+    <arg name="get_planning_scene_service" value="$(arg get_planning_scene_service)"/>
+  </include>
+
+</launch>
+
diff --git a/launch/tiago_arm_client.launch b/launch/tiago_arm_client.launch
index 7e6223fed7771fdedadec5922050e3a1034656e1..db742b0fc33667a8edd4420d00b07d69e4e07e94 100644
--- a/launch/tiago_arm_client.launch
+++ b/launch/tiago_arm_client.launch
@@ -1,20 +1,31 @@
+<?xml version="1.0" encoding="UTF-8"?>
 <launch>
+  <arg name="node_name" default="arm_client" />
+  <arg name="output" default="log" />
+  <arg name="launch_prefix" default="" />
+  <arg name="config_file" default="$(find tiago_arm_module)/config/tiago_arm_module_default.yaml" />
+  <arg name="move_groups_file" default="$(find tiago_arm_module)/config/tiago_move_groups.yaml" />
+  <arg name="joint_states_topic" default="/joint_states"/>
+  <arg name="arm_action" default="/move_group"/>
+  <arg name="planning_scene_topic" default="/planning_scene"/>
+  <arg name="get_planning_scene_service" default="/get_planning_scene"/>
 
   <!-- launch the play motion client node -->
-  <node name="arm_client"
+  <node name="$(arg node_name)"
         pkg="tiago_arm_module"
         type="tiago_arm_client"
-        output="screen">
+	output="$(arg output)"
+	launch-prefix="$(arg launch_prefix)">
     <remap from="~/arm_torso/joint_states"
-             to="/joint_states"/>
+             to="$(arg joint_states_topic)"/>
     <remap from="~/arm_torso/arm"
-             to="/move_group"/>
+             to="$(arg arm_action)"/>
     <remap from="~/arm_torso/planning_scene"
-             to="/planning_scene"/>
+             to="$(arg planning_scene_topic)"/>
     <remap from="~/arm_torso/get_planning_scene"
-             to="/get_planning_scene"/>
-    <rosparam file="$(find tiago_arm_module)/config/tiago_arm_module_default.yaml" command="load" ns="arm_torso" />
-    <rosparam file="$(find tiago_arm_module)/config/tiago_move_groups.yaml" command="load" ns="arm_torso" />
+             to="$(arg get_planning_scene_service)"/>
+    <rosparam file="$(arg config_file)" command="load" ns="arm_torso" />
+    <rosparam file="$(arg move_groups_file)" command="load" ns="arm_torso" />
   </node>
 
   <!-- launch dynamic reconfigure -->
diff --git a/launch/tiago_arm_client_sim.launch b/launch/tiago_arm_client_sim.launch
index 4dcf5affe60a0927dd36d68c29d0cd0187f350ef..ed133261c9949d388265bc536fefe187198cca34 100644
--- a/launch/tiago_arm_client_sim.launch
+++ b/launch/tiago_arm_client_sim.launch
@@ -1,4 +1,14 @@
+<?xml version="1.0" encoding="UTF-8"?>
 <launch>
+  <arg name="node_name" default="arm_client" />
+  <arg name="output" default="log" />
+  <arg name="launch_prefix" default="" />
+  <arg name="config_file" default="$(find tiago_arm_module)/config/tiago_arm_module_default.yaml" />
+  <arg name="move_groups_file" default="$(find tiago_arm_module)/config/tiago_move_groups.yaml" />
+  <arg name="joint_states_topic" default="/joint_states"/>
+  <arg name="arm_action" default="/move_group"/>
+  <arg name="planning_scene_topic" default="/planning_scene"/>
+  <arg name="get_planning_scene_service" default="/get_planning_scene"/>
 
   <include file="$(find tiago_gazebo)/launch/tiago_gazebo.launch">
     <arg name="public_sim" value="true" />
@@ -7,7 +17,17 @@
     <arg name="use_moveit_camera" value="true"/>
   </include>
 
-  <include file="$(find tiago_arm_module)/launch/tiago_arm_client.launch"/>
+  <include file="$(find tiago_arm_module)/launch/tiago_arm_client.launch">
+    <arg name="node_name"                  value="$(arg node_name)" />
+    <arg name="output"                     value="$(arg output)" />
+    <arg name="launch_prefix"              value="$(arg launch_prefix)" />
+    <arg name="config_file"                value="$(arg config_file)" />
+    <arg name="move_groups_file"           value="$(arg move_groups_file)" />
+    <arg name="joint_states_topic"         value="$(arg joint_states_topic)"/>
+    <arg name="arm_action"                 value="$(arg arm_action)"/>
+    <arg name="planning_scene_topic"       value="$(arg planning_scene_topic)"/>
+    <arg name="get_planning_scene_service" value="$(arg get_planning_scene_service)"/>
+  </include>
 
 </launch>