74 lines
2.8 KiB
XML
74 lines
2.8 KiB
XML
<!--
|
|
Copyright 2016 The Cartographer Authors
|
|
|
|
Licensed under the Apache License, Version 2.0 (the "License");
|
|
you may not use this file except in compliance with the License.
|
|
You may obtain a copy of the License at
|
|
|
|
http://www.apache.org/licenses/LICENSE-2.0
|
|
|
|
Unless required by applicable law or agreed to in writing, software
|
|
distributed under the License is distributed on an "AS IS" BASIS,
|
|
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
|
See the License for the specific language governing permissions and
|
|
limitations under the License.
|
|
-->
|
|
|
|
<launch>
|
|
<param name="robot_description"
|
|
textfile="$(find google_cartographer)/urdf/backpack_3d.urdf" />
|
|
|
|
<node name="robot_state_publisher" pkg="robot_state_publisher"
|
|
type="robot_state_publisher" />
|
|
|
|
<node name="cartographer" pkg="google_cartographer"
|
|
type="cartographer_node" output="screen" >
|
|
<rosparam subst_value="true">
|
|
# This node publishes the transformation between the tracking and map
|
|
# frames.
|
|
map_frame: "map"
|
|
tracking_frame: "base_link"
|
|
|
|
# Lua configuration files are always searched in the cartographer
|
|
# installation directory. We also ship configuration that work well for
|
|
# the platforms that we used to collect our example data. You probably
|
|
# want to add your own configuration overwrites in your own node
|
|
# directories - you should add the path here as first entry then.
|
|
configuration_files_directories: [
|
|
"$(find google_cartographer)/configuration_files"
|
|
]
|
|
|
|
# Configuration file for SLAM. The settings in here are tweaked to the
|
|
# collection platform you are using.
|
|
mapping_configuration_basename: "backpack_3d.lua"
|
|
|
|
imu_topic: "/imu"
|
|
|
|
# Laser min and max range. Everything not in this range will not be used for mapping.
|
|
laser_min_range_m: 0.
|
|
laser_max_range_m: 30.
|
|
|
|
# Missing laser echoes will be inserted as free space at this distance.
|
|
laser_missing_echo_ray_length_m: 5.
|
|
|
|
# Only choose one in the next parameter block
|
|
# laser_scan_2d_topic: "/horizontal_2d_laser"
|
|
# multi_echo_laser_scan_2d_topic: "/horizontal_multiecho_2d_laser"
|
|
laser_scan_3d_topics: ["/horizontal_3d_laser", "/vertical_3d_laser"]
|
|
</rosparam>
|
|
</node>
|
|
|
|
<!-- TODO(hrapp): still useful for occasional testing, but delete eventually.
|
|
<node pkg="hector_mapping" type="hector_mapping" name="hector_height_mapping"
|
|
output="screen">
|
|
<param name="scan_topic" value="horizontal_2d_laser" />
|
|
<param name="pub_map_odom_transform" value="true"/>
|
|
<param name="map_frame" value="map" />
|
|
<param name="base_frame" value="base_link" />
|
|
<param name="odom_frame" value="base_link" />
|
|
<param name="map_size" value="4096" />
|
|
<param name="map_resolution" value="0.1" />
|
|
</node>
|
|
-->
|
|
</launch>
|