65 lines
2.8 KiB
XML
65 lines
2.8 KiB
XML
<?xml version="1.0"?>
|
|
<launch>
|
|
<arg name="tf_map_scanmatch_transform_frame_name" default="scanmatcher_frame"/>
|
|
<arg name="base_frame" default="base_footprint"/>
|
|
<arg name="odom_frame" default="odom"/>
|
|
<arg name="pub_map_odom_transform" default="true"/>
|
|
<arg name="scan_subscriber_queue_size" default="5"/>
|
|
<arg name="scan_topic" default="scan"/>
|
|
<arg name="map_size" default="2048"/>
|
|
<!-- set use_tf_pose_start_estimate and map_with_known_poses to `true` when
|
|
the map-base_footprint transform is provided by a different node, such
|
|
as fake_localization -->
|
|
<arg name="disable_localization" default="false"/>
|
|
|
|
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
|
|
|
|
<!-- Frame names -->
|
|
<param name="map_frame" value="map" />
|
|
<param name="base_frame" value="$(arg base_frame)" />
|
|
<param name="odom_frame" value="$(arg odom_frame)" />
|
|
|
|
<!-- Tf use -->
|
|
<param name="use_tf_scan_transformation" value="true"/>
|
|
<param name="use_tf_pose_start_estimate" value="$(arg disable_localization)"/>
|
|
<param name="map_with_known_poses" value="$(arg disable_localization)" />
|
|
<param name="pub_map_odom_transform" value="$(arg pub_map_odom_transform)"/>
|
|
<param name="pub_map_scanmatch_transform" value="true" />
|
|
|
|
<!-- Map size / start point -->
|
|
<param name="map_resolution" value="0.050"/>
|
|
<param name="map_size" value="$(arg map_size)"/>
|
|
<param name="map_start_x" value="0.5"/>
|
|
<param name="map_start_y" value="0.5" />
|
|
<param name="map_multi_res_levels" value="3" />
|
|
<param name="map_pub_period" value ="2.0" />
|
|
|
|
<!-- Map update parameters -->
|
|
<param name="update_factor_free" value="0.4"/>
|
|
<param name="update_factor_occupied" value="0.9" />
|
|
<param name="map_update_distance_thresh" value="0.4"/>
|
|
<param name="map_update_angle_thresh" value="0.06" />
|
|
<param name="laser_min_dist" value="0.1" />
|
|
<param name="laser_max_dist" value="10.0" />
|
|
<param name="laser_z_min_value" value="-1.0" />
|
|
<param name="laser_z_max_value" value="1.0" />
|
|
|
|
<!-- Advertising config -->
|
|
<param name="advertise_map_service" value="true"/>
|
|
|
|
<param name="scan_subscriber_queue_size" value="$(arg scan_subscriber_queue_size)"/>
|
|
<param name="scan_topic" value="$(arg scan_topic)"/>
|
|
<param name="pose_update_topic" value="poseupdate" />
|
|
<param name="sys_msg_topic" value="syscommand" />
|
|
<param name="pub_odometry" value="false" />
|
|
|
|
<!-- Debug parameters -->
|
|
<!--
|
|
<param name="output_timing" value="false"/>
|
|
<param name="pub_drawings" value="true"/>
|
|
<param name="pub_debug_output" value="true"/>
|
|
-->
|
|
<param name="tf_map_scanmatch_transform_frame_name" value="$(arg tf_map_scanmatch_transform_frame_name)" />
|
|
<remap from="map" to="/map" />
|
|
</node>
|
|
</launch> |