浏览代码

增加gmapping建立好地图后,使用save_map.sh脚本可以直接保存地图

corvin rasp melodic 2 年之前
父节点
当前提交
64f6dd5290

+ 12 - 0
save_map.sh

@@ -0,0 +1,12 @@
+#!/bin/bash
+
+green="\e[32;1m"
+normal="\e[0m"
+
+cd src/robot_navigation/maps/
+rosrun map_server map_saver -f test_map
+
+echo -e "${green}>>> 成功保存地图!${normal}"
+echo -e "\n"
+
+exit 0

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

@@ -1,9 +1,8 @@
 # Description:DWA局部规划器配置参数,经过实际测试得到小车最小的x轴移动速度
 #   是0.05m/s,当小于该值小车可能无法响应移动命令.最小的旋转速度是0.4rad/s,
 #   当小于该值小车将无法响应小车的旋转命令.
-#   vy_samples:在y方向速度空间采样点数,对于差速驱动的小车y方向速度永远只有一个0.0m/s,
-#     所以该值最小要设置为1,不能设置为0;
-#   prune_plan:定义当机器人是否边沿着路径移动时,清除掉已经走过的路径规划;
+#   vy_samples:在y方向速度空间采样点数,对于差速驱动的小车y方向速度永远只有一个0.0m/s
+#   prune_plan:跟踪的全局路径参数,定义当机器人是否边沿着路径移动时,清除掉已经走过1m的全局路径;
 # Author: corvin
 # History:
 #   20200413:init this file.
@@ -39,8 +38,9 @@ DWAPlannerROS:
 
 # Forward Simulation Parametesrs
   sim_time: 1.7
-  vx_samples: 4
-  vy_samples: 1
+  sim_granularity: 0.025
+  vx_samples: 7
+  vy_samples: 0
   vth_samples: 20
 
 # Trajectory Scoring Parameters
@@ -56,4 +56,4 @@ DWAPlannerROS:
   oscillation_reset_dist: 0.05
 
 # Global plan parameters
-  prune_plan: true
+  prune_plan: true

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

@@ -23,7 +23,7 @@
     <param name="recovery_behavior_enabled" value="true"/>
     <param name="clearing_rotation_allowed" value="true"/>
 
-    <param name="shutdown_costmaps"    value="false"/>
+    <param name="shutdown_costmaps"    value="true"/>
     <param name="oscillation_timeout"  value="10.0"/>
     <param name="oscillation_distance" value="0.2"/>
 

二进制
src/robot_navigation/maps/test_map.pgm


+ 41 - 19
src/robot_navigation/rviz/view_navigation.rviz

@@ -3,10 +3,9 @@ Panels:
     Help Height: 123
     Name: Displays
     Property Tree Widget:
-      Expanded:
-        - /Odometry1/Shape1
-      Splitter Ratio: 0.5083333253860474
-    Tree Height: 510
+      Expanded: ~
+      Splitter Ratio: 0.4713541567325592
+    Tree Height: 311
   - Class: rviz/Selection
     Name: Selection
   - Class: rviz/Tool Properties
@@ -78,7 +77,7 @@ Visualization Manager:
     - Alpha: 0.6000000238418579
       Class: rviz/Map
       Color Scheme: costmap
-      Draw Behind: false
+      Draw Behind: true
       Enabled: true
       Name: Map
       Topic: /move_base/global_costmap/costmap
@@ -189,7 +188,7 @@ Visualization Manager:
       Update Interval: 0
       Value: true
       Visual Enabled: true
-    - Alpha: 1
+    - Alpha: 0.5
       Buffer Length: 1
       Class: rviz/Path
       Color: 44; 65; 255
@@ -213,9 +212,9 @@ Visualization Manager:
       Unreliable: false
       Value: true
     - Alpha: 1
-      Buffer Length: 1
+      Buffer Length: 7
       Class: rviz/Path
-      Color: 255; 29; 218
+      Color: 85; 170; 0
       Enabled: true
       Head Diameter: 0.30000001192092896
       Head Length: 0.20000000298023224
@@ -265,10 +264,10 @@ Visualization Manager:
       Name: Odometry
       Position Tolerance: 0.05000000074505806
       Shape:
-        Alpha: 0.6000000238418579
+        Alpha: 0.699999988079071
         Axes Length: 1
         Axes Radius: 0.10000000149011612
-        Color: 199; 199; 99
+        Color: 245; 245; 122
         Head Length: 0.05000000074505806
         Head Radius: 0.05000000074505806
         Shaft Length: 0.05000000074505806
@@ -316,6 +315,29 @@ Visualization Manager:
       Topic: /particlecloud
       Unreliable: false
       Value: false
+    - Alpha: 1
+      Buffer Length: 1
+      Class: rviz/Path
+      Color: 255; 0; 0
+      Enabled: true
+      Head Diameter: 0.30000001192092896
+      Head Length: 0.20000000298023224
+      Length: 0.30000001192092896
+      Line Style: Lines
+      Line Width: 0.029999999329447746
+      Name: Path
+      Offset:
+        X: 0
+        Y: 0
+        Z: 0
+      Pose Color: 255; 85; 255
+      Pose Style: None
+      Radius: 0.029999999329447746
+      Shaft Diameter: 0.10000000149011612
+      Shaft Length: 0.10000000149011612
+      Topic: /move_base/DWAPlannerROS/global_plan
+      Unreliable: false
+      Value: true
   Enabled: true
   Global Options:
     Background Color: 45; 32; 41
@@ -343,7 +365,7 @@ Visualization Manager:
   Value: true
   Views:
     Current:
-      Angle: -0.04500005766749382
+      Angle: 0.005000150762498379
       Class: rviz/TopDownOrtho
       Enable Stereo Rendering:
         Stereo Eye Separation: 0.05999999865889549
@@ -353,19 +375,19 @@ Visualization Manager:
       Invert Z Axis: false
       Name: Current View
       Near Clip Distance: 0.009999999776482582
-      Scale: 145.46278381347656
+      Scale: 137.76795959472656
       Target Frame: <Fixed Frame>
       Value: TopDownOrtho (rviz)
-      X: 2.021449089050293
-      Y: 1.3053816556930542
+      X: 1.6592411994934082
+      Y: 1.4609137773513794
     Saved: ~
 Window Geometry:
   Displays:
     collapsed: true
-  Height: 880
+  Height: 697
   Hide Left Dock: true
   Hide Right Dock: true
-  QMainWindow State: 000000ff00000000fd00000004000000000000016a000002c1fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006500fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730000000044000002c1000000de00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000280fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000004400000280000000b900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004d400000044fc0100000002fb0000000800540069006d00650100000000000004d40000028000fffffffb0000000800540069006d00650100000000000004500000000000000000000004d4000002c100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  QMainWindow State: 000000ff00000000fd0000000400000000000001820000037dfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006500fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007300000000440000037d000000de00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000254fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000004400000254000000b900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004d400000044fc0100000002fb0000000800540069006d00650000000000000004d40000048d00fffffffb0000000800540069006d00650100000000000004500000000000000000000003dc0000025400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
   Selection:
     collapsed: false
   Time:
@@ -374,6 +396,6 @@ Window Geometry:
     collapsed: false
   Views:
     collapsed: true
-  Width: 1236
-  X: 10
-  Y: 42
+  Width: 988
+  X: 150
+  Y: 160