Quellcode durchsuchen

配置dwa local planner算法参数可以控制小车自动导航时顺利倒车移动

corvin rasp melodic vor 2 Jahren
Ursprung
Commit
018a046dbf

+ 2 - 8
src/robot_navigation/README.md

@@ -30,17 +30,11 @@ $ roslaunch robot_navigation view_navigation.launch
 最后保存地图
 
 ```sh
-$ rosrun map_server map_saver -f  ~/ros_minibot_ws/src/robot_navigation/maps/mymap
+$ rosrun map_server map_saver -f  ~/panda_ws/src/robot_navigation/maps/mymap
 ```
 
 ### 导航运行方法
-首先启动小车
-
-```sh
-$ roslaunch robot_bringup robot_bringup.launch
-```
-
-运行amcl导航
+首先启动小车,运行amcl导航
 
 ```sh
 $ roslaunch robot_navigation amcl_ydlidar_X2L.launch

+ 21 - 15
src/robot_navigation/config/dwa_local_planner_params.yaml

@@ -1,40 +1,46 @@
-# Description:DWA局部规划器配置参数
+# Description:DWA局部规划器配置参数,经过实际测试得到小车最小的x轴移动速度
+#   是0.05m/s,当小于该值小车可能无法响应移动命令.最小的旋转速度是0.4rad/s,
+#   当小于该值小车将无法响应小车的旋转命令.
+#   vy_samples:在y方向速度空间采样点数,对于差速驱动的小车y方向速度永远只有一个0.0m/s,
+#     所以该值最小要设置为1,不能设置为0;
 # Author: corvin
 # History:
 #   20200413:init this file.
+#   20220902:优化导航参数,使dwa算法运行更稳定;
 #
 
 base_local_planner: "dwa_local_planner/DWAPlannerROS"
 
 DWAPlannerROS:
 # Robot configuration params
-  acc_lim_x: 0.3
+  acc_lim_x: 0.5
   acc_lim_y: 0
-  acc_lim_th: 0.5
+  acc_lim_th: 1.5
 
-  max_vel_trans: 0.4
-  min_vel_trans: 0.25
+  max_vel_trans: 0.8
+  min_vel_trans: 0.1
+  trans_stopped_vel: 0.1
 
-  max_vel_x: 0.4
-  min_vel_x: 0.3
+  max_vel_x: 0.8
+  min_vel_x: -0.8
 
   max_vel_y: 0
   min_vel_y: 0
 
-  max_vel_theta: 0.8
-  min_vel_theta: 0.5
+  max_vel_theta: 2.0
+  min_vel_theta: 0.4
+  theta_stopped_vel: 0.4
 
 # Goal Tolerance Parametes
-  xy_goal_tolerance: 0.30
+  xy_goal_tolerance: 0.25
   yaw_goal_tolerance: 0.3
   latch_xy_goal_tolerance: false
 
 # Forward Simulation Parametesrs
   sim_time: 1
-  vx_samples: 30
-  vy_samples: 0
-  vth_samples: 40
-  controller_frequency: 8
+  vx_samples: 5
+  vy_samples: 1
+  vth_samples: 20
 
 # Trajectory Scoring Parameters
   path_distance_bias: 32.0
@@ -42,7 +48,7 @@ DWAPlannerROS:
   occdist_scale: 0.02
   forward_point_distance: 0.325
   stop_time_buffer: 0.2
-  scaling_speed: 0.3
+  scaling_speed: 0.25
   max_scaling_factor: 0.2
 
 # Oscillation Prevention Parameters

+ 4 - 1
src/robot_navigation/launch/amcl_ydlidar_X2L.launch → src/robot_navigation/launch/amcl_dwa.launch

@@ -64,4 +64,7 @@
     <param name="recovery_alpha_slow" value="0.001"/>
     <param name="recovery_alpha_fast" value="0.1"/>
   </node>
-</launch>
+
+  <!-- startup view_navigation.launch -->
+  <include file="$(find robot_navigation)/launch/view_navigation.launch" />
+</launch>

+ 11 - 3
src/robot_navigation/launch/gmapping_ydlidar_X2L.launch → src/robot_navigation/launch/gmapping.launch

@@ -9,14 +9,19 @@
   Author: corvin
   History:
     20200325:init this file.
+    20220902:增加启动gmapping建图前先把robot_bringup.launch加载启动,
+      然后加载gmapping算法开始建地图,最后加载view_navigation.launch查看建图过程;
 -->
 <launch>
   <param name="use_sim_time" value="false"/>
 
+  <!-- startup robot_bringup.launch -->
+  <include file="$(find robot_bringup)/launch/robot_bringup.launch"/>
+
   <!-- startup EAI X2L lidar node -->
-  <include file="$(find robot_navigation)/launch/ydlidar_X2L.launch" />
+  <include file="$(find robot_navigation)/launch/ydlidar_X2L.launch"/>
 
-  <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">  
+  <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
     <param name="odom_frame"   value="odom_combined"/>
 
     <param name="map_update_interval" value="4.0"/>
@@ -53,4 +58,7 @@
     <param name="lasamplerange" value="0.005"/>
     <param name="lasamplestep"  value="0.005"/>
   </node>
-</launch>
+
+  <!-- startup view_navigation.launch -->
+  <include file="$(find robot_navigation)/launch/view_navigation.launch"/>
+</launch>

+ 7 - 7
src/robot_navigation/launch/move_base.launch

@@ -13,15 +13,15 @@
 -->
 <launch>
   <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" clear_params="true">
-    <param name="controller_frequency" value="10" />
-    <param name="controller_patiente"  value="4.0" />
+    <param name="controller_frequency" value="7"/>
+    <param name="controller_patiente"  value="3.0"/>
 
-    <param name="planner_patience"  value="5.0" />
-    <param name="planner_frequency" value="0.0" />
-    <param name="conservative_reset_dist" value="3.0" />
+    <param name="planner_patience"  value="5.0"/>
+    <param name="planner_frequency" value="0.0"/>
+    <param name="conservative_reset_dist" value="3.0"/>
 
-    <param name="recovery_behavior_enabled" value="true" />
-    <param name="clearing_rotation_allowed" value="true" />
+    <param name="recovery_behavior_enabled" value="true"/>
+    <param name="clearing_rotation_allowed" value="true"/>
 
     <param name="shutdown_costmaps"    value="false"/>
     <param name="oscillation_timeout"  value="10.0"/>

Datei-Diff unterdrückt, da er zu groß ist
+ 1 - 1
src/robot_navigation/maps/test_map.pgm


+ 1 - 1
src/robot_navigation/maps/test_map.yaml

@@ -1,6 +1,6 @@
 image: test_map.pgm
 resolution: 0.050000
-origin: [-16.200000, -5.000000, 0.000000]
+origin: [-5.000000, -5.000000, 0.000000]
 negate: 0
 occupied_thresh: 0.65
 free_thresh: 0.196

+ 1 - 1
update_code.sh

@@ -69,4 +69,4 @@ echo -e "\n"
 echo -e "${green} rqt_image_view${normal}"
 echo -e "\n"
 
-exit 0
+exit 0

Einige Dateien werden nicht angezeigt, da zu viele Dateien in diesem Diff geändert wurden.