Преглед изворни кода

更新slam自动导航参数

corvin_zhang пре 4 година
родитељ
комит
a092b7426e

+ 13 - 16
src/robot_navigation/config/dwa_local_planner_params.yaml

@@ -7,45 +7,42 @@
 DWAPlannerROS:
 
 #robot configuration params
-  acc_lim_x: 0.1
-  acc_lim_y: 0.1
-  acc_lim_th: 0.2
+  acc_lim_x: 0.5
+  acc_lim_y: 0.5
+  acc_lim_th: 1.0
 
   max_vel_trans: 0.3
   min_vel_trans: 0.15
 
   max_vel_x: 0.2
-  min_vel_x: -0.16
+  min_vel_x: -0.2
 
   max_vel_y: 0.2
   min_vel_y: -0.2
 
-# angular volocity limit
-  max_vel_theta: 0.8
+  max_vel_theta: 2.0
   min_vel_theta: 0.4
-  min_in_place_vel_theta: 0.5
 
 # Goal Tolerance Parametes
   xy_goal_tolerance: 0.10
-  yaw_goal_tolerance: 0.15
+  yaw_goal_tolerance: 0.17
   latch_xy_goal_tolerance: false
 
 # Forward Simulation Parameters
-  sim_time: 2.5
-  sim_granularity: 0.025
-  vx_samples: 15
+  sim_time: 1.5
+  vx_samples: 10
   vy_samples: 10
-  vth_samples: 30
+  vth_samples: 40
+  controller_frequency: 4.0
 
 # Trajectory Scoring Parameters
-  path_distance_bias: 30.0
-  goal_distance_bias: 24.0
+  path_distance_bias: 32.0
+  goal_distance_bias: 20.0
   occdist_scale: 0.02
   forward_point_distance: 0.325
   stop_time_buffer: 0.2
-  scaling_speed: 0.20
+  scaling_speed: 0.25
   max_scaling_factor: 0.2
-  publish_cost_grid: false
 
 # Oscillation Prevention Parameters
   oscillation_reset_dist: 0.05

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

@@ -21,7 +21,3 @@ global_costmap:
    rolling_window: false
    transform_tolerance: 2.0
 
-   plugins:
-       - {name: static_map, type: "costmap_2d::StaticLayer"}
-       - {name: obstacles,  type: "costmap_2d::VoxelLayer"}
-

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

@@ -16,9 +16,6 @@
 #  20180410: init this file.
 #  20200413:更新本地代价地图配置参数.
 local_costmap:
-    plugins:
-        - {name: static_map,    type: "costmap_2d::StaticLayer"}
-        - {name: obstacles,     type: "costmap_2d::VoxelLayer"}
     global_frame: odom_combined
     robot_base_frame: base_footprint
     update_frequency: 1.0
@@ -26,8 +23,8 @@ local_costmap:
 
     static_map: false
     rolling_window: true
-    width: 1.0
-    height: 1.0
+    width: 2.0
+    height: 2.0
     resolution: 0.02   #should same as map.yaml file
     transform_tolerance: 2.0
 

Разлика између датотеке није приказан због своје велике величине
+ 1 - 1
src/robot_navigation/maps/mymap_org.pgm


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

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

Неке датотеке нису приказане због велике количине промена