diff --git a/launch/joints_client_bt_example.launch b/launch/joints_client_bt_example.launch
index c6328bbf3dbdc52b6960f796fa1453d43fecae03..ebdfd6916cdbc893fb7e311a8ce6ae1915bd8e4f 100644
--- a/launch/joints_client_bt_example.launch
+++ b/launch/joints_client_bt_example.launch
@@ -23,7 +23,7 @@
 
   <!-- JointTrajectoryController -->
   <arg name="controller_config_file" default="$(find iri_joint_trajectory_gazebo)/config/$(arg device_ns)_sim_config.yaml" />
-  <arg name="joint_trajecotry_config_file" default="$(find iri_joint_trajectory_gazebo)/config/joint_trajectory_controller_config.yaml"/>
+  <arg name="joint_trajectory_config_file" default="$(find iri_joint_trajectory_gazebo)/config/joint_trajectory_controller_config.yaml"/>
   <arg name="controller_description_file" default="$(find iri_joint_trajectory_gazebo)/urdf/$(arg device_ns)_example.xacro" />
   <arg name="effort_controller_ns" default="effort_controller" />
   <arg name="position_controller_ns" default="position_controller" />
@@ -35,7 +35,7 @@
     <arg name="robot_ns" value="$(arg robot_ns)"/>
     <arg name="output" value="$(arg output)"/>
     <arg name="launch_prefix" value="$(arg launch_prefix)"/>
-    <arg name="config_file" value="$(arg joint_trajecotry_config_file)"/>
+    <arg name="config_file" value="$(arg joint_trajectory_config_file)"/>
   </include>
 
   <include file="$(find gazebo_ros)/launch/empty_world.launch">
@@ -54,25 +54,6 @@
     <arg name="pub_clock_frequency" value="100"/>
   </include>
 
-  <!-- load the controllers -->
-  <node name="controller_spawner"
-        pkg ="controller_manager"
-        type="controller_manager"
-        respawn="false"
-        output="screen"
-        ns="/$(arg robot_ns)"
-        args="spawn joint_state_controller">
-  </node>
-
-  <node name="controller_loader"
-        pkg ="controller_manager"
-        type="controller_manager"
-        respawn="false"
-        output="screen"
-        ns="/$(arg robot_ns)"
-        args="load $(arg effort_controller_ns) $(arg position_controller_ns)">
-  </node>
-
   <param name="robot_description"
     command="$(find xacro)/xacro --inorder '$(arg controller_description_file)'" />
   
diff --git a/launch/joints_client_example.launch b/launch/joints_client_example.launch
index 49b21706917d845cd1042e8ea149a93e5d56c24d..f691d2d1236ca95b1f775879abf1cc90ca9226f8 100644
--- a/launch/joints_client_example.launch
+++ b/launch/joints_client_example.launch
@@ -23,7 +23,7 @@
 
   <!-- JointTrajectoryController -->
   <arg name="controller_config_file" default="$(find iri_joint_trajectory_gazebo)/config/$(arg device_ns)_sim_config.yaml" />
-  <arg name="joint_trajecotry_config_file" default="$(find iri_joint_trajectory_gazebo)/config/joint_trajectory_controller_config.yaml"/>
+  <arg name="joint_trajectory_config_file" default="$(find iri_joint_trajectory_gazebo)/config/joint_trajectory_controller_config.yaml"/>
   <arg name="controller_description_file" default="$(find iri_joint_trajectory_gazebo)/urdf/$(arg device_ns)_example.xacro" />
   <arg name="effort_controller_ns" default="effort_controller" />
   <arg name="position_controller_ns" default="position_controller" />
@@ -35,7 +35,7 @@
     <arg name="robot_ns" value="$(arg robot_ns)"/>
     <arg name="output" value="$(arg output)"/>
     <arg name="launch_prefix" value="$(arg launch_prefix)"/>
-    <arg name="config_file" value="$(arg joint_trajecotry_config_file)"/>
+    <arg name="config_file" value="$(arg joint_trajectory_config_file)"/>
   </include>
 
   <include file="$(find gazebo_ros)/launch/empty_world.launch">
@@ -54,25 +54,6 @@
     <arg name="pub_clock_frequency" value="100"/>
   </include>
 
-  <!-- load the controllers -->
-  <node name="controller_spawner"
-        pkg ="controller_manager"
-        type="controller_manager"
-        respawn="false"
-        output="screen"
-        ns="/$(arg robot_ns)"
-        args="spawn joint_state_controller">
-  </node>
-
-  <node name="controller_loader"
-        pkg ="controller_manager"
-        type="controller_manager"
-        respawn="false"
-        output="screen"
-        ns="/$(arg robot_ns)"
-        args="load $(arg effort_controller_ns) $(arg position_controller_ns)">
-  </node>
-
   <param name="robot_description"
     command="$(find xacro)/xacro --inorder '$(arg controller_description_file)'" />