|
@@ -8,7 +8,7 @@
|
|
|
-->
|
|
|
<launch>
|
|
|
<!-- Run the map server with a map -->
|
|
|
- <node name="map_server" pkg="map_server" type="map_server" args="$(find robot_navigation)/maps/mymap.yaml" />
|
|
|
+ <node name="map_server" pkg="map_server" type="map_server" args="$(find robot_navigation)/maps/3.yaml" />
|
|
|
|
|
|
<!-- startup ydlidar X2L node -->
|
|
|
<include file="$(find robot_navigation)/launch/ydlidar_X2L.launch" />
|
|
@@ -23,26 +23,31 @@
|
|
|
<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="tf_broadcast" value="true"/>
|
|
|
|
|
|
<param name="use_map_topic" value="false"/>
|
|
|
- <param name="transform_tolerance" value="0.1" />
|
|
|
+ <param name="first_map_only" value="false" />
|
|
|
+
|
|
|
+ <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="5000"/>
|
|
|
+ <param name="max_particles" value="2500"/>
|
|
|
<param name="kld_err" value="0.1"/>
|
|
|
<param name="kld_z" value="0.99"/>
|
|
|
<param name="odom_alpha1" value="0.2"/>
|
|
|
- <param name="odom_alpha2" value="0.2"/>
|
|
|
- <param name="odom_alpha3" value="0.2"/>
|
|
|
+ <param name="odom_alpha2" value="0.1"/>
|
|
|
+ <param name="odom_alpha3" value="0.1"/>
|
|
|
<param name="odom_alpha4" value="0.2"/>
|
|
|
- <param name="odom_alpha5" value="0.2"/>
|
|
|
+ <param name="odom_alpha5" value="0.0"/>
|
|
|
+
|
|
|
+ <param name="save_pose_rate" value="0.5" />
|
|
|
|
|
|
- <param name="laser_z_hit" value="0.9"/>
|
|
|
+ <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.05"/>
|
|
|
- <param name="laser_sigma_hit" value="0.2"/>
|
|
|
+ <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"/>
|
|
@@ -50,11 +55,11 @@
|
|
|
<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.5"/>
|
|
|
- <param name="resample_interval" value="2"/>
|
|
|
- <param name="transform_tolerance" value="3.0"/>
|
|
|
- <param name="recovery_alpha_slow" value="0.0"/>
|
|
|
- <param name="recovery_alpha_fast" value="0.0"/>
|
|
|
+ <param name="update_min_a" value="0.08"/>
|
|
|
+ <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>
|
|
|
|