diff --git a/CMakeLists.txt b/CMakeLists.txt
index 45eb39b8e63065faa9d89108af79de6d15dc110d..f8eeccd70ba49ec518786a5e8735ee486fcddaee 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -57,12 +57,10 @@ include_directories(${catkin_INCLUDE_DIRS})
 add_executable(BasicCartesianPlanner src/BasicCartesianPlanner.cpp)
 add_executable(BasicJointSpacePlanner src/BasicJointSpacePlanner.cpp)
 add_executable(ObstacleAwarePlanner src/ObstacleAwarePlanner.cpp)
-add_executable(GraspPlanner src/GraspPlanner.cpp)
 add_executable(PickPlacePlanner src/PickPlacePlanner.cpp)
 
 ## Add cmake target dependencies of the executable
 target_link_libraries(BasicCartesianPlanner ${catkin_LIBRARIES})
 target_link_libraries(BasicJointSpacePlanner ${catkin_LIBRARIES})
 target_link_libraries(ObstacleAwarePlanner ${catkin_LIBRARIES})
-target_link_libraries(GraspPlanner ${catkin_LIBRARIES})
 target_link_libraries(PickPlacePlanner ${catkin_LIBRARIES})
diff --git a/README.md b/README.md
index 52d1851fa12dd717bc31354d8b6089c18d56139a..85b579b13332f3b7f86765216a5ad41d5df74ebd 100644
--- a/README.md
+++ b/README.md
@@ -13,6 +13,18 @@ Contains different examples for the planning and execution of robotic motions wi
 Please note that all examples must be run in a built catkin workspace from within
 a shell with all ROS paths properly set up (i.e., after running `source devel/setup.sh`).
 
+### Planning and Simulation based on RViz
+
+This is an example to use RViz and Gazebo interactively. Motions can be planned and executed from the RViz GUI.
+
+- Command: `roslaunch sample_applications interactive_planner.launch`
+- Expected results:
+    - RViz window to control the robot
+    - Gazebo window to observe the executed robot motion
+    - rqt to show log messages
+    - The robot does not move automatically, but can be controlled with RViz (cf. the [tutorial](http://docs.ros.org/melodic/api/moveit_tutorials/html/doc/quickstart_in_rviz/quickstart_in_rviz_tutorial.html))
+
+
 ### Minimal "Hello World" Example
 
 This example of an execution of a simple motion.
@@ -52,7 +64,6 @@ In this example, an object can be observed in the RViz planning window. This obj
     - A Gazebo window to observe the executed robot motion opens
     - An rqt window to show log messages opens
     - An RViz window to show the plan and trigger the motion open
-    - The motion does **not** start automatically, instead it must be triggered by pressing *next* in the RvizVisualToolsGUI within RViz
 
 ### Execution of a Pick-and-Place Task
 
@@ -72,16 +83,6 @@ In this example, an object can be observed in the RViz planning window. This obj
       problems can also happen during an actual execution, so we have to live with them.
     - If a problem like this occurs, be thankful that it was just a simulation and simply restart.
 
-### Planning and Simulation based on RViz
-
-This is an example to use RViz and Gazebo interactively. Motions can be planned and executed from the RViz GUI.
-
-- Command: `roslaunch sample_applications interactive_planner.launch`
-- Expected results:
-    - RViz window to control the robot
-    - Gazebo window to observe the executed robot motion
-    - rqt to show log messages
-    - The robot does not move automatically, but can be controlled with RViz (cf. the [tutorial](http://docs.ros.org/melodic/api/moveit_tutorials/html/doc/quickstart_in_rviz/quickstart_in_rviz_tutorial.html))
 
 
 
diff --git a/launch/basic_cartesian_planner.launch b/launch/cartesian_planner.launch
similarity index 100%
rename from launch/basic_cartesian_planner.launch
rename to launch/cartesian_planner.launch
diff --git a/launch/interactive_planner.launch b/launch/interactive_planner.launch
index adb361e603591121375703bad9bda5073962aaac..1cf1e63e7a76638c961369e5dcd2e54887354103 100644
--- a/launch/interactive_planner.launch
+++ b/launch/interactive_planner.launch
@@ -4,6 +4,4 @@
 
     <include file="$(find panda_moveit_config)/launch/moveit_rviz.launch" />
 
-    <node name="rqt_console" pkg="rqt_console" type="rqt_console" />
-
 </launch>
diff --git a/launch/basic_joint_space_planner.launch b/launch/joint_space_planner.launch
similarity index 100%
rename from launch/basic_joint_space_planner.launch
rename to launch/joint_space_planner.launch
diff --git a/launch/obstacle_aware_planner.launch b/launch/obstacle_aware_planner.launch
index cbd564c10bff2df4c02bf29fa58a09a9c2dd75f4..fe48f4592e6b8481ee328c3a46259ab972233628 100644
--- a/launch/obstacle_aware_planner.launch
+++ b/launch/obstacle_aware_planner.launch
@@ -4,7 +4,7 @@
 
     <include file="$(find panda_moveit_config)/launch/moveit_rviz.launch" />
 
-    <node name="spawn_box" pkg="gazebo_ros" type="spawn_model" args="-urdf -z 1 -file $(find tutorial_moveit_motion_planning)/models/box.urdf -model box" respawn="false" output="screen" />
+    <node name="spawn_box" pkg="gazebo_ros" type="spawn_model" args="-urdf -z 1 -file $(find sample_applications)/models/box.urdf -model box" respawn="false" output="screen" />
 
     <node pkg="sample_applications" type="ObstacleAwarePlanner" name="ObstacleAwarePlannerInstance" respawn="false" output="screen"/>
 
diff --git a/src/BasicCartesianPlanner.cpp b/src/BasicCartesianPlanner.cpp
index 5240eab83513efcdf0b5eedf80c8fd55d41f7706..e5afd6e95f3882d68a25adec56cf96d04d6a2388 100644
--- a/src/BasicCartesianPlanner.cpp
+++ b/src/BasicCartesianPlanner.cpp
@@ -22,23 +22,8 @@ int main(int argc, char **argv) {
     static const std::string PLANNING_GROUP = "panda_arm";
     moveit::planning_interface::MoveGroupInterface group(PLANNING_GROUP);
 
-    // visualization setup
-    // MoveIts visual tools provide capabilities for visualizing objects, robots, and trajectories in RViz
-    namespace rvt = rviz_visual_tools;
-    moveit_visual_tools::MoveItVisualTools visual_tools("panda_link0");
-
-    // Batch publishing is used to reduce the number of messages being sent to RViz for large visualizations
-    visual_tools.enableBatchPublishing();
-
-    // remote control is an introspection tool that allows users to step through a high level script
-    // via buttons and keyboard shortcuts in RViz
-    visual_tools.loadRemoteControl();
     ros::Duration(3.0).sleep();
 
-    // we can use visual_tools to wait for user input
-    visual_tools.prompt("Press 'next' to move the simulated robot. \n");
-    visual_tools.trigger();
-
     group.setStartStateToCurrentState();
 
     // You can plan a Cartesian path directly by specifying a list of waypoints
@@ -89,9 +74,6 @@ int main(int argc, char **argv) {
     rt.getRobotTrajectoryMsg(trajectory_msg);
     */
 
-    visual_tools.trigger();
-    visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to move the simulated robot");
-
     // execute the planned motion
     group.execute(plan);
 
diff --git a/src/BasicJointSpacePlanner.cpp b/src/BasicJointSpacePlanner.cpp
index e99010f5c54098239997056c5a891ce0860209e7..ad3fd33538465b46c3278e91a141086a339f14e6 100644
--- a/src/BasicJointSpacePlanner.cpp
+++ b/src/BasicJointSpacePlanner.cpp
@@ -22,23 +22,8 @@ int main(int argc, char **argv) {
     moveit::planning_interface::MoveGroupInterface move_group(PLANNING_GROUP);
     moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
 
-    // visualization setup
-    // MoveIts visual tools provide capabilities for visualizing objects, robots, and trajectories in RViz
-    namespace rvt = rviz_visual_tools;
-    moveit_visual_tools::MoveItVisualTools visual_tools("panda_link0");
-
-    // Batch publishing is used to reduce the number of messages being sent to RViz for large visualizations
-    visual_tools.enableBatchPublishing();
-
-    // remote control is an introspection tool that allows users to step through a high level script
-    // via buttons and keyboard shortcuts in RViz
-    visual_tools.loadRemoteControl();
     ros::Duration(3.0).sleep();
 
-    // we can use visual_tools to wait for user input
-    visual_tools.prompt("Press 'next' to plan the motion. \n");
-    visual_tools.trigger();
-
     // getting basic information
     ROS_INFO("Planning frame: %s", move_group.getPlanningFrame().c_str());
     ROS_INFO("End effector link: %s", move_group.getEndEffectorLink().c_str());
@@ -69,9 +54,6 @@ int main(int argc, char **argv) {
     bool success = (move_group.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS);
     ROS_INFO("Visualizing plan %s", success ? "" : "FAILED");
 
-    visual_tools.trigger();
-    visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to continue the demo");
-
     // Move the (simulated) robot in gazebo
     move_group.move();
 
diff --git a/src/PickPlacePlanner.cpp b/src/PickPlacePlanner.cpp
index 4f236a0e5e653790409bdcd798638c2b17adedf0..0dcd019720a5976b08828c8220786432a625b1e7 100644
--- a/src/PickPlacePlanner.cpp
+++ b/src/PickPlacePlanner.cpp
@@ -64,7 +64,6 @@
  */
 void openGripper(trajectory_msgs::JointTrajectory& posture)
 {
-  // BEGIN_SUB_TUTORIAL open_gripper
   /* Add both finger joints of panda robot. */
   posture.joint_names.resize(2);
   posture.joint_names[0] = "panda_finger_joint1";
@@ -76,7 +75,6 @@ void openGripper(trajectory_msgs::JointTrajectory& posture)
   posture.points[0].positions[0] = 0.04;
   posture.points[0].positions[1] = 0.04;
   posture.points[0].time_from_start = ros::Duration(0.5);
-  // END_SUB_TUTORIAL
 }
 
 /**