Forráskód Böngészése

将gmapping过程中的odom_frame从odom_combined更新为odom,在global_costmap_params.yaml中添加obstacle_layer,这样全局路径规划时才可以规划避开障碍物的路径

corvin rasp melodic 2 éve
szülő
commit
60c105aa66

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

@@ -12,6 +12,8 @@
 #   20220928:删除plugins中的obstacle_layer,解决导航过程中局部代价地图
 #     会消失问题,报错信息为:The origin for the sensor at(*,*)  is 
 #     out of map bounds. So, the costmap cannot raytrace for it.
+#   20201005:重新将obstacle_layer层配置参数加进来,否则无法在全局路径规划
+#     时规划的全局路径无法正常避开障碍物.
 
 global_costmap:
    global_frame: map
@@ -21,10 +23,9 @@ global_costmap:
    publish_frequency: 2.0
 
    rolling_window: false
-   resolution: 0.05
-   transform_tolerance: 5.0
+   transform_tolerance: 4.0
 
    plugins:
    - {name: static_layer,    type: "costmap_2d::StaticLayer"}
+   - {name: obstacle_layer,  type: "costmap_2d::ObstacleLayer"}
    - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
-

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

@@ -27,8 +27,8 @@ local_costmap:
     width: 2.0
     height: 2.0
     resolution: 0.05   #should same as map.yaml file
-    transform_tolerance: 2.0
+    transform_tolerance: 1.0
 
     plugins:
     - {name: obstacle_layer,  type: "costmap_2d::ObstacleLayer"}
-    - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
+    - {name: inflation_layer, type: "costmap_2d::InflationLayer"}

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

@@ -3,14 +3,15 @@
     首先启动x2l雷达,然后启动gmapping节点.所有节点启动成功后,即可
     开始gmapping建图,在rviz中可以查看整个建图过程.下面来解释一下
     gmapping操作的重点参数:
-    1):delta:调节生成地图的分辨率,每像素点代表实际的距离,单位米.
-    2):map_update_interval:建立地图时每隔多长时间更新一下地图,单位秒,该值越小越消耗cpu资源.
-    3):maxUrange:激光雷达使用的最大范围,超过该距离的雷达数据会舍弃不参与建图.
+    1)delta:调节生成地图的分辨率,每像素点代表实际的距离,单位米.
+    2)map_update_interval:建立地图时每隔多长时间更新一下地图,单位秒,该值越小越消耗cpu资源.
+    3)maxUrange:激光雷达使用的最大范围,超过该距离的雷达数据会舍弃不参与建图.
   Author: corvin
   History:
     20200325:init this file.
     20220902:增加启动gmapping建图前先把robot_bringup.launch加载启动,
       然后加载gmapping算法开始建地图,最后加载view_navigation.launch查看建图过程;
+    20201005:将gmapping建图过程在依赖的odom_frame从odom_combined更新为odom;
 -->
 <launch>
   <param name="use_sim_time" value="false"/>
@@ -22,7 +23,7 @@
   <include file="$(find robot_navigation)/launch/ydlidar_X2L.launch"/>
 
   <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
-    <param name="odom_frame"   value="odom_combined"/>
+    <param name="odom_frame"   value="odom"/>
 
     <param name="map_update_interval" value="4.0"/>
     <param name="maxUrange"    value="7.0"/>
@@ -61,4 +62,4 @@
 
   <!-- startup view_navigation.launch -->
   <include file="$(find robot_navigation)/launch/view_navigation.launch"/>
-</launch>
+</launch>