diff --git a/launch/rpa_positioning.launch b/launch/rpa_positioning.launch
index e1cf7d9ea7a65cc0bd96e41dd3ca4bde40f12d8b..f7035a6dc77b96c9d13c17913dbb3730a5920dba 100644
--- a/launch/rpa_positioning.launch
+++ b/launch/rpa_positioning.launch
@@ -34,6 +34,10 @@
           type="static_transform_publisher"
           name="odom_base"
           args="0 0 0 0 0 0 odom base 1000" />
+    <node pkg="tf"
+          type="static_transform_publisher"
+          name="base_imu"
+          args="0 0 0 0 0 0 base imu 1000" />
 		  
     <!--WOLF-->
     <node type="wolf_ros_node" 
diff --git a/rviz/positioning_rosbag.rviz b/rviz/positioning_rosbag.rviz
index 16cec3be8d0f1bd12fa523c28983807ec2b44a24..c6a8867204fde10491389a0ff16de295734870c1 100644
--- a/rviz/positioning_rosbag.rviz
+++ b/rviz/positioning_rosbag.rviz
@@ -5,6 +5,7 @@ Panels:
     Property Tree Widget:
       Expanded:
         - /Global Options1
+        - /Imu BNO1
         - /Trajectory1
         - /Trajectory1/Namespaces1
         - /Landmarks1/Namespaces1
@@ -64,15 +65,15 @@ Visualization Manager:
       Topic: /imu/data
       Unreliable: false
       Value: false
-    - Alpha: 1
+    - Alpha: 0.200000003
       Class: rviz_plugin_tutorials/Imu
       Color: 204; 51; 204
-      Enabled: false
+      Enabled: true
       History Length: 1
       Name: Imu BNO
-      Topic: /bno055_imu/imu
+      Topic: /bno055_imu/imu_remapped
       Unreliable: false
-      Value: false
+      Value: true
     - Class: rviz/MarkerArray
       Enabled: true
       Marker Topic: /wolf_ros_node/graph_trajectory
@@ -188,7 +189,7 @@ Visualization Manager:
       Marker Topic: /novatel/oem7/bestpos_ENU_marker
       Name: Fix BestPose
       Namespaces:
-        trajectory: true
+        {}
       Queue Size: 100
       Value: true
     - Class: rviz/Group
@@ -372,7 +373,7 @@ Visualization Manager:
   Views:
     Current:
       Class: rviz/ThirdPersonFollower
-      Distance: 31.9203568
+      Distance: 39.9709778
       Enable Stereo Rendering:
         Stereo Eye Separation: 0.0599999987
         Stereo Focal Distance: 1
@@ -387,10 +388,10 @@ Visualization Manager:
       Invert Z Axis: false
       Name: Current View
       Near Clip Distance: 0.00999999978
-      Pitch: 0.109797992
+      Pitch: 0.334797949
       Target Frame: ENU
       Value: ThirdPersonFollower (rviz)
-      Yaw: 4.0904789
+      Yaw: 4.16047955
     Saved: ~
 Window Geometry:
   Displays:
diff --git a/yaml/IRI/params.yaml b/yaml/IRI/params.yaml
index e306259f5f423ae23daa79e0d3e34fba60c30c63..d17f8b2211ca80c253d16269ffa1f45bad97c7bb 100644
--- a/yaml/IRI/params.yaml
+++ b/yaml/IRI/params.yaml
@@ -2,17 +2,27 @@ config:
   debug: 
     profiling: true
     profiling_file: "~/profiling_IRI.txt"
-    print_problem: false
-    print_period: 1
+    print_problem: true
+    print_period: 10
     
   problem:
     frame_structure: "POV"
     dimension: 3
     tree_manager:
-      follow: "../tree_manager/sliding_window_20_0.yaml" 
+       follow: "../tree_manager/sliding_window_20_0.yaml" 
     prior:
       #follow: "../prior/POV_factor.yaml"
-      follow: "../prior/POV_fix.yaml"
+      #follow: "../prior/POV_fix.yaml"
+      mode: "factor"
+      time_tolerance: 0.1
+      $state:
+        P: [0,0,0]
+        O: [0,0,0,1]
+        V: [0,0,0]
+      $sigma:
+        P: [0.31, 0.31, 0.31]
+        O: [1, 1, 1]
+        V: [0.31, 0.31, 0.31]
       
   solver:
     max_num_iterations: 20
@@ -41,7 +51,8 @@ config:
       name: "gnss"
       plugin: "gnss"
       extrinsic:
-         pose: [1.36, -0.04, 0.280] # BNO055 in rosbag
+         pose: [0.0, 0.0, 0.28] # M600
+         #pose: [1.36, -0.04, 0.280] # BNO055 in rosbag
       follow: "../sensor_f9t.yaml"
 
   processors:
@@ -79,7 +90,7 @@ config:
       follow: "subscriber_imu.yaml"
     -
       type: "SubscriberCompass"
-      topic: "/bno055_imu/magnetometer"
+      topic: "/bno055_imu/magnetometer2"
       sensor_name: "compass"
       package: "wolf_ros_imu"
       follow: "subscriber_imu.yaml"
@@ -90,13 +101,13 @@ config:
       package: "wolf_ros_gnss"
       marker_color: [0,0,1,1]
       period: 0.1
-    -
-      type: "SubscriberGnssFixNovatelPublisherEcef"
-      topic: "/novatel/oem7/bestpos" 
-      sensor_name: "gnss"
-      package: "wolf_ros_gnss"
-      marker_color: [0,1,0,1]
-      period: 0.1
+    #-
+    #  type: "SubscriberGnssFixNovatelPublisherEcef"
+    #  topic: "/novatel/oem7/bestpos" 
+    #  sensor_name: "gnss"
+    #  package: "wolf_ros_gnss"
+    #  marker_color: [0,1,0,1]
+    #  period: 0.1
       
   ROS publisher:
     -
@@ -133,6 +144,15 @@ config:
       package: "wolf_ros_gnss"
       period: 0.01
       sensor_gnss_name: "gnss"
+    -
+      type: "PublisherTf"
+      topic: " "
+      package: "wolf_ros_node"
+      period: 0.2
+      map_frame_id: "map"
+      odom_frame_id: "odom"
+      base_frame_id: "base"
+      publish_odom_tf: false
     -
       type: "PublisherGraph"
       topic: "graph"
diff --git a/yaml/IRI/processor_gnss.yaml b/yaml/IRI/processor_gnss.yaml
index b786171df41eb638bbf9de55084bdd7913eecd76..4504ae238bd7af7aac69e539a02db5e1252786ec 100644
--- a/yaml/IRI/processor_gnss.yaml
+++ b/yaml/IRI/processor_gnss.yaml
@@ -10,7 +10,7 @@ fix: false
 enu_map_fix_dist: 5
 keyframe_vote:
   voting_active: true
-  max_time_span: 0.01
+  max_time_span: 1#0.01
   min_features_for_keyframe: 0 #4
 gnss:
   sateph: 6    # satellite ephemeris/clock: EPHOPT_BRDC(0):broadcast ephemeris, EPHOPT_PREC(1): precise ephemeris, EPHOPT_SBAS(2): broadcast + SBAS, EPHOPT_SSRAPC(3): broadcast + SSR_APC, EPHOPT_SSRCOM(4): broadcast + SSR_COM, EPHOPT_LEX(5): QZSS LEX ephemeris, EPHOPT_SBAS2(6):broadcast + SBAS(sats with SBAS corr and sats with BRDC eph), EPHOPT_SBAS3(7):broadcast + SBAS(EPHOPT_SBAS if possible, otherwise EPHOPT_SBAS2), EPHOPT_SBAS4(8):broadcast + SBAS(EPHOPT_SBAS if possible, otherwise EPHOPT_BRDC)
@@ -40,8 +40,8 @@ gnss:
     sigma_carrier: 0.1   # m
     multi_freq: false
     remove_outliers: false
-    all_against_all: false
-    batch: true
+    all_against_all: true
+    batch: false
     #only if batch:
     min_common_sats: 6
     raim_n: 2
diff --git a/yaml/IRI/sensor_bno_compass.yaml b/yaml/IRI/sensor_bno_compass.yaml
index 5fa032c67166036ce0f81a0955db519284965f5e..45472f4be9dd8d8db3dde18ffca678a0d4cc69b3 100644
--- a/yaml/IRI/sensor_bno_compass.yaml
+++ b/yaml/IRI/sensor_bno_compass.yaml
@@ -7,6 +7,6 @@ stdev_noise: 0.3
 follow: "../magnetic_field.yaml"
 
 # calibration
-bias_prior_mode: "factor"
+bias_prior_mode: "none"
 bias_prior_state: [0, 0, 0]
 bias_prior_sigma: [0.3, 0.3, 0.3]
\ No newline at end of file
diff --git a/yaml/IRI/subscriber_imu.yaml b/yaml/IRI/subscriber_imu.yaml
index 78af3a039abb4d088ec63157b91eb5e28d18641b..96e2aabbb84a4c8edb2c81449124f067cea653d4 100644
--- a/yaml/IRI/subscriber_imu.yaml
+++ b/yaml/IRI/subscriber_imu.yaml
@@ -2,8 +2,8 @@ enableable: true
 topic_enable: "gnss_available"
 
 imu_x_axis: 1
-imu_y_axis: -2
-imu_z_axis: -3
+imu_y_axis: 2
+imu_z_axis: 3
 
 cov_source: "msg"
 
diff --git a/yaml/M600a/config_f9t.yaml b/yaml/M600a/config_f9t.yaml
index 25973e7a975afb7ff193d8a0759f4c0f5c632cb3..c5c2f4078f1c4ba62f670b238adcdba733414717 100644
--- a/yaml/M600a/config_f9t.yaml
+++ b/yaml/M600a/config_f9t.yaml
@@ -13,7 +13,7 @@ debug: 1                    # Range 0-4 (0 means no debug statements will print)
 raw_data_stream:
   publish: true
   dir: /home/nucgauss1/ublox_logs
-  file_prefix: f9t_
+  file_prefix: f9t_M600a_
 
 
 device: /dev/ublox_gps
diff --git a/yaml/M600b/config_f9t.yaml b/yaml/M600b/config_f9t.yaml
index 7ff7cb95a3198a61ee03dbebe0d5f6e76893e9b0..bf15ccf1755c43f20e90edba4ee0b603f669dcf3 100644
--- a/yaml/M600b/config_f9t.yaml
+++ b/yaml/M600b/config_f9t.yaml
@@ -13,7 +13,7 @@ debug: 1                    # Range 0-4 (0 means no debug statements will print)
 raw_data_stream:
   publish: true
   dir: /home/nucgauss1/ublox_logs
-  file_prefix: f9t_
+  file_prefix: f9t_M600b_
 
 
 device: /dev/ublox_gps
diff --git a/yaml/atlantic/config_f9t.yaml b/yaml/atlantic/config_f9t.yaml
index 5516d6306daca335181b25f2ceef4bafe3f47b59..0ec5cc07c66fa995b959213a82b4ae51c7afee3e 100644
--- a/yaml/atlantic/config_f9t.yaml
+++ b/yaml/atlantic/config_f9t.yaml
@@ -13,7 +13,7 @@ debug: 1                    # Range 0-4 (0 means no debug statements will print)
 raw_data_stream:
   publish: true
   dir: /home/nucgauss1/ublox_logs
-  file_prefix: f9t_
+  file_prefix: f9t_atlantic_
 
 
 device: /dev/ublox_gps
diff --git a/yaml/magnetic_field.yaml b/yaml/magnetic_field.yaml
index a1f82d85235fc6fe8646fcf5affd21ff50d0a1d8..ba800ca5d0a921cc5af564e51bea06979c33c121 100644
--- a/yaml/magnetic_field.yaml
+++ b/yaml/magnetic_field.yaml
@@ -2,7 +2,9 @@
 # N: 26,943.4 nT   E: 43.1 nT   D: 34,827.0 nT
 # E: 0.0431 uT     N: 26.9 uT   U: -34.8 uT
 field_prior_mode: "fix"
-#field_prior_state: [0.0431, 26.9, -34.8]
+field_prior_state: [0.0431, 26.9, -34.8]
+#field_prior_sigma: [10, 10, 10]
+
 # computed from measurements: 
-field_prior_state: [-17.2, 71.8, 4.5]
+#field_prior_state: [-17.2, 71.8, 4.5]
 #field_prior_sigma: [10, 10, 10]
\ No newline at end of file
diff --git a/yaml/scrab/config_f9t.yaml b/yaml/scrab/config_f9t.yaml
index 7ff7cb95a3198a61ee03dbebe0d5f6e76893e9b0..bd21ca19b182a4a332e121f8e899b93aa0e32848 100644
--- a/yaml/scrab/config_f9t.yaml
+++ b/yaml/scrab/config_f9t.yaml
@@ -13,7 +13,7 @@ debug: 1                    # Range 0-4 (0 means no debug statements will print)
 raw_data_stream:
   publish: true
   dir: /home/nucgauss1/ublox_logs
-  file_prefix: f9t_
+  file_prefix: f9t_scrab_
 
 
 device: /dev/ublox_gps
diff --git a/yaml/tucan/config_f9t.yaml b/yaml/tucan/config_f9t.yaml
index 9de448600ba29b37688646e38ea23baf61834782..7a015ff502d3b2dbd6323b82023f40a49cca3c28 100644
--- a/yaml/tucan/config_f9t.yaml
+++ b/yaml/tucan/config_f9t.yaml
@@ -13,7 +13,7 @@ debug: 1                    # Range 0-4 (0 means no debug statements will print)
 raw_data_stream:
   publish: true
   dir: /home/gauss/ublox_logs
-  file_prefix: f9t_
+  file_prefix: f9t_tucan_
 
 
 device: /dev/ublox_gps