Commit 21012be8 authored by dla.adolfsson@gmail.com's avatar dla.adolfsson@gmail.com
Browse files

added launch files

parent 446c08af
<?xml version="1.0"?>
<launch>
<!-- Start rosbag with launchfile-->
<arg name="run_bag" default="false" />
<!-- Absolute Path to map to be used for localization. The map needs to be built by graph_fuser package -->
<arg name="map_file_path" default="$(find graph_map)/maps/ndt_map.MAP" />
<arg name="robot_prefix" default="robot5" />
<arg name="rviz_enabled" default="true" />
<arg name="root_link_id" default="map_laser2d" />
<!-- Include visualization in rviz -->
<group if="$(arg rviz_enabled)">
<include file="$(find graph_map)/launch/visualize_graph_fuser.launch" >
<arg name="localization" value="true" />
<arg name="oru-lab" value="true" />
</include>
</group>
<!-- Run monte carlo localization -->
<!--node name="occupancy_map_server" pkg="map_server" type="map_server" args=" $(find graph_map)/maps/occupancy_map.yaml" output="screen"/--> <!--frame_id map_velodyne-->
<group if="$(arg rviz_enabled)">
<node name="graph_map_publisher" pkg="graph_map" type="graph_map_publisher" output="screen">
<param name="map_rate" value="1" />
<param name="map_file" value="$(arg map_file_path)" />
<param name="map_frame" value="/maps/map_laser2d" />
<param name="map_parent_frame_id" value="$(arg root_link_id)"/>
<param name="map_topic" value="/maps/map_velodyne" />
</node>
</group>
<!--node pkg="tf" type="static_transform_publisher" name="velodyne_map_static_broadcaster" args="0 0 0 0 0 0 world map_velodyne 100"/-->
<!--node pkg="tf" type="static_transform_publisher" name="occupancy_map_static_broadcaster" args="0 0 0 0 0 0 world map 100"/-->
</launch>
<?xml version="1.0" encoding="utf-8"?>
<launch>
<arg name="run_bag" default="false"/>
<arg name="robot_prefix" default="robot5"/>
<arg name="output_pointcloud_topic_name" default="/fused_cloud"/>
<arg name="rviz_enabled" default="false"/>
<group if="$(arg rviz_enabled)">
<!-- Include visualization in rviz -->
<include file="$(find graph_map)/launch/visualize_graph_fuser.launch" >
<arg name="mapping" value="true" />
<arg name="oru-lab" value="true" />
</include>
</group>
<!-- start mapping node -->
<node pkg="graph_map" type="graph_map_fuser_node" name="graph_node" output="screen">
<!-- Choose weather to initiate pose to pose_init_<x,y,t> or the data of /<gt_topic> -->
<param name="initPoseFromGT" value="false" />
<param name="pose_init_x" value="0" />
<param name="pose_init_y" value="0" />
<param name="pose_init_t" value="0" />
<param name="save_occupancy" value="true" />
<!-- Select mapping technique to one of the methods listed in graph_map/include/graph_factory.h -->
<param name="map_type" value="ndt_map" />
<!-- use local maps instead of a single map, this can improve map descriptiveness -->
<param name="use_submap" value="false" />
<param name="interchange_radius" value="7" />
<param name="compound_radius" value="0" />
<param name="map_switching_method" value="node_position_esg" /> <!-- <node_position> (revisit previously mapped nodes), node_position_est (never revisit, form an exactly sparse submap graph -->
<param name="velodyne_config_file" value="$(find graph_map)/config/VLP16db.yaml" />
<!-- choose to disable essential parts of the software -->
<param name="enable_registration" value="true" />
<param name="registration_2D" value="false" />
<!-- Select registration technique to one of the methods listed in graph_map/include/graph_factory.h -->
<param name="registration_type" value="ndt_d2d_reg" />
<!-- Use fine to course ndt_cells in registration -->
<param name="multi-res" value="false" />
<param name="resolutionLocalFactor" value="1.2" />
<param name="reg_itr_max" value="30" />
<!-- Resolution of a map, usually between 0.4 and 1.2 -->
<param name="n_neighbours" value="1" />
<param name="enable_mapping" value="true" />
<param name="resolution" value="0.65" />
<param name="tf_pose_frame" value="" />
<!-- if laser_2d is true, a 2d scanner will be used for mapping-->
<param name="laser_2d" value="false" />
<param name="laser_frame_id" value="$(arg robot_prefix)/velodyne " />
<!-- Topic of laser scanner -->
<!--param name="points_topic" value="$(arg namespace_prefix)/kmo_navserver/laserscan1" /-->
<param name="points_topic" value="$(arg robot_prefix)/sensors/velodyne_packets" />
<param name="output_pointcloud_topic_name" value="$(arg output_pointcloud_topic_name)" />
<param name="useOdometry" value="true" />
<param name="odometry_topic" value="$(arg robot_prefix)/control/odom"/>
<param name="use_tf_listener" value="true" />
<param name="gt_topic" value="$(arg robot_prefix)/control/state" />
<!-- odometry frame id-->
<param name="odom_tf" value="$(arg robot_prefix)/odom" />
<param name="base_tf" value="$(arg robot_prefix)/base_footprint" />
<!-- check if the registration pose output is similar to odometry prediction within max_translation_norm or max_rotation_norm -->
<param name="check_consistency" value="true" />
<param name="max_translation_norm" value="0.2" />
<param name="max_rotation_norm" value="0.78539816339" />
<!-- size of map -->
<param name="size_x_meters" value="70" />
<param name="size_y_meters" value="70" />
<param name="size_z_meters" value="10" />
<!--<param name="laser_variance_z" value="0.02" /> -->
<!--range of sensor, min range can prevent self-mapping of the robot or operator of the lidar, max range can remove uncertain measurments -->
<param name="max_range" value="130." />
<param name="min_range" value="1.8" />
<!-- Specific sensor offset parameters with respect to the odometry frame -->
<param name="sensor_pose_x" value="0.807" />
<param name="sensor_pose_y" value="-0.003" />
<param name="sensor_pose_z" value="0.95" />
<param name="sensor_pose_t" value="0" />
<param name="sensor_offset_t" value="0.0" />
<!-- Output directory where the map is stored -->
<!-- invoke rosservice call /graph_ -->
<param name="map_directory" value="$(find graph_map)/maps" />
<param name="visualize" value="true" />
<param name="disable_map_visualization" value="false" />
<param name="T_map" value="3.0" />
<!-- a minimum movement is required before fusing frames -->
<param name="use_keyframe" value="true" />
<param name="min_keyframe_dist" value="0.05" />
<param name="min_keyframe_rot_deg" value="1.0" />
</node>
<node pkg="octomap_server" type="octomap_server_node" name="octomap_server">
<remap from="cloud_in" to="$(arg output_pointcloud_topic_name)"/>
<param name="frame_id" value="world"/>
<param name="resolution" value="0.15"/>
<param name="sensor_model/max_range" value="10.0"/>
<param name="pointcloud_max_z" value="5"/>
<param name="occupancy_min_z" value="0.1"/>
<param name="occupancy_max_z" value="1.8"/>
</node>
<!-- start a rosbag -->
<group if="$(arg run_bag)">
<arg name="path" default="$(find graph_map)/data/" />
<arg name="file_1" default="2018-05-18-09-55-16.bag" />
<node pkg="rosbag" type="play" name="player" output="screen" args="--clock -r 1.0 -q $(arg path)$(arg file_1)"/>
</group>
<node pkg="tf" type="static_transform_publisher" name="velodyne_map_static_broadcaster" args="0 0 0 0 0 0 world map_laser2d 100" />
</launch>
<?xml version="1.0" encoding="utf-8"?>
<launch>
<arg name="run_bag" default="false"/>
<arg name="robot_prefix" default="robot5"/>
<arg name="output_pointcloud_topic_name" default="/fused_cloud"/>
<arg name="rviz_enabled" default="true"/>
<group if="$(arg rviz_enabled)">
<!-- Include visualization in rviz -->
<include file="$(find graph_map)/launch/visualize_graph_fuser.launch" >
<arg name="mapping" value="true" /> Command 'rosbag' from package 'python-rosbag' (universe)
<arg name="oru-lab" value="true" />
</include>
</group>
<node pkg="tf" type="static_transform_publisher" name="velodyne_map_static_broadcaster" args="0 0 0 0 0 0 world map_velodyne 100" />
</launch>
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment