XTDrone/sitl_config/ugv/catvehicle/launch/hectorslam-sicktest.launch

78 lines
3.2 KiB
XML

<!--
Author: Jonathan Sprinkle, Sam Taylor, Alex Warren
Copyright (c) 2015 Arizona Board of Regents
All rights reserved.
Permission is hereby granted, without written agreement and without
license or royalty fees, to use, copy, modify, and distribute this
software and its documentation for any purpose, provided that the
above copyright notice and the following two paragraphs appear in
all copies of this software.
IN NO EVENT SHALL THE ARIZONA BOARD OF REGENTS BE LIABLE TO ANY PARTY
FOR DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES
ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN
IF THE ARIZONA BOARD OF REGENTS HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGE.
THE ARIZONA BOARD OF REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES,
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY
AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER
IS ON AN "AS IS" BASIS, AND THE UNIVERSITY OF CALIFORNIA HAS NO OBLIGATION
TO PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
Summary:
========
This launch file loads the SLAM algorithms using the hector_slam package
How to execute this file?
========================
roslaunch catvehicle catvehicle_skidpan.launch
-->
<launch>
<arg name="robot_name" default="catvehicle"/>
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" respawn="false" output="screen" >
<param name="pub_map_odom_transform" value="true"/>
<param name="map_frame" value="map" />
<param name="scan_topic" value="/scan" />
<param name="base_frame" value="/laser" />
<param name="odom_frame" value="/slamodom" />
<param name="map_resolution" value="0.1" />
<param name="map_size" value="500" />
<param name="map_pub_period" value="0.5" />
<param name="scan_subscriber_queue_size" value="100"/>
</node>
<node pkg="tf" type="static_transform_publisher" name="map2odom_tf_$(arg robot_name)"
args="0 0 0 0 0 0 /slamodom /laser 5"/>
<arg name="trajectory_source_frame_name" default="/slamodom"/>
<arg name="trajectory_update_rate" default="4"/>
<arg name="trajectory_publish_rate" default="0.25"/>
<node pkg="hector_trajectory_server" type="hector_trajectory_server" name="hector_trajectory_server" output="screen">
<param name="target_frame_name" type="string" value="/map" />
<param name="source_frame_name" type="string" value="$(arg trajectory_source_frame_name)" />
<param name="trajectory_update_rate" type="double" value="$(arg trajectory_update_rate)" />
<param name="trajectory_publish_rate" type="double" value="$(arg trajectory_publish_rate)" />
</node>
<node pkg="hector_geotiff" type="geotiff_node" name="hector_geotiff_node" output="screen" launch-prefix="nice -n 15">
<remap from="map" to="/dynamic_map" />
<param name="map_file_path" type="string" value="$(find catvehicle)/maps" />
<param name="map_file_base_name" type="string" value="hector_slam_map" />
<param name="geotiff_save_period" type="double" value="0" />
<param name="draw_background_checkerboard" type="bool" value="true" />
<param name="draw_free_space_grid" type="bool" value="true" />
</node>
</launch>