diff --git a/husarion_ugv_controller/config/WH01_controller.yaml b/husarion_ugv_controller/config/WH01_controller.yaml
index 4187aa50..26738b0b 100644
--- a/husarion_ugv_controller/config/WH01_controller.yaml
+++ b/husarion_ugv_controller/config/WH01_controller.yaml
@@ -41,7 +41,7 @@
publish_rate: 100.0
odom_frame_id: odom
- base_frame_id: base_link
+ base_frame_id: base_footprint
twist_covariance_diagonal: [5.4e-5, 5.4e-5, 0.0, 0.0, 0.0, 1.9e-4] # Values measured experimentally
# Whether to use feedback or commands for odometry calculations
diff --git a/husarion_ugv_controller/config/WH02_controller.yaml b/husarion_ugv_controller/config/WH02_controller.yaml
index 6d109509..efadc514 100644
--- a/husarion_ugv_controller/config/WH02_controller.yaml
+++ b/husarion_ugv_controller/config/WH02_controller.yaml
@@ -42,7 +42,7 @@
publish_rate: 100.0
odom_frame_id: odom
- base_frame_id: base_link
+ base_frame_id: base_footprint
twist_covariance_diagonal: [5.4e-5, 5.4e-5, 0.0, 0.0, 0.0, 1.9e-4] # Selected intuitively based on WH01 results
# Whether to use feedback or commands for odometry calculations
diff --git a/husarion_ugv_controller/config/WH04_controller.yaml b/husarion_ugv_controller/config/WH04_controller.yaml
index b13bbd11..94cfe52d 100644
--- a/husarion_ugv_controller/config/WH04_controller.yaml
+++ b/husarion_ugv_controller/config/WH04_controller.yaml
@@ -42,7 +42,7 @@
publish_rate: 100.0
odom_frame_id: odom
- base_frame_id: base_link
+ base_frame_id: base_footprint
twist_covariance_diagonal: [2.7e-5, 2.7e-5, 0.0, 0.0, 0.0, 1.0e-4] # Selected intuitively based on WH01 results
# Whether to use feedback or commands for odometry calculations
diff --git a/husarion_ugv_controller/config/WH05_controller.yaml b/husarion_ugv_controller/config/WH05_controller.yaml
index 7499d0fb..5d9f891c 100644
--- a/husarion_ugv_controller/config/WH05_controller.yaml
+++ b/husarion_ugv_controller/config/WH05_controller.yaml
@@ -41,7 +41,7 @@
publish_rate: 100.0
odom_frame_id: odom
- base_frame_id: base_link
+ base_frame_id: base_footprint
twist_covariance_diagonal: [5.4e-5, 5.4e-5, 0.0, 0.0, 0.0, 1.9e-4] # Values measured experimentally
# Whether to use feedback or commands for odometry calculations
diff --git a/husarion_ugv_description/urdf/lynx/lynx_macro.urdf.xacro b/husarion_ugv_description/urdf/lynx/lynx_macro.urdf.xacro
index 4bff5bf8..c126d80c 100644
--- a/husarion_ugv_description/urdf/lynx/lynx_macro.urdf.xacro
+++ b/husarion_ugv_description/urdf/lynx/lynx_macro.urdf.xacro
@@ -11,15 +11,9 @@
imu_rpy:='0.0 0.0 -1.57'
namespace:=''">
-
-
-
-
-
-
+
-
@@ -61,7 +55,7 @@
true
-
+
husarion_ugv_hardware_interfaces/LynxSystem
1600
@@ -182,8 +176,9 @@
-
-
+
+
+
diff --git a/husarion_ugv_description/urdf/panther/body.urdf.xacro b/husarion_ugv_description/urdf/panther/body.urdf.xacro
index 4d44ebef..5a05a6be 100644
--- a/husarion_ugv_description/urdf/panther/body.urdf.xacro
+++ b/husarion_ugv_description/urdf/panther/body.urdf.xacro
@@ -30,7 +30,7 @@
-
+