Browse Source

更新建地图和自动导航的配置参数,将地图分辨率从0.02更新为0.05

corvin rasp melodic 2 years ago
parent
commit
0739b44517

+ 0 - 67
src/robot_navigation/config/base_local_planner_params.yaml

@@ -1,67 +0,0 @@
-# Copyright(c): 2016-2020 ROS小课堂 www.corvin.cn
-# Author: corvin
-# Description:
-#  本地规划配置文件,各参数意义如下:
-#   max_vel_x:最大前进速度.
-#   min_vel_x:最小前进速度.
-#   max_vel_y:最大横向移动速度.
-#   min_vel_y:最小横向移动速度.
-#   max_vel_theta:最大旋转角速度.
-#   min_in_place_vel_theta:机器人最小原地旋转速度.
-#   escape_vel: 机器人后退速度,该值必须是负数. 
-# History:
-#   20180410: init this file.
-#   20180411: update param based on kinds.
-#
-
-recovery_behavior_enabled: true
-clearing_rotation_allowed: false
-
-TrajectoryPlannerROS:
-   #Robot Configuration Parameters
-   max_vel_x: 0.15
-   min_vel_x: 0.10
-   y_vels: [-0.17,-0.1,0.1,0.17]
-   max_vel_theta: 0.5
-   min_vel_theta: -0.5
-   min_in_place_vel_theta: 0.3
-   escape_vel: -0.10
-
-   acc_lim_x: 0.05
-   acc_lim_y: 0.05   # accelerator speed 
-   acc_lim_theta: 0.1
-
-   holonomic_robot: true
-
-   #Goal Tolerance Parameters
-   xy_goal_tolerance: 0.30  # 30cm
-   yaw_goal_tolerance: 0.3  # about 17 degrees
-   latch_xy_goal_tolerance: true
-
-   #Forward Simulation Parameters
-   sim_time: 2.0
-   sim_granularity: 0.025
-   angular_sim_granularity: 0.025
-   vx_samples: 5
-   vy_samples: 3 # omniwheel robot
-   vtheta_samples: 12 
-   
-   #Trajectory Scoring Parameters
-   meter_scoring: true
-   pdist_scale: 0.8
-   gdist_scale: 0.5
-   occdist_scale: 0.1
-
-   heading_lookahead: 0.325
-   heading_scoring: false
-   heading_scoring_timestep: 0.8
-   dwa: true
-   publish_cost_grid_pc: false
-
-   #Oscillation Prevention Parameters
-   oscillation_timeout: 3.0
-   oscillation_reset_dist: 0.5
-
-   #Global Plan Parameters
-   prune_plan: true
-

+ 1 - 2
src/robot_navigation/config/costmap_common_params.yaml

@@ -1,4 +1,4 @@
-# Copyright(c):2016-2020 ROS小课堂 www.corvin.cn
+# Copyright(c):2016-2022 ROS小课堂 www.corvin.cn
 # Description:
 # 代价地图通用配置文件,各参数意义如下:
 #   obstacle_range: 最大障碍物检测范围,超过该范围不认为是障碍物
@@ -18,7 +18,6 @@
 #   20200413:更新参数并更新注释信息.
 #
 
-
 #单独圆形机器人的参数
 #robot_radius: 0.13
 

+ 1 - 1
src/robot_navigation/config/dwa_local_planner_params.yaml

@@ -1,4 +1,4 @@
-# Copyright: 2016-2020 www.corvin.cn ROS小课堂
+# Copyright: 2016-2022 www.corvin.cn ROS小课堂
 # Description:DWA局部规划器配置参数
 # Author: corvin
 # History:

+ 3 - 3
src/robot_navigation/config/global_costmap_params.yaml

@@ -1,4 +1,4 @@
-# Copyright(C): 2016-2020 www.corvin.cn ROS小课堂
+# Copyright(C): 2016-2022 www.corvin.cn ROS小课堂
 # Description:
 #   全局代价地图配置文件,各参数意义如下:
 #   global_frame: 全局代价地图参考系
@@ -10,7 +10,7 @@
 #   transform_tolerance: 指定在tf树中frame直接的转换最大延时,单位秒
 # Author: corvin
 # History:
-#   20180410: init this file.
+#   20180410:init this file.
 #   20200927:增加plugins参数,配置静态层和膨胀层.
 global_costmap:
    global_frame: map
@@ -20,7 +20,7 @@ global_costmap:
    publish_frequency: 1.0
    static_map: true
    rolling_window: false
-   transform_tolerance: 2.0
+   transform_tolerance: 5.0
 
    plugins:
    - {name: static_layer,     type: "costmap_2d::StaticLayer"}

+ 2 - 2
src/robot_navigation/config/local_costmap_params.yaml

@@ -1,4 +1,4 @@
-#Copyright(c):2016-2020 www.corvin.cn ROS小课堂
+#Copyright(c):2016-2022 www.corvin.cn ROS小课堂
 #Description:
 #  本地代价地图配置文件,各参数意义如下:
 #  global_frame:指定本地代价地图参考系
@@ -26,7 +26,7 @@ local_costmap:
     rolling_window: true
     width: 2.0
     height: 2.0
-    resolution: 0.02   #should same as map.yaml file
+    resolution: 0.05   #should same as map.yaml file
     transform_tolerance: 2.0
 
     plugins:

+ 4 - 4
src/robot_navigation/launch/amcl_ydlidar_X2L.launch

@@ -1,5 +1,5 @@
 <!--
-  Copyright: 2016-2020 www.corvin.cn ROS小课堂
+  Copyright: 2016-2022 www.corvin.cn ROS小课堂
   Description:使用EAI的X2L雷达进行amcl定位,加载地图进行路径规划,自动导航
   Author: corvin
   History:
@@ -26,10 +26,10 @@
 
     <param name="use_map_topic" value="false"/>
     <param name="transform_tolerance" value="0.1" />
-    <param name="gui_publish_rate" value="10.0"/>
+    <param name="gui_publish_rate" value="5.0"/>
     <param name="laser_max_beams" value="300"/>
-    <param name="min_particles" value="500"/>
-    <param name="max_particles" value="5000"/>
+    <param name="min_particles" value="250"/>
+    <param name="max_particles" value="2500"/>
     <param name="kld_err" value="0.1"/>
     <param name="kld_z" value="0.99"/>
     <param name="odom_alpha1" value="0.2"/>

+ 3 - 6
src/robot_navigation/launch/gmapping_ydlidar_X2L.launch

@@ -1,10 +1,10 @@
 <!--
-  Copyright: 2016-2020 www.corvin.cn ROS小课堂
+  Copyright: 2016-2022 www.corvin.cn ROS小课堂
   Description:使用EAI的X2L雷达进行gamapping建图,整个过程如下:
     首先启动x2l雷达,然后启动move_base节点,最后启动gmapping节点.
     所有节点启动成功后,即可开始gmapping建图,在rviz中可以查看整个
     建图过程.下面来解释一下gmapping操作的重点参数:
-    1):delta:调节生成地图的分辨率,单位米.
+    1):delta:调节生成地图的分辨率,每个像素点代表的实际距离,单位米.
   Author: corvin
   History:
     20200325:init this file.
@@ -15,9 +15,6 @@
   <!-- startup EAI X2L lidar node -->
   <include file="$(find robot_navigation)/launch/ydlidar_X2L.launch" />
 
-  <!-- startup move_base node --><!-- 建图不需要启动move_base -->
-  <!-- <include file="$(find robot_navigation)/launch/move_base.launch" /> -->
-
   <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">  
     <param name="odom_frame" value="odom_combined" />
 
@@ -48,7 +45,7 @@
     <param name="ymin" value="-5.0"/>
     <param name="xmax" value="5.0"/>
     <param name="ymax" value="5.0"/>
-    <param name="delta" value="0.02"/> <!--resolution of the map --><!--大环境建图范围为0.05-0.1 -->
+    <param name="delta" value="0.05"/> <!--resolution of the map --><!--大环境建图范围为0.05-0.1 -->
 
     <param name="llsamplerange" value="0.01"/>
     <param name="llsamplestep"  value="0.01"/>

File diff suppressed because it is too large
+ 2 - 2
src/robot_navigation/maps/mymap.pgm


+ 2 - 2
src/robot_navigation/maps/mymap.yaml

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

Some files were not shown because too many files changed in this diff