Parcourir la source

增加ydlidar x2l gmapping文件

corvin il y a 5 ans
Parent
commit
e587dd4fa7

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

@@ -17,8 +17,8 @@
 #
 
 local_costmap:
-   global_frame: /odom_combined
-   robot_base_frame: /base_footprint
+   global_frame: odom_combined
+   robot_base_frame: base_footprint
    update_frequency: 3.0
    publish_frequency: 2.0
    static_map: false

+ 43 - 0
src/robot_navigation/launch/gmapping_ydlidar_X2L.launch

@@ -0,0 +1,43 @@
+<launch>
+  <param name="use_sim_time" value="false"/>  
+
+  <!-- startup rplidar node -->
+  <include file="$(find robot_navigation)/launch/ydlidar_X2L.launch" />
+
+  <!-- startup move_base node -->
+  <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="kernelSize" value="1"/>
+    <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="minimumScore" value="50"/>
+    <param name="srr" value="0.1"/>
+    <param name="srt" value="0.2"/>
+    <param name="str" value="0.1"/>
+    <param name="stt" value="0.2"/>
+    <param name="linearUpdate" value="1.0"/>
+    <param name="angularUpdate" value="0.5"/>
+    <param name="temporalUpdate" value="3.0"/>
+    <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="delta" value="0.05"/>
+    <param name="llsamplerange" value="0.01"/>
+    <param name="llsamplestep" value="0.01"/>
+    <param name="lasamplerange" value="0.005"/>
+    <param name="lasamplestep" value="0.005"/>
+  </node>
+</launch>

+ 18 - 0
src/robot_navigation/launch/ydlidar_X2L.launch

@@ -0,0 +1,18 @@
+<launch>
+  <node name="ydlidar_node"  pkg="ydlidar_ros"  type="ydlidar_node" output="screen" respawn="false" >
+    <param name="port"         type="string" value="/dev/ydlidar"/>  
+    <param name="baudrate"         type="int" value="115200"/>  
+    <param name="frame_id"     type="string" value="lidar"/>
+    <param name="resolution_fixed"    type="bool"   value="true"/>
+    <param name="auto_reconnect"    type="bool"   value="true"/>
+    <param name="reversion"    type="bool"   value="false"/>
+    <param name="angle_min"    type="double" value="-180" />
+    <param name="angle_max"    type="double" value="180" />
+    <param name="range_min"    type="double" value="0.1" />
+    <param name="range_max"    type="double" value="12.0" />
+    <param name="ignore_array" type="string" value="" />
+    <param name="frequency"    type="double" value="8"/>
+    <param name="samp_rate"    type="int"    value="3"/>
+    <param name="isSingleChannel"    type="bool"   value="true"/>
+  </node>
+</launch>