( Trying again, accidentally deleted source branch for previous PR ) Related issue: #577 The min/max range default to the same as the backback_2d examples; same thing for the URDF file. However, the name of both the config file and the launch file are kept generic.master
parent
5ce6e68dd3
commit
0a917893c5
|
@ -0,0 +1,36 @@
|
|||
-- Copyright 2018 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.
|
||||
|
||||
options = {
|
||||
tracking_frame = "base_link",
|
||||
pipeline = {
|
||||
{
|
||||
action = "min_max_range_filter",
|
||||
min_range = 1.,
|
||||
max_range = 60.,
|
||||
},
|
||||
{
|
||||
action = "write_ros_map",
|
||||
range_data_inserter = {
|
||||
insert_free_space = true,
|
||||
hit_probability = 0.55,
|
||||
miss_probability = 0.49,
|
||||
},
|
||||
filestem = "map",
|
||||
resolution = 0.05,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return options
|
|
@ -0,0 +1,33 @@
|
|||
<!--
|
||||
Copyright 2018 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.
|
||||
-->
|
||||
|
||||
<!--
|
||||
Using this will generate one .pgm and one .yaml file that together
|
||||
form the typical occupancy grid ROS map.
|
||||
The files will be placed in the same directory of the bag file.
|
||||
Remember to change configuration in the lua config_file.
|
||||
-->
|
||||
|
||||
<launch>
|
||||
<arg name="urdf_filename" default="$(find cartographer_ros)/urdf/backback_2d.urdf"/>
|
||||
|
||||
<node name="cartographer_assets_writer" pkg="cartographer_ros" required="true"
|
||||
type="cartographer_assets_writer" args="
|
||||
-configuration_directory $(find cartographer_ros)/configuration_files
|
||||
-configuration_basename assets_writer_ros_map.lua
|
||||
-urdf_filename $(arg urdf_filename)
|
||||
-bag_filenames $(arg bag_filenames)
|
||||
-pose_graph_filename $(arg pose_graph_filename)"
|
||||
output="screen">
|
||||
</node>
|
||||
</launch>
|
Loading…
Reference in New Issue