Browse Source

新增base_golba_palnner_params.yaml配置文件

corvin_zhang 4 years ago
parent
commit
142489e6f6

+ 24 - 0
src/robot_navigation/config/base_global_planner_params.yaml

@@ -0,0 +1,24 @@
+# Copyright: 2016-2020 ROS小课堂 www.corvin.cn
+# Description: 三轮全向移动小车的全局路径规划参数配置文件.
+# Author: corvin
+# History:
+#   20200821: init this file.
+
+# Global Planner Selection
+base_global_planner: "global_planner/GlobalPlanner"
+
+GlobalPlanner:
+    allow_unknown: false
+    default_tolerance: 0.2
+    visualize_potential: false
+    use_dijkstra: true
+    use_quadratic: true
+    use_grid_path: false
+    old_navfn_behavior: false
+    lethal_cost: 253
+    neutral_cost: 50
+    cost_factor: 3
+    publish_potential: true
+    orientation_mode: 0
+    orientation_window_size: 1
+

+ 7 - 5
src/robot_navigation/config/dwa_local_planner_params.yaml

@@ -4,14 +4,16 @@
 # History:
 #   20200413:init this file.
 #
-DWAPlannerROS:
 
+base_local_planner: "dwa_local_planner/DWAPlannerROS"
+
+DWAPlannerROS:
 #robot configuration params
   acc_lim_x: 0.5
   acc_lim_y: 0.5
-  acc_lim_th: 1.0
+  acc_lim_th: 0.5
 
-  max_vel_trans: 0.3
+  max_vel_trans: 0.2
   min_vel_trans: 0.15
 
   max_vel_x: 0.2
@@ -20,8 +22,8 @@ DWAPlannerROS:
   max_vel_y: 0.2
   min_vel_y: -0.2
 
-  max_vel_theta: 2.0
-  min_vel_theta: 0.4
+  max_vel_theta: 1.0
+  min_vel_theta: 0.5
 
 # Goal Tolerance Parametes
   xy_goal_tolerance: 0.10

+ 0 - 1
src/robot_navigation/launch/amcl_ydlidar_X2L.launch

@@ -25,7 +25,6 @@
     <param name="odom_frame_id" value="odom_combined"/>
 
     <param name="use_map_topic" value="true"/>
-    <param name="odom_alpha5" value="0.1"/>
     <param name="transform_tolerance" value="0.5" />
     <param name="gui_publish_rate" value="1.0"/>
     <param name="laser_max_beams" value="300"/>

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

@@ -13,9 +13,6 @@
 -->
 <launch>
   <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" clear_params="true">
-    <param name="base_global_planner" value="navfn/NavfnROS" />
-    <param name="base_local_planner"  value="dwa_local_planner/DWAPlannerROS" />
-
     <param name="controller_frequency" value="1.5" />
     <param name="controller_patiente"  value="4.0" />
 
@@ -36,6 +33,9 @@
     <rosparam file="$(find robot_navigation)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
     <rosparam file="$(find robot_navigation)/config/local_costmap_params.yaml"  command="load" />
     <rosparam file="$(find robot_navigation)/config/global_costmap_params.yaml" command="load" />
+
+    <!-- 加载move_base使用的全局路径规划和局部路径规划算法及对应的参数  -->
+    <rosparam file="$(find robot_navigation)/config/base_global_planner_params.yaml" command="load" />
     <rosparam file="$(find robot_navigation)/config/dwa_local_planner_params.yaml" command="load" />
   </node>
 </launch>

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


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

@@ -1,6 +1,6 @@
-image: /home/corvin/blackTornadoRobot/src/robot_navigation/maps/mymap.pgm
+image: mymap.pgm
 resolution: 0.020000
-origin: [-15.880000, -5.000000, 0.000000]
+origin: [-15.240000, -5.000000, 0.000000]
 negate: 0
 occupied_thresh: 0.65
 free_thresh: 0.196

+ 1 - 1
src/ros_arduino_bridge/ros_arduino_python/config/my_arduino_params.yaml

@@ -36,7 +36,7 @@ odom_name: odom
 wheel_diameter: 0.058
 wheel_track: 0.109     #L value
 encoder_resolution: 11 #12V DC motors
-gear_reduction: 103    #empty payload rpm 60 r/m
+gear_reduction: 78    #empty payload rpm 60 r/m
 linear_scale_correction: 1.028
 angular_scale_correction: 1.00
 

Some files were not shown because too many files changed in this diff