diff --git a/README.md b/README.md
index fe1552068..a01a0f938 100644
--- a/README.md
+++ b/README.md
@@ -115,7 +115,7 @@ Launch arguments are largely common to both simulation and physical robot. Howev
| ✅ | ✅ | `wheel_type` | Specify the wheel type. If the selected wheel type is not 'custom', the wheel_config_path and controller_config_path arguments will be automatically adjusted and can be omitted.
***string:*** `WH01` (for Panther), `WH05` (for Lynx) (choices: `WH01`, `WH02`, `WH04`, `WH05`, `custom`) |
| ❌ | ✅ | `x` | Initial robot position in the global 'x' axis.
***float:*** `0.0` |
| ❌ | ✅ | `y` | Initial robot position in the global 'y' axis.
***float:***` -2.0` |
-| ❌ | ✅ | `z` | Initial robot position in the global 'z' axis.
***float:*** `0.0` |
+| ❌ | ✅ | `z` | Initial robot position in the global 'z' axis.
***float:*** `0.2` |
| ❌ | ✅ | `roll` | Initial robot 'roll' orientation.
***float:*** `0.0` |
| ❌ | ✅ | `pitch` | Initial robot 'pitch' orientation.
***float:*** `0.0` |
| ❌ | ✅ | `yaw` | Initial robot 'yaw' orientation.
***float:*** `0.0` |
diff --git a/husarion_ugv_controller/config/WH01_controller.yaml b/husarion_ugv_controller/config/WH01_controller.yaml
index 66d3455f8..da21d73ec 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_footprint
+ base_frame_id: base_link
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 9f8380daa..0e6e8ee5f 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_footprint
+ base_frame_id: base_link
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 a31abf446..2ae5cb34f 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_footprint
+ base_frame_id: base_link
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 ac146f01c..e9cfd5985 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_footprint
+ base_frame_id: base_link
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/launch/rviz.launch.py b/husarion_ugv_description/launch/rviz.launch.py
index 054802d30..5dc2a34ab 100644
--- a/husarion_ugv_description/launch/rviz.launch.py
+++ b/husarion_ugv_description/launch/rviz.launch.py
@@ -58,7 +58,7 @@ def generate_launch_description():
rviz_config = ReplaceString(
source_file=rviz_config,
- replacements={"/": ns_ext, "": namespace},
+ replacements={"/": ns_ext, "": namespace},
)
rviz_node = Node(
diff --git a/husarion_ugv_description/rviz/husarion_ugv.rviz b/husarion_ugv_description/rviz/husarion_ugv.rviz
index 8285a0474..8d6a56c49 100644
--- a/husarion_ugv_description/rviz/husarion_ugv.rviz
+++ b/husarion_ugv_description/rviz/husarion_ugv.rviz
@@ -45,7 +45,7 @@ Visualization Manager:
Z: 0
Plane: XY
Plane Cell Count: 10
- Reference Frame:
+ Reference Frame: /base_footprint
Value: true
Enabled: true
Name: Map
@@ -73,7 +73,7 @@ Visualization Manager:
Inertia: false
Mass: false
Name: RobotModel
- TF Prefix:
+ TF Prefix:
Update Interval: 0
Value: true
Visual Enabled: true
@@ -135,7 +135,7 @@ Visualization Manager:
Enabled: true
Global Options:
Background Color: 48; 48; 48
- Fixed Frame: /odom
+ Fixed Frame: /odom
Frame Rate: 30
Name: root
Tools:
diff --git a/husarion_ugv_description/urdf/lynx/body.urdf.xacro b/husarion_ugv_description/urdf/lynx/base.urdf.xacro
similarity index 97%
rename from husarion_ugv_description/urdf/lynx/body.urdf.xacro
rename to husarion_ugv_description/urdf/lynx/base.urdf.xacro
index 295748c2a..f18041428 100644
--- a/husarion_ugv_description/urdf/lynx/body.urdf.xacro
+++ b/husarion_ugv_description/urdf/lynx/base.urdf.xacro
@@ -13,11 +13,11 @@
-
+
-
+
diff --git a/husarion_ugv_description/urdf/lynx/lynx_macro.urdf.xacro b/husarion_ugv_description/urdf/lynx/lynx_macro.urdf.xacro
index 5cc44a5da..6bedaf63d 100644
--- a/husarion_ugv_description/urdf/lynx/lynx_macro.urdf.xacro
+++ b/husarion_ugv_description/urdf/lynx/lynx_macro.urdf.xacro
@@ -17,7 +17,7 @@
-
+
diff --git a/husarion_ugv_description/urdf/panther/body.urdf.xacro b/husarion_ugv_description/urdf/panther/base.urdf.xacro
similarity index 100%
rename from husarion_ugv_description/urdf/panther/body.urdf.xacro
rename to husarion_ugv_description/urdf/panther/base.urdf.xacro
diff --git a/husarion_ugv_description/urdf/panther/panther_macro.urdf.xacro b/husarion_ugv_description/urdf/panther/panther_macro.urdf.xacro
index 33d8f8578..135c2bc85 100644
--- a/husarion_ugv_description/urdf/panther/panther_macro.urdf.xacro
+++ b/husarion_ugv_description/urdf/panther/panther_macro.urdf.xacro
@@ -22,7 +22,7 @@
-
+
diff --git a/husarion_ugv_gazebo/launch/spawn_robot.launch.py b/husarion_ugv_gazebo/launch/spawn_robot.launch.py
index 875a2806f..d68ce0091 100644
--- a/husarion_ugv_gazebo/launch/spawn_robot.launch.py
+++ b/husarion_ugv_gazebo/launch/spawn_robot.launch.py
@@ -57,7 +57,7 @@ def generate_launch_description():
z = LaunchConfiguration("z")
declare_z_arg = DeclareLaunchArgument(
- "z", default_value="0.0", description="Initial robot position in the global 'z' axis."
+ "z", default_value="0.2", description="Initial robot position in the global 'z' axis."
)
roll = LaunchConfiguration("roll")
diff --git a/husarion_ugv_localization/config/enu_localization.yaml b/husarion_ugv_localization/config/enu_localization.yaml
index 9cd7071e8..6b2668cc7 100644
--- a/husarion_ugv_localization/config/enu_localization.yaml
+++ b/husarion_ugv_localization/config/enu_localization.yaml
@@ -10,7 +10,7 @@
map_frame: map
odom_frame: odom
- base_link_frame: base_footprint
+ base_link_frame: base_link
world_frame: odom
publish_tf: true
publish_acceleration: false
diff --git a/husarion_ugv_localization/config/enu_localization_with_gps.yaml b/husarion_ugv_localization/config/enu_localization_with_gps.yaml
index e9e31763b..ef1fa6ff6 100644
--- a/husarion_ugv_localization/config/enu_localization_with_gps.yaml
+++ b/husarion_ugv_localization/config/enu_localization_with_gps.yaml
@@ -10,7 +10,7 @@
map_frame: map
odom_frame: odom
- base_link_frame: base_footprint
+ base_link_frame: base_link
world_frame: odom
publish_tf: true
publish_acceleration: false
diff --git a/husarion_ugv_localization/config/relative_localization.yaml b/husarion_ugv_localization/config/relative_localization.yaml
index 98d4e91f8..5f420735b 100644
--- a/husarion_ugv_localization/config/relative_localization.yaml
+++ b/husarion_ugv_localization/config/relative_localization.yaml
@@ -10,7 +10,7 @@
map_frame: map
odom_frame: odom
- base_link_frame: base_footprint
+ base_link_frame: base_link
world_frame: odom
publish_tf: true
publish_acceleration: false
diff --git a/husarion_ugv_localization/config/relative_localization_with_gps.yaml b/husarion_ugv_localization/config/relative_localization_with_gps.yaml
index 444ed7fc0..fa8426758 100644
--- a/husarion_ugv_localization/config/relative_localization_with_gps.yaml
+++ b/husarion_ugv_localization/config/relative_localization_with_gps.yaml
@@ -10,7 +10,7 @@
map_frame: map
odom_frame: odom
- base_link_frame: base_footprint
+ base_link_frame: base_link
world_frame: odom
publish_tf: true
publish_acceleration: false