Browse Source

将global_costmap中的obstacle_layer的plugins删除,解决The origin for the sensor at is out of map bounds问题

corvin rasp melodic 2 years ago
parent
commit
c89cf9f7ba

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

@@ -14,6 +14,11 @@
 #   20180410:init this file.
 #   20200413:更新参数并更新注释信息.
 #   20220920:更新inflation_layer配置参数,更新带夹爪机器人的footprint参数.
+#   20220928:将obstacle_range和raytrace_range从obstacle_layer中移动
+#     到外面,这样就是全局的配置参数,不是obstacle_layer命名空间内的私有参数.
+
+obstacle_range: 1.4
+raytrace_range: 1.5
 
 #单独圆形机器人的底盘半径参数,不带前面夹爪
 #robot_radius: 0.10
@@ -27,8 +32,6 @@ footprint: [[ 0.30,  0.00],[ 0.30,  0.07],[ 0.07,  0.07],
 #障碍物图层
 obstacle_layer:
  enabled: true
- obstacle_range: 1.3
- raytrace_range: 1.4
  observation_sources: scan
  scan: {sensor_frame: lidar,
         data_type: LaserScan,

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

@@ -9,13 +9,16 @@
 # History:
 #   20180410:init this file.
 #   20200927:增加plugins参数,配置静态层和膨胀层.
+#   20220928:删除plugins中的obstacle_layer,解决导航过程中局部代价地图
+#     会消失问题,报错信息为:The origin for the sensor at(*,*)  is 
+#     out of map bounds. So, the costmap cannot raytrace for it.
 
 global_costmap:
    global_frame: map
    robot_base_frame: base_footprint
 
-   update_frequency: 1.0
-   publish_frequency: 1.0
+   update_frequency: 2.0
+   publish_frequency: 2.0
 
    rolling_window: false
    resolution: 0.05
@@ -23,6 +26,5 @@ global_costmap:
 
    plugins:
    - {name: static_layer,    type: "costmap_2d::StaticLayer"}
-   - {name: obstacle_layer,  type: "costmap_2d::ObstacleLayer"}
    - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
 

+ 3 - 5
src/robot_navigation/config/local_costmap_params.yaml

@@ -13,9 +13,7 @@
 #  20180410:init this file.
 #  20200413:更新本地代价地图配置参数.
 #  20200927:添加plugins参数,配置障碍物层和膨胀层.
-#  20220927:更新width和height为1.8,解决"The origin for the sensor
-#    at (0.05, 2.73) is out of map bounds. So, the costmap cannot
-#    raytrace for it."
+#  20220927:更新width和height为2.0,以机器人为中心,前1m后1m,左1m右1m.
 
 local_costmap:
     global_frame: odom_combined
@@ -25,8 +23,8 @@ local_costmap:
     publish_frequency: 4.0
 
     rolling_window: true
-    width: 1.8
-    height: 1.8
+    width: 2.0
+    height: 2.0
     resolution: 0.05   #should same as map.yaml file
     transform_tolerance: 2.0