Pārlūkot izejas kodu

更新自动导航相关代码对齐,增加可读性

corvin rasp melodic 2 gadi atpakaļ
vecāks
revīzija
a507324b9b

+ 14 - 15
src/robot_navigation/launch/amcl_ydlidar_X2L.launch

@@ -23,21 +23,21 @@
   <node pkg="amcl" type="amcl" name="robot_amcl">
     <param name="odom_model_type" value="diff-corrected"/>
 
-    <param name="base_frame_id" value="base_footprint"/>
+    <param name="base_frame_id"   value="base_footprint"/>
     <param name="global_frame_id" value="map"/>
-    <param name="odom_frame_id" value="odom_combined"/>
+    <param name="odom_frame_id"   value="odom_combined"/>
     <param name="tf_broadcast"    value="true"/>
 
-    <param name="use_map_topic" value="false"/>
-    <param name="first_map_only" value="false" />
+    <param name="use_map_topic"  value="false"/>
+    <param name="first_map_only" value="false"/>
 
-    <param name="transform_tolerance" value="3" />
+    <param name="transform_tolerance" value="3"/>
     <param name="gui_publish_rate" value="10.0"/>
     <param name="laser_max_beams" value="300"/>
     <param name="min_particles" value="500"/>
     <param name="max_particles" value="2500"/>
     <param name="kld_err" value="0.1"/>
-    <param name="kld_z" value="0.99"/>
+    <param name="kld_z"   value="0.99"/>
     <param name="odom_alpha1" value="0.2"/>
     <param name="odom_alpha2" value="0.1"/>
     <param name="odom_alpha3" value="0.1"/>
@@ -46,23 +46,22 @@
 
     <param name="save_pose_rate" value="0.5" />
 
-    <param name="laser_z_hit" value="0.5"/>
+    <param name="laser_z_hit"   value="0.5"/>
     <param name="laser_z_short" value="0.05"/>
-    <param name="laser_z_max" value="0.05"/>
-    <param name="laser_z_rand" value="0.5"/>
-    <param name="laser_sigma_hit" value="0.1"/>
+    <param name="laser_z_max"   value="0.05"/>
+    <param name="laser_z_rand"  value="0.5"/>
+    <param name="laser_sigma_hit"    value="0.1"/>
     <param name="laser_lambda_short" value="0.1"/>
     <param name="laser_model_type" value="likelihood_field"/>
     <param name="laser_model_type" value="beam"/>
-    <param name="laser_min_range" value="0.14"/>
-    <param name="laser_max_range" value="7.0"/>
+    <param name="laser_min_range"  value="0.14"/>
+    <param name="laser_max_range"  value="7.0"/>
     <param name="laser_likelihood_max_dist" value="2.0"/>
     <param name="update_min_d" value="0.05"/>
     <param name="update_min_a" value="0.08"/>
-    <param name="resample_interval" value="1"/>
+    <param name="resample_interval"   value="1"/>
     <param name="transform_tolerance" value="0.8"/>
     <param name="recovery_alpha_slow" value="0.001"/>
     <param name="recovery_alpha_fast" value="0.1"/>
   </node>
-</launch>
-
+</launch>

+ 14 - 17
src/robot_navigation/launch/gmapping_ydlidar_X2L.launch

@@ -1,8 +1,8 @@
 <!--
   Description:使用EAI的X2L雷达进行gamapping建图,整个过程如下:
-    首先启动x2l雷达,然后启动move_base节点,最后启动gmapping节点.
-    所有节点启动成功后,即可开始gmapping建图,在rviz中可以查看整个
-    建图过程.下面来解释一下gmapping操作的重点参数:
+    首先启动x2l雷达,然后启动gmapping节点.所有节点启动成功后,即可
+    开始gmapping建图,在rviz中可以查看整个建图过程.下面来解释一下
+    gmapping操作的重点参数:
     1):delta:调节生成地图的分辨率,单位米.
   Author: corvin
   History:
@@ -14,22 +14,19 @@
   <!-- startup EAI X2L lidar node -->
   <include file="$(find robot_navigation)/launch/ydlidar_X2L.launch" />
 
-  <!-- startup move_base node --><!-- 建图不需要启动move_base -->
-  <!-- <include file="$(find robot_navigation)/launch/move_base.launch" /> -->
-
   <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">  
     <param name="odom_frame" value="odom_combined" />
 
     <param name="map_update_interval" value="5.0"/>
-    <param name="maxUrange" value="7.5"/>
-    <param name="sigma" value="0.05"/>
+    <param name="maxUrange"  value="7.5"/>
+    <param name="sigma"      value="0.05"/>
     <param name="kernelSize" value="1"/>
-    <param name="lstep" value="0.05"/>
-    <param name="astep" value="0.05"/>
+    <param name="lstep"      value="0.05"/>
+    <param name="astep"      value="0.05"/>
     <param name="iterations" value="5"/>
-    <param name="lsigma" value="0.075"/>
-    <param name="ogain"  value="3.0"/>
-    <param name="lskip"  value="0"/>
+    <param name="lsigma"     value="0.075"/>
+    <param name="ogain"      value="3.0"/>
+    <param name="lskip"      value="0"/>
     <param name="minimumScore" value="50"/>
 
     <param name="srr" value="0.1"/>
@@ -43,10 +40,10 @@
     <param name="resampleThreshold" value="0.5"/>
     <param name="particles" value="30"/>
 
-    <param name="xmin" value="-5.0"/>
-    <param name="ymin" value="-5.0"/>
-    <param name="xmax" value="5.0"/>
-    <param name="ymax" value="5.0"/>
+    <param name="xmin"  value="-5.0"/>
+    <param name="ymin"  value="-5.0"/>
+    <param name="xmax"  value="5.0"/>
+    <param name="ymax"  value="5.0"/>
     <param name="delta" value="0.05"/> <!--resolution of the map --><!--大环境建图范围为0.05-0.1 -->
 
     <param name="llsamplerange" value="0.01"/>

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

@@ -23,11 +23,11 @@
     <param name="recovery_behavior_enabled" value="true" />
     <param name="clearing_rotation_allowed" value="true" />
 
-    <param name="shutdown_costmaps"    value="false" />
-    <param name="oscillation_timeout"  value="10.0" />
-    <param name="oscillation_distance" value="0.2" />
+    <param name="shutdown_costmaps"    value="false"/>
+    <param name="oscillation_timeout"  value="10.0"/>
+    <param name="oscillation_distance" value="0.2"/>
 
-    <param name="max_planning_retries" value="10"  />
+    <param name="max_planning_retries" value="10"/>
 
     <rosparam file="$(find robot_navigation)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
     <rosparam file="$(find robot_navigation)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />