From 31291566f713ddf2f168f5722c992d0912c4c857 Mon Sep 17 00:00:00 2001
From: Ethan <jiaao@student.unimelb.edu.au>
Date: Fri, 9 Aug 2024 12:37:54 +0800
Subject: [PATCH] add amcl

---
 catkin_ws/src/asclinic_pkg/launch/amcl.launch | 23 ++++++++++
 .../src/asclinic_pkg/launch/gmapping.launch   |  2 +-
 catkin_ws/src/asclinic_pkg/maps/test.txt      |  1 +
 .../src/asclinic_pkg/param/amcl_params.yaml   | 46 +++++++++++++++++++
 4 files changed, 71 insertions(+), 1 deletion(-)
 create mode 100644 catkin_ws/src/asclinic_pkg/launch/amcl.launch
 create mode 100644 catkin_ws/src/asclinic_pkg/maps/test.txt
 create mode 100644 catkin_ws/src/asclinic_pkg/param/amcl_params.yaml

diff --git a/catkin_ws/src/asclinic_pkg/launch/amcl.launch b/catkin_ws/src/asclinic_pkg/launch/amcl.launch
new file mode 100644
index 00000000..0ac731ec
--- /dev/null
+++ b/catkin_ws/src/asclinic_pkg/launch/amcl.launch
@@ -0,0 +1,23 @@
+<launch>
+  <!-- 启动 map_server 以发布地图 -->
+  <node name="map_server" pkg="map_server" type="map_server" args="$(find asclinic_pkg)/maps/map.yaml" />
+
+  <!-- 静态 TF 变换: base_link 到 laser -->
+  <node pkg="tf2_ros" type="static_transform_publisher" name="base_to_laser" args="0 0 1 0 0 0 base_link laser" />
+
+  <!-- 静态 TF 变换: odom 到 base_link -->
+  <node pkg="tf2_ros" type="static_transform_publisher" name="odom_to_base" args="0 0 0 0 0 0 odom base_link" />
+
+  <!-- 启动 AMCL 节点 -->
+  <node name="amcl" pkg="amcl" type="amcl" output="screen">
+    <param name="use_map_topic" value="true" />
+    <param name="odom_frame_id" value="odom" />
+    <param name="base_frame_id" value="base_link" />
+    <param name="global_frame_id" value="map" />
+    <param name="scan_topic" value="/asc/scan" />
+    <rosparam file="$(find asclinic_pkg)/param/amcl_params.yaml" command="load" />
+  </node>
+
+  <!-- 启动 RViz -->
+  <node name="rviz" pkg="rviz" type="rviz" />
+</launch>
diff --git a/catkin_ws/src/asclinic_pkg/launch/gmapping.launch b/catkin_ws/src/asclinic_pkg/launch/gmapping.launch
index 574d231b..3a299f4f 100644
--- a/catkin_ws/src/asclinic_pkg/launch/gmapping.launch
+++ b/catkin_ws/src/asclinic_pkg/launch/gmapping.launch
@@ -20,7 +20,7 @@
     <param name="ymin" value="-3.0"/>
     <param name="xmax" value="3.0"/>
     <param name="ymax" value="3.0"/>
-    <param name="maxUrange" value="8.0"/>
+    <param name="maxUrange" value="3.0"/>
     <param name="maxRange" value="8.0"/>
     <remap from="scan" to="/asc/scan"/>
   </node>
diff --git a/catkin_ws/src/asclinic_pkg/maps/test.txt b/catkin_ws/src/asclinic_pkg/maps/test.txt
new file mode 100644
index 00000000..d800886d
--- /dev/null
+++ b/catkin_ws/src/asclinic_pkg/maps/test.txt
@@ -0,0 +1 @@
+123
\ No newline at end of file
diff --git a/catkin_ws/src/asclinic_pkg/param/amcl_params.yaml b/catkin_ws/src/asclinic_pkg/param/amcl_params.yaml
new file mode 100644
index 00000000..97356469
--- /dev/null
+++ b/catkin_ws/src/asclinic_pkg/param/amcl_params.yaml
@@ -0,0 +1,46 @@
+# AMCL parameters
+
+
+min_particles: 500
+max_particles: 2000
+kld_err: 0.05
+kld_z: 0.99
+update_min_d: 0.2
+update_min_a: 0.2
+resample_interval: 1
+transform_tolerance: 0.5
+
+# Motion model parameters
+recovery_alpha_slow: 0.1
+recovery_alpha_fast: 0.1
+alpha1: 0.2
+alpha2: 0.2
+alpha3: 0.2
+alpha4: 0.2
+alpha5: 0.1
+
+# Laser model parameters
+laser_min_range: 0.1
+laser_max_range: 3
+laser_max_beams: 60
+laser_z_hit: 0.95
+laser_z_short: 0.1
+laser_z_max: 0.05
+laser_z_rand: 0.05
+laser_sigma_hit: 0.2
+laser_lambda_short: 0.1
+
+# Odometry model parameters
+odom_alpha1: 0.2
+odom_alpha2: 0.2
+odom_alpha3: 0.2
+odom_alpha4: 0.2
+odom_alpha5: 0.1
+
+# Initial pose estimation
+init_pose_x: 0.0
+init_pose_y: 0.0
+init_pose_a: 0.0
+init_cov_xx: 0.5
+init_cov_yy: 0.5
+init_cov_aa: 0.1
-- 
GitLab