diff --git a/bag/generate_trajectory_csv.bash b/bag/generate_trajectory_csv.bash
index 327693d5d6a805c8d5e7e627c206ce17b1572647..b1b55b3e4626b06ff6239018804182ae14ebac13 100644
--- a/bag/generate_trajectory_csv.bash
+++ b/bag/generate_trajectory_csv.bash
@@ -15,7 +15,7 @@ for yamlfile in $(find ../yaml/trajectory_analysys -maxdepth 1 -type f -printf "
 do
   rm recordings/trajectory_recording$yamlname.bag
   yamlname=${yamlfile%.*}
-  roslaunch wolf_demo_imu2d imu2d_analysys.launch bag:=$BAG\_filtered_notf test:=$yamlfile speed:=1 suffix:=$yamlname
+  roslaunch wolf_demo_imu2d imu2d_analysys.launch bag:=$BAG\_filtered_notf test:=$yamlfile speed:=1 suffix:=$yamlname rviz:=false
   if [[ ${yamlname:0:1} == 'G' ]]
   then
     tend=$(rosbag info -y -k end recordings/trajectory_recording$yamlname.bag)
diff --git a/launch/imu2d_analysys.launch b/launch/imu2d_analysys.launch
index a3a4c66ce33dce7b3d71fe0a57226e46136779fa..a3a429253c9f1fcfd859c58495945feb87db70e3 100644
--- a/launch/imu2d_analysys.launch
+++ b/launch/imu2d_analysys.launch
@@ -1,6 +1,8 @@
 <!-- -->
 <launch>
     <param name="use_sim_time" value="true" />
+    <arg name="record" default="true" />
+    <arg name="rviz" default="true" />
     <arg name="speed" default="1" />
     <arg name="sec" default="0" />
     <arg name="profiling" default="false" />
@@ -14,7 +16,9 @@
     <!-- using "clock" option to use the simulated time. Rosbag launch as the first node  -->
 
     <node pkg="rostopic" type="rostopic" name="" args='pub /helena/sensors/bno055_imu/imu/topic_enable std_msgs/Bool "data: True"'/>
-    <node pkg="rosbag" type="record" name="recorder" args='record -O $(find wolf_demo_imu2d)/bag/recordings/trajectory_recording$(arg suffix).bag "/wolf_ros_node/trajectory" "/wolf_ros_node/pose_pose_with_cov"'/>
+    <group if="$(arg record)">
+      <node pkg="rosbag" type="record" name="recorder" args='record -O $(find wolf_demo_imu2d)/bag/recordings/trajectory_recording$(arg suffix).bag "/wolf_ros_node/trajectory" "/wolf_ros_node/pose_pose_with_cov"'/>
+    </group>
 
     <node pkg="tf"
           type="static_transform_publisher"
@@ -42,10 +46,13 @@
         required="true"
     	  args="-s $(arg sec) -r $(arg speed) --clock $(find wolf_demo_imu2d)/bag/$(arg bag).bag"/>      
 
-    <node type="rviz"
-          name="rviz"
-          pkg="rviz"
-          args="-d $(find wolf_demo_imu2d)/rviz/imu2d_demo.rviz"/>
+    <group if="$(arg rviz)">
+      <node type="rviz"
+            name="rviz"
+            pkg="rviz"
+            args="-d $(find wolf_demo_imu2d)/rviz/imu2d_demo.rviz"/>
+    </group>
+
     <node type="wolf_ros_node"
     	    name="wolf_ros_node"
     	    pkg="wolf_ros_node"
diff --git a/yaml/trajectory_analysys/E-1_0.yaml b/yaml/trajectory_analysys/E-1_0.yaml
index 933b2502b6964339b3bfee73d5a9c4f8484b940c..eb3837c60645475c9e1d841ff01688413cc31897 100644
--- a/yaml/trajectory_analysys/E-1_0.yaml
+++ b/yaml/trajectory_analysys/E-1_0.yaml
@@ -100,12 +100,12 @@ config:
       topic: "/ana/sensors/scan"
       sensor_name: "scanner_front_left"
       load_params_from_msg: true
-    -
-      package: "wolf_ros_imu"
-      type: "SubscriberImuEnableable"
-      topic: "/ana/sensors/bno055_imu/imumal"
-      sensor_name: "bno"
-      follow: "parameters/test_imu_subscriber_bno.yaml"
+    #-
+    #  package: "wolf_ros_imu"
+    #  type: "SubscriberImuEnableable"
+    #  topic: "/ana/sensors/bno055_imu/imumal"
+    #  sensor_name: "bno"
+    #  follow: "parameters/test_imu_subscriber_bno.yaml"
     -
       package: "wolf_ros_imu"
       type: "SubscriberImuEnableable"