forked from carlosmccosta/dynamic_robot_localization
-
Notifications
You must be signed in to change notification settings - Fork 1
/
dynamic_robot_localization_system_6dof.launch
73 lines (58 loc) · 4.46 KB
/
dynamic_robot_localization_system_6dof.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- frame ids -->
<arg name="map_frame_id" default="map" />
<arg name="odom_frame_id" default="odom" />
<arg name="base_link_frame_id" default="base_link" />
<arg name="sensor_frame_id" default="camera_rgb_optical_frame" />
<!-- reference map data -->
<arg name="reference_pointcloud_filename" default="" />
<arg name="reference_pointcloud_available" default="true" /> <!-- if false, drl will perform slam (simultaneous localization and mapping) -->
<!-- sensor data from point cloud topic -->
<arg name="ambient_pointcloud_topic" default="/camera/depth_registered/points" />
<!-- main configurations -->
<arg name="pcl_verbosity_level" default="ERROR" /> <!-- VERBOSE | DEBUG | INFO | WARN | ERROR | ALWAYS || ALWAYS -> no console output -->
<arg name="ros_verbosity_level" default="INFO" /> <!-- DEBUG | INFO | WARN | ERROR | FATAL -->
<arg name="yaml_configuration_filters_filename" default="$(find dynamic_robot_localization)/yaml/configs/filters/filters_3d_tof.yaml" if="$(arg reference_pointcloud_available)" />
<arg name="yaml_configuration_filters_filename" default="$(find dynamic_robot_localization)/yaml/configs/filters/filters_3d_tof_slam.yaml" unless="$(arg reference_pointcloud_available)" />
<!-- initial pose setup -->
<arg name="robot_initial_pose_in_base_to_map" default="true" />
<arg name="robot_initial_pose_available" default="true" />
<arg name="robot_initial_x" default="0.0" />
<arg name="robot_initial_y" default="0.0" />
<arg name="robot_initial_z" default="0.0" />
<arg name="robot_initial_roll" default="0.0" />
<arg name="robot_initial_pitch" default="0.0" />
<arg name="robot_initial_yaw" default="0.0" />
<include file="$(find dynamic_robot_localization)/launch/dynamic_robot_localization_system.launch" >
<arg name="pcl_verbosity_level" default="$(arg pcl_verbosity_level)" />
<arg name="ros_verbosity_level" default="$(arg ros_verbosity_level)" />
<arg name="map_frame_id" default="$(arg map_frame_id)" />
<arg name="odom_frame_id" default="$(arg odom_frame_id)" />
<arg name="base_link_frame_id" default="$(arg base_link_frame_id)" />
<arg name="sensor_frame_id" default="$(arg sensor_frame_id)" />
<arg name="yaml_configuration_filters_filename" default="$(arg yaml_configuration_filters_filename)"/>
<arg name="yaml_configuration_pose_estimation_filename" default="$(find dynamic_robot_localization)/yaml/configs/empty.yaml" />
<!-- <arg name="yaml_configuration_pose_estimation_filename" default="$(find dynamic_robot_localization)/yaml/configs/pose_estimation/initial_pose_estimation_3d.yaml" /> -->
<arg name="yaml_configuration_tracking_filename" default="$(find dynamic_robot_localization)/yaml/configs/pose_tracking/cluttered_environments_dynamic_large_map_3d.yaml" if="$(arg reference_pointcloud_available)" />
<arg name="yaml_configuration_tracking_filename" default="$(find dynamic_robot_localization)/yaml/configs/pose_tracking/cluttered_environments_dynamic_large_map_slam_3d.yaml" unless="$(arg reference_pointcloud_available)" />
<arg name="yaml_configuration_recovery_filename" default="$(find dynamic_robot_localization)/yaml/configs/pose_recovery/recovery_3d.yaml" />
<arg name="reference_pointcloud_filename" default="$(arg reference_pointcloud_filename)" if="$(arg reference_pointcloud_available)" />
<arg name="reference_pointcloud_filename" default="" unless="$(arg reference_pointcloud_available)" />
<arg name="reference_pointcloud_available" default="$(arg reference_pointcloud_available)" />
<arg name="reference_pointcloud_type_3d" default="true" />
<arg name="ambient_pointcloud_topic" default="$(arg ambient_pointcloud_topic)" />
<arg name="robot_initial_pose_in_base_to_map" default="$(arg robot_initial_pose_in_base_to_map)" />
<arg name="robot_initial_pose_available" default="$(arg robot_initial_pose_available)" />
<arg name="robot_initial_x" default="$(arg robot_initial_x)" />
<arg name="robot_initial_y" default="$(arg robot_initial_y)" />
<arg name="robot_initial_z" default="$(arg robot_initial_z)" />
<arg name="robot_initial_roll" default="$(arg robot_initial_roll)" />
<arg name="robot_initial_pitch" default="$(arg robot_initial_pitch)" />
<arg name="robot_initial_yaw" default="$(arg robot_initial_yaw)" />
<arg name="use_laser_assembler" default="false" />
<arg name="invert_tf_transform" default="true" />
<arg name="invert_tf_hierarchy" default="true" />
<arg name="use_octomap_for_dynamic_map_update" default="false" />
</include>
</launch>