From 427c0dff36fe1d5f19b508699f01ea151546d73d Mon Sep 17 00:00:00 2001 From: Ethan <jiaao@student.unimelb.edu.au> Date: Wed, 14 Aug 2024 14:06:46 +0800 Subject: [PATCH] amcl change --- catkin_ws/src/asclinic_pkg/launch/amcl.launch | 4 +++- catkin_ws/src/asclinic_pkg/launch/forklift2.launch | 7 ++----- catkin_ws/src/asclinic_pkg/param/amcl_params.yaml | 2 +- catkin_ws/src/asclinic_pkg/src/forklift/control_node.cpp | 2 +- 4 files changed, 7 insertions(+), 8 deletions(-) diff --git a/catkin_ws/src/asclinic_pkg/launch/amcl.launch b/catkin_ws/src/asclinic_pkg/launch/amcl.launch index 0ac731ec..90dd84ed 100644 --- a/catkin_ws/src/asclinic_pkg/launch/amcl.launch +++ b/catkin_ws/src/asclinic_pkg/launch/amcl.launch @@ -8,13 +8,15 @@ <!-- 静态 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" /> + <node pkg="tf2_ros" type="static_transform_publisher" name="map_odom_broadcaster" + args="0 0 0 0 0 0 map odom"/> <!-- 启动 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" /> + <remap from="scan" to="/asc/scan"/> <rosparam file="$(find asclinic_pkg)/param/amcl_params.yaml" command="load" /> </node> diff --git a/catkin_ws/src/asclinic_pkg/launch/forklift2.launch b/catkin_ws/src/asclinic_pkg/launch/forklift2.launch index 489693bf..0466f2fa 100644 --- a/catkin_ws/src/asclinic_pkg/launch/forklift2.launch +++ b/catkin_ws/src/asclinic_pkg/launch/forklift2.launch @@ -7,11 +7,7 @@ /> <!-- Launch the I2C for Motors node --> - <node - pkg="asclinic_pkg" - type="odometry_new" - name="odometry_new" - /> + <!-- Launch the control node --> <node @@ -35,4 +31,5 @@ <param name="angle_compensate" type="bool" value="true"/> </node> </group> + </launch> diff --git a/catkin_ws/src/asclinic_pkg/param/amcl_params.yaml b/catkin_ws/src/asclinic_pkg/param/amcl_params.yaml index 97356469..852c6334 100644 --- a/catkin_ws/src/asclinic_pkg/param/amcl_params.yaml +++ b/catkin_ws/src/asclinic_pkg/param/amcl_params.yaml @@ -6,7 +6,7 @@ max_particles: 2000 kld_err: 0.05 kld_z: 0.99 update_min_d: 0.2 -update_min_a: 0.2 +update_min_a: 0.1 resample_interval: 1 transform_tolerance: 0.5 diff --git a/catkin_ws/src/asclinic_pkg/src/forklift/control_node.cpp b/catkin_ws/src/asclinic_pkg/src/forklift/control_node.cpp index f917c59e..f92b691d 100644 --- a/catkin_ws/src/asclinic_pkg/src/forklift/control_node.cpp +++ b/catkin_ws/src/asclinic_pkg/src/forklift/control_node.cpp @@ -84,7 +84,7 @@ void pending(){ void pureRotation(float flag) { - float rotating_pwm = 10; + float rotating_pwm = 15; float right; float left; if (flag > 0) { -- GitLab