Browse Source

在自动导航时,添加了膨胀层,障碍物层

corvin_zhang 4 years ago
parent
commit
1267b5c60e

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

@@ -33,7 +33,6 @@ inflation_radius: 0.15
 cost_scaling_factor: 10
 
 map_type: costmap
-
 observation_sources: scan
-scan: {data_type: LaserScan, topic: scan, marking: true, clearing: true}
+scan: {sensor_frame: lidar, data_type: LaserScan, topic: scan, marking: true, clearing: true}
 

+ 8 - 2
src/robot_navigation/config/global_costmap_params.yaml

@@ -11,13 +11,19 @@
 # Author: corvin
 # History:
 #   20180410: init this file.
-#
+#   20200927:增加plugins参数,配置静态层和膨胀层.
 global_costmap:
    global_frame: map
    robot_base_frame: base_footprint
+
    update_frequency: 1.0
-   publish_frequency: 0
+   publish_frequency: 1.0
    static_map: true
    rolling_window: false
    transform_tolerance: 2.0
 
+   plugins:
+   - {name: static_layer,     type: "costmap_2d::StaticLayer"}
+   - {name: obstacle_layer,     type: "costmap_2d::ObstacleLayer"}
+   - {name: inflation_layer,  type: "costmap_2d::InflationLayer"}
+

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

@@ -15,11 +15,12 @@
 #History:
 #  20180410: init this file.
 #  20200413:更新本地代价地图配置参数.
+#  20200927:添加plugins参数,配置障碍物层和膨胀层.
 local_costmap:
     global_frame: odom_combined
     robot_base_frame: base_footprint
-    update_frequency: 1.0
-    publish_frequency: 1.0
+    update_frequency: 3.0
+    publish_frequency: 3.0
 
     static_map: false
     rolling_window: true
@@ -28,3 +29,7 @@ local_costmap:
     resolution: 0.02   #should same as map.yaml file
     transform_tolerance: 2.0
 
+    plugins:
+    - {name: obstacle_layer,   type: "costmap_2d::ObstacleLayer"}
+    - {name: inflation_layer,  type: "costmap_2d::InflationLayer"}
+

+ 3 - 2
src/robot_navigation/launch/move_base.launch

@@ -7,14 +7,15 @@
     (3)local_costmap_params.yaml
     (4)global_costmap_params.yaml
     (5)base_local_planner_params.yaml
+    controller_frequency:move_base向控制底盘移动话题cmd_vel发送控制命令的频率.
   Author: corvin
   History:
     20190728:init this file.
 -->
 <launch>
   <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" clear_params="true">
-    <param name="controller_frequency" value="1.5" />
-    <param name="controller_patiente"  value="4.0" />
+    <param name="controller_frequency" value="4.5" />
+    <param name="controller_patiente"  value="3.0" />
 
     <param name="planner_patience"  value="5.0" />
     <param name="planner_frequency" value="1.0" />

+ 2 - 1
src/robot_navigation/launch/ydlidar_X2L.launch

@@ -4,9 +4,10 @@
   Author: corvin
   History:
     20200325: init this file.
+    20200927:在启动雷达时候配置了required参数,当雷达没有正常启动,则整个导航过程停止.
 -->
 <launch>
-  <node name="ydlidar_X2L_node" pkg="ydlidar_ros" type="ydlidar_node" output="screen" respawn="false" >
+  <node name="ydlidar_X2L_node" pkg="ydlidar_ros" type="ydlidar_node" output="screen" required="true" >
     <param name="port"      type="string" value="/dev/ydlidar"/>
     <param name="baudrate"  type="int"    value="115200"/>
     <param name="frame_id"  type="string" value="lidar"/>

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


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

@@ -1,6 +1,6 @@
 image: mymap.pgm
 resolution: 0.020000
-origin: [-15.240000, -5.000000, 0.000000]
+origin: [-17.160000, -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