Explorar o código

将dwa_local_planner的最大线速度减小,0.7->0.5减慢速度使运动更稳定,在进行gmapping时将建图的时间从每4s建一次升级为3s,加快建图速度

corvin rasp melodic %!s(int64=2) %!d(string=hai) anos
pai
achega
cf6a0745a3

+ 7 - 6
src/robot_navigation/config/dwa_local_planner_params.yaml

@@ -9,19 +9,20 @@
 #   20200413:init this file.
 #   20220902:优化导航参数,使dwa算法运行更稳定;
 #   20220920:优化dwa算法参数,使运行更稳定;
+#   20221019:更新小车移动的最快线速度为0.5m/s;
 
 base_local_planner: "dwa_local_planner/DWAPlannerROS"
 
 DWAPlannerROS:
 # Robot configuration params
-  max_vel_x: 0.7
-  min_vel_x: -0.7
+  max_vel_x: 0.5
+  min_vel_x: -0.5
 
   max_vel_y: 0
   min_vel_y: 0
 
 # The velocity when robot is moving in a straight line
-  max_vel_trans: 0.7
+  max_vel_trans: 0.5
   min_vel_trans: 0.1
   trans_stopped_vel: 0.1
 
@@ -29,7 +30,7 @@ DWAPlannerROS:
   min_vel_theta: 0.5
   theta_stopped_vel: 0.5
 
-  acc_lim_x: 0.7
+  acc_lim_x: 1.5
   acc_lim_y: 0
   acc_lim_th: 2.0
 
@@ -41,12 +42,12 @@ DWAPlannerROS:
 # Forward Simulation Parametesrs
   sim_time: 1.7
   sim_granularity: 0.025
-  vx_samples: 7
+  vx_samples: 8
   vy_samples: 0
   vth_samples: 20
 
 # Trajectory Scoring Parameters
-  path_distance_bias: 42.0
+  path_distance_bias: 44.0
   goal_distance_bias: 18.0
   occdist_scale: 0.02
   forward_point_distance: 0.2

+ 7 - 5
src/robot_navigation/launch/gmapping.launch

@@ -12,6 +12,8 @@
     20220902:增加启动gmapping建图前先把robot_bringup.launch加载启动,
       然后加载gmapping算法开始建地图,最后加载view_navigation.launch查看建图过程;
     20201005:将gmapping建图过程在依赖的odom_frame从odom_combined更新为odom;
+    20201019:更新map_update_interval参数从4->3,3秒更新一次地图,建立的地图大小
+      xmin,xmax,ymin,ymax更新为6;
 -->
 <launch>
   <param name="use_sim_time" value="false"/>
@@ -25,7 +27,7 @@
   <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
     <param name="odom_frame"   value="odom"/>
 
-    <param name="map_update_interval" value="4.0"/>
+    <param name="map_update_interval" value="3.0"/>
     <param name="maxUrange"    value="7.0"/>
     <param name="sigma"        value="0.05"/>
     <param name="kernelSize"   value="1"/>
@@ -48,10 +50,10 @@
     <param name="resampleThreshold" value="0.5"/>
     <param name="particles"      value="30"/>
 
-    <param name="xmin"  value="-5.0"/>
-    <param name="ymin"  value="-5.0"/>
-    <param name="xmax"  value="5.0"/>
-    <param name="ymax"  value="5.0"/>
+    <param name="xmin"  value="-6.0"/>
+    <param name="ymin"  value="-6.0"/>
+    <param name="xmax"  value="6.0"/>
+    <param name="ymax"  value="6.0"/>
     <param name="delta" value="0.05"/> <!--resolution of the map -->
 
     <param name="llsamplerange" value="0.01"/>