diff --git a/launch/demo_gazebo.launch b/launch/demo_gazebo.launch
index a9f320c59601bb8fb909d972025dac60f735b4ca..2f63ceb1888d79e58a184c93efb9cf86feb031eb 100644
--- a/launch/demo_gazebo.launch
+++ b/launch/demo_gazebo.launch
@@ -1,21 +1,27 @@
 <launch>
-
   <!-- specify the planning pipeline -->
   <arg name="pipeline" default="ompl" />
 
+  <!-- Panda specific options -->
+  <arg name="load_gripper" default="true" />
+  <arg name="transmission" default="effort" />
+
   <!-- Gazebo specific options -->
-  <arg name="gazebo_gui" default="true"/>
-  <arg name="paused" default="false"/>
+  <arg name="gazebo_gui" default="true" />
+  <arg name="paused" default="false" />
 
-  <!-- launch the gazebo simulator and spawn the robot -->
-  <include file="$(dirname)/gazebo.launch" >
-    <arg name="paused" value="$(arg paused)"/>
-    <arg name="gazebo_gui" value="$(arg gazebo_gui)"/>
+  <!-- Launch the gazebo simulator and spawn the robot -->
+  <include file="$(find franka_gazebo)/launch/panda.launch" pass_all_args="true">
+    <arg name="headless" value="$(eval not arg('gazebo_gui'))" />
+    <arg name="use_gripper" default="$(arg load_gripper)" />
+    <arg name="controller" default="joint_trajectory_controller" />
   </include>
 
   <include file="$(dirname)/demo.launch" pass_all_args="true">
     <!-- robot description is loaded by gazebo.launch, to enable Gazebo features -->
     <arg name="load_robot_description" value="false" />
-    <arg name="moveit_controller_manager" value="ros_control" />
+    <!-- MoveItSimpleControllerManager provides ros_control's JointTrajectory controllers
+         as well as GripperCommand actions -->
+    <arg name="moveit_controller_manager" value="simple" />
   </include>
 </launch>
diff --git a/launch/gazebo.launch b/launch/gazebo.launch
deleted file mode 100644
index 75fb922bc833cba9c11230d73f809e1e81536892..0000000000000000000000000000000000000000
--- a/launch/gazebo.launch
+++ /dev/null
@@ -1,32 +0,0 @@
-<?xml version="1.0"?>
-<launch>
-  <arg name="paused" default="false"/>
-  <arg name="gazebo_gui" default="true"/>
-  <arg name="initial_joint_positions" doc="Initial joint configuration of the robot"
-       default=" -J panda_finger_joint1 0.035 -J panda_finger_joint2 0.035 -J panda_joint1 0 -J panda_joint2 -0.785 -J panda_joint3 0 -J panda_joint4 -2.356 -J panda_joint5 0 -J panda_joint6 1.571 -J panda_joint7 0.785"/>
-
-  <!-- startup simulated world -->
-  <include file="$(find gazebo_ros)/launch/empty_world.launch">
-    <arg name="world_name" default="worlds/empty.world"/>
-    <arg name="paused" value="true"/>
-    <arg name="gui" value="$(arg gazebo_gui)"/>
-  </include>
-
-  <!-- send robot urdf to param server -->
-  <param name="robot_description" command="xacro hand:=true '$(find franka_description)/robots/panda_arm.urdf.xacro'" />
-
-  <!-- unpause only after loading robot model -->
-  <arg name="unpause" value="$(eval '' if arg('paused') else '-unpause')" />
-  <!-- push robot_description to factory and spawn robot in gazebo at the origin, change x,y,z arguments to spawn in a different position -->
-  <arg name="world_pose" value="-x 0 -y 0 -z 0" />
-  <node name="spawn_gazebo_model" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model robot $(arg unpause) $(arg world_pose) $(arg initial_joint_positions)"
-    respawn="false" output="screen" />
-
-  <!-- Load joint controller parameters for Gazebo -->
-  <rosparam file="$(find panda_moveit_config)/config/gazebo_controllers.yaml" />
-  <!-- Spawn Gazebo ROS controllers -->
-  <node name="gazebo_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="joint_state_controller" />
-  <!-- Load ROS controllers -->
-  <include file="$(dirname)/ros_controllers.launch"/>
-
-</launch>