├── tf_tree
└── frames.pdf
├── launch
├── run.sh
├── kitti_3d.launch
├── assets_writer_kitti_3d.launch
├── demo_kitti_3d.launch
└── offline_kitti_3d.launch
├── package.xml
├── CMakeLists.txt
├── configuration_files
├── transform.lua
├── assets_writer_kitti_3d.lua
├── kitti_3d_modi.lua
├── kitti_3d.rviz
├── kitti_3d_new.rviz
├── kitti_3d_for_debug.rviz
└── kitti_3d_rgb.rviz
└── README.md
/tf_tree/frames.pdf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/inkyusa/cartographer_kitti_config/HEAD/tf_tree/frames.pdf
--------------------------------------------------------------------------------
/launch/run.sh:
--------------------------------------------------------------------------------
1 | #!/bin/sh
2 | roslaunch ./demo_kitti_3d.launch bag_filename:=/home/enddl22/workspace/bags/cartographer/kitti/kitti_2011_09_30_drive_0027_synced_imu_velo.bag
3 |
--------------------------------------------------------------------------------
/package.xml:
--------------------------------------------------------------------------------
1 |
2 | cartographer_kitti_config
3 | 0.1.0
4 |
5 | Cartographer configurations and launch files for the KITTI dataset.
6 |
7 |
8 | Inkyu Sa
9 |
10 | Apache 2.0
11 |
12 | catkin
13 |
14 | g++-static
15 |
16 | cartographer_ros
17 | message_runtime
18 | roscpp
19 | roslib
20 |
21 | rosunit
22 |
--------------------------------------------------------------------------------
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.12) # Ships with Ubuntu 14.04 (Trusty)
2 |
3 | project(cartographer_kitti_config)
4 |
5 | set(PACKAGE_DEPENDENCIES
6 | cartographer_ros
7 | roscpp
8 | roslib
9 | )
10 |
11 | find_package(cartographer REQUIRED)
12 | include("${CARTOGRAPHER_CMAKE_DIR}/functions.cmake")
13 | google_initialize_cartographer_project()
14 | google_enable_testing()
15 |
16 | find_package(LuaGoogle REQUIRED)
17 |
18 | find_package(catkin REQUIRED COMPONENTS ${PACKAGE_DEPENDENCIES})
19 |
20 | # Override Catkin's GTest configuration to use GMock.
21 | set(GTEST_FOUND TRUE)
22 | set(GTEST_INCLUDE_DIRS ${GMOCK_INCLUDE_DIRS})
23 | set(GTEST_LIBRARIES ${GMOCK_LIBRARIES})
24 |
25 | catkin_package(CATKIN_DEPENDS message_runtime ${PACKAGE_DEPENDENCIES})
26 |
27 | install(DIRECTORY launch configuration_files
28 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
29 | )
--------------------------------------------------------------------------------
/configuration_files/transform.lua:
--------------------------------------------------------------------------------
1 | -- Copyright 2017 The Cartographer Authors
2 | --
3 | -- Licensed under the Apache License, Version 2.0 (the "License");
4 | -- you may not use this file except in compliance with the License.
5 | -- You may obtain a copy of the License at
6 | --
7 | -- http://www.apache.org/licenses/LICENSE-2.0
8 | --
9 | -- Unless required by applicable law or agreed to in writing, software
10 | -- distributed under the License is distributed on an "AS IS" BASIS,
11 | -- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | -- See the License for the specific language governing permissions and
13 | -- limitations under the License.
14 |
15 | XY_TRANSFORM = {
16 | translation = { 0., 0., 0. },
17 | rotation = { 0., -math.pi / 2., 0., },
18 | }
19 |
20 | XZ_TRANSFORM = {
21 | translation = { 0., 0., 0. },
22 | rotation = { 0. , 0., -math.pi / 2, },
23 | }
24 |
25 | YZ_TRANSFORM = {
26 | translation = { 0., 0., 0. },
27 | rotation = { 0. , 0., math.pi, },
28 | }
29 |
--------------------------------------------------------------------------------
/launch/kitti_3d.launch:
--------------------------------------------------------------------------------
1 |
13 |
14 |
15 |
16 |
21 |
22 |
23 |
25 |
--------------------------------------------------------------------------------
/launch/assets_writer_kitti_3d.launch:
--------------------------------------------------------------------------------
1 |
16 |
17 |
18 |
25 |
26 |
27 |
--------------------------------------------------------------------------------
/launch/demo_kitti_3d.launch:
--------------------------------------------------------------------------------
1 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
31 |
32 |
33 | - world
34 |
35 |
36 |
--------------------------------------------------------------------------------
/launch/offline_kitti_3d.launch:
--------------------------------------------------------------------------------
1 |
16 |
17 |
18 |
19 |
20 |
22 |
23 |
24 |
30 |
31 |
32 |
33 |
34 |
35 |
37 |
38 |
39 | - world
40 |
41 |
42 |
43 |
45 |
46 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # cartographer_kitti_config
2 | cartographer configuration files for KITTI dataset including .lua and .launch
3 |
4 | # download bagfiles
5 | We provide two bag files (kitti_2011_09_30_drive_0027_synced_imu_velo.bag and kitti_2011_09_30_drive_0028_synced_imu_velo.bag) that were generated from the oroginal KITTI datasets. Note that these bags only contain IMU and 3D point clouds from Velodyne. Stereo images are exclueded for the sake of file size and they aren't exploited with Cartographer.
6 |
7 | * [kitti_2011_09_30_drive_0027_synced_imu_velo.bag](https://drive.google.com/open?id=1KXX1tgWKL1D50oDpIjYe6UMDJKKTwW8U)
8 | * [kitti_2011_09_30_drive_0028_synced_imu_velo.bag](https://drive.google.com/open?id=1Fu5OsjAzozjJ_Q2xdqkoq-gbmo9Mb7uL)
9 |
10 |
11 | Examples below assume that you have a bag file at `/home/userHome/workspace/bags/kitti/kitti_2011_09_30_drive_0027_synced_imu_velo.bag`.
12 |
13 | ## demo KITTI 3D
14 | ```
15 | roslaunch cartographer_kitti_config demo_kitti_3d.launch bag_filename:=/home/userHome/workspace/bags/kitti/kitti_2011_09_30_drive_0027_synced_imu_velo.bag
16 | ```
17 | After execute the script, this is what you expect,
18 |
19 |
20 | https://youtu.be/29Knm-phAyI
21 |
22 | ## demo offline KITTI 3D
23 | ```
24 | roslaunch cartographer_kitti_config offline_kitti_3d.launch bag_filenames:=/home/userHome/workspace/bags/kitti/kitti_2011_09_30_drive_0027_synced_imu_velo.bag
25 | ```
26 | ## assets writer KITTI 3D
27 | ```
28 | roslaunch cartographer_kitti_config assets_writer_kitti_3d.launch bag_filenames:=/home/userHome/workspace/bags/kitti/kitti_2011_09_30_drive_0027_synced_imu_velo.bag pose_graph_filename:=/home/userHome/workspace/bags/kitti/kitti_2011_09_30_drive_0027_synced_imu_velo.bag.pbstream
29 | ```
30 |
31 | For the longer sequence dataset (i.e., kitti_2011_09_30_drive_0028_synced_imu_velo.bag), just substitue the name of bag file and you expect to see a similar figure as below (no stereo images).
32 |
33 |
34 | https://youtu.be/mn4y3yQm3Pc
35 |
36 |
37 | ## Citation
38 | If this small piece of software is somehow useful for your work, please cite this repository:
39 | ```
40 | @misc{kitti_lidar_cartographer_2018,
41 | title={Cartographer configurations for processing KITTI datasets},
42 | author={Inkyu Sa},
43 | year={2018},
44 | publisher={Github},
45 | journal={GitHub repository},
46 | howpublished={\url{https://tinyurl.com/ub35aah}},
47 | }
48 | ```
49 |
--------------------------------------------------------------------------------
/configuration_files/assets_writer_kitti_3d.lua:
--------------------------------------------------------------------------------
1 | -- Copyright 2016 The Cartographer Authors
2 | --
3 | -- Licensed under the Apache License, Version 2.0 (the "License");
4 | -- you may not use this file except in compliance with the License.
5 | -- You may obtain a copy of the License at
6 | --
7 | -- http://www.apache.org/licenses/LICENSE-2.0
8 | --
9 | -- Unless required by applicable law or agreed to in writing, software
10 | -- distributed under the License is distributed on an "AS IS" BASIS,
11 | -- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | -- See the License for the specific language governing permissions and
13 | -- limitations under the License.
14 |
15 | -- VOXEL_SIZE = 5e-2
16 | VOXEL_SIZE = 2e-1 -- 20cm
17 |
18 | include "transform.lua"
19 |
20 | options = {
21 | tracking_frame = "imu_link",
22 | pipeline = {
23 | {
24 | action = "min_max_range_filter",
25 | min_range = 1.,
26 | max_range = 60.,
27 | },
28 | {
29 | action = "dump_num_points",
30 | },
31 | {
32 | action = "fixed_ratio_sampler",
33 | sampling_ratio = 0.1,
34 | },
35 | -- {
36 | -- action = "intensity_to_color",
37 | -- min_intensity = 0.,
38 | -- max_intensity = 1.,
39 | -- },
40 | -- {
41 | -- action = "write_pcd",
42 | -- filename = "points.pcd",
43 | -- },
44 |
45 | -- Gray X-Rays. These only use geometry to color pixels.
46 | -- {
47 | -- action = "write_xray_image",
48 | -- voxel_size = VOXEL_SIZE,
49 | -- filename = "xray_yz_all",
50 | -- transform = YZ_TRANSFORM,
51 | -- },
52 | {
53 | action = "write_xray_image",
54 | voxel_size = VOXEL_SIZE,
55 | filename = "xray_xy_all",
56 | transform = XY_TRANSFORM,
57 | },
58 | -- {
59 | -- action = "write_xray_image",
60 | -- voxel_size = VOXEL_SIZE,
61 | -- filename = "xray_xz_all",
62 | -- transform = XZ_TRANSFORM,
63 | -- },
64 | -- {
65 | -- action = "write_probability_grid",
66 | -- draw_trajectories = true,
67 | -- resolution = 0.05,
68 | -- range_data_inserter = {
69 | -- insert_free_space = true,
70 | -- hit_probability = 0.55,
71 | -- miss_probability = 0.49,
72 | -- },
73 | -- filename = "probability_grid",
74 | -- },
75 | -- {
76 | -- action = "color_points",
77 | -- frame_id = "velo_link",
78 | -- color = { 255., 0., 0. },
79 | -- },
80 | --{
81 | -- action = "voxel_filter_and_remove_moving_objects",
82 | -- voxel_size = VOXEL_SIZE,
83 | --},
84 | -- {
85 | -- action = "write_xray_image",
86 | -- voxel_size = VOXEL_SIZE,
87 | -- filename = "xray_yz_all_color",
88 | -- transform = YZ_TRANSFORM,
89 | -- },
90 | -- {
91 | -- action = "write_xray_image",
92 | -- voxel_size = VOXEL_SIZE,
93 | -- filename = "xray_xy_all_color",
94 | -- transform = XY_TRANSFORM,
95 | -- },
96 | -- {
97 | -- action = "write_xray_image",
98 | -- voxel_size = VOXEL_SIZE,
99 | -- filename = "xray_xz_all_color",
100 | -- transform = XZ_TRANSFORM,
101 | -- },
102 | }
103 | }
104 |
105 | return options
106 |
--------------------------------------------------------------------------------
/configuration_files/kitti_3d_modi.lua:
--------------------------------------------------------------------------------
1 | -- Copyright 2016 The Cartographer Authors
2 | --
3 | -- Licensed under the Apache License, Version 2.0 (the "License");
4 | -- you may not use this file except in compliance with the License.
5 | -- You may obtain a copy of the License at
6 | --
7 | -- http://www.apache.org/licenses/LICENSE-2.0
8 | --
9 | -- Unless required by applicable law or agreed to in writing, software
10 | -- distributed under the License is distributed on an "AS IS" BASIS,
11 | -- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | -- See the License for the specific language governing permissions and
13 | -- limitations under the License.
14 |
15 | include "map_builder.lua"
16 | include "trajectory_builder.lua"
17 |
18 | options = {
19 | map_builder = MAP_BUILDER,
20 | trajectory_builder = TRAJECTORY_BUILDER,
21 | map_frame = "map",
22 | tracking_frame = "imu_link",
23 | published_frame = "base_link",
24 | odom_frame = "odom",
25 | provide_odom_frame = true,
26 | publish_frame_projected_to_2d = false,
27 | use_odometry = false,
28 | use_nav_sat = false,
29 | use_landmarks = false,
30 | num_laser_scans = 0,
31 | num_multi_echo_laser_scans = 0,
32 | num_subdivisions_per_laser_scan = 1,
33 | num_point_clouds = 1,
34 | lookup_transform_timeout_sec = 0.2,
35 | submap_publish_period_sec = 0.3,
36 | pose_publish_period_sec = 5e-3,
37 | trajectory_publish_period_sec = 30e-3,
38 | rangefinder_sampling_ratio = 1.,
39 | odometry_sampling_ratio = 1.,
40 | fixed_frame_pose_sampling_ratio = 1.,
41 | imu_sampling_ratio = 1.,
42 | landmarks_sampling_ratio = 1.,
43 | }
44 | -- ============================================
45 | -- TRAJECTORY_BUILDER_3D params (local SLAM)
46 | -- ============================================
47 | TRAJECTORY_BUILDER_3D.num_accumulated_range_data = 1
48 | TRAJECTORY_BUILDER_3D.ceres_scan_matcher.translation_weight = 5.
49 | TRAJECTORY_BUILDER_3D.use_online_correlative_scan_matching = true
50 | TRAJECTORY_BUILDER_3D.imu_gravity_time_constant = .1
51 | TRAJECTORY_BUILDER_3D.voxel_filter_size = 0.3
52 | --TRAJECTORY_BUILDER_3D.submaps.high_resolution = 0.2
53 | TRAJECTORY_BUILDER_3D.submaps.high_resolution = 0.2
54 | TRAJECTORY_BUILDER_3D.submaps.high_resolution_max_range = 50.
55 | -- TRAJECTORY_BUILDER_3D.submaps.num_range_data= 300.
56 |
57 |
58 | -- No point of trying to SLAM over the points on your car
59 | TRAJECTORY_BUILDER_3D.min_range = 1.0
60 | TRAJECTORY_BUILDER_3D.max_range = 100.
61 | TRAJECTORY_BUILDER_3D.motion_filter.max_time_seconds = 0.5
62 | TRAJECTORY_BUILDER_3D.motion_filter.max_distance_meters = 0.3
63 | TRAJECTORY_BUILDER_3D.motion_filter.max_angle_radians = math.rad(5.)
64 | TRAJECTORY_BUILDER_3D.ceres_scan_matcher.rotation_weight = 4.5e1 --4e1
65 | TRAJECTORY_BUILDER_3D.ceres_scan_matcher.translation_weight = 7 --6
66 | --TRAJECTORY_BUILDER_3D.ceres_scan_matcher.rotation_weight = 5 --2e1 --4e1
67 | --TRAJECTORY_BUILDER_3D.ceres_scan_matcher.translation_weight = 3 --6
68 |
69 | -- ============================================
70 | -- MAP_BUILDER params (trivial thing that switching 2D or 3D)
71 | -- ============================================
72 | MAP_BUILDER.use_trajectory_builder_3d = true
73 | MAP_BUILDER.num_background_threads = 8
74 |
75 | -- ============================================
76 | -- POSE_GRAPH params (global SLAM)
77 | -- ============================================
78 | -- The bigger the Huber scale, the higher is the impact of (potential) outliers.
79 | -- high huber scale allows more outliers with more noisy samples
80 | POSE_GRAPH.optimization_problem.huber_scale = 1e2
81 |
82 | --POSE_GRAPH.optimization_problem.rotation_weight = 6e5
83 | --POSE_GRAPH.optimize_every_n_nodes = 320
84 | POSE_GRAPH.optimize_every_n_nodes = 150
85 | -- POSE_GRAPH.global_constraint_search_after_n_seconds = 3.
86 | POSE_GRAPH.global_sampling_ratio = 0.1
87 |
88 | --POSE_GRAPH.constraint_builder.sampling_ratio = 0.03
89 | POSE_GRAPH.constraint_builder.sampling_ratio = 0.1
90 |
91 | POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 100
92 | --POSE_GRAPH.constraint_builder.min_score = 0.62
93 | POSE_GRAPH.constraint_builder.min_score = 0.45
94 |
95 | --POSE_GRAPH.constraint_builder.global_localization_min_score = 0.66
96 | POSE_GRAPH.constraint_builder.global_localization_min_score = 0.45
97 | POSE_GRAPH.constraint_builder.loop_closure_rotation_weight = 1e2
98 |
99 | POSE_GRAPH.constraint_builder.max_constraint_distance = 50.
100 | -- POSE_GRAPH.max_num_final_iterations=400
101 | POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.linear_xy_search_window = 25.
102 | POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.linear_z_search_window = 10.
103 | POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.angular_search_window = math.rad(15.)
104 |
105 | -- POSE_GRAPH.constraint_builder.ceres_scan_matcher.rotation_weight = 10.
106 |
107 | -- POSE_GRAPH.constraint_builder.min_score = 0.55
108 | -- POSE_GRAPH.constraint_builder.global_localization_min_score = 0.55
109 | POSE_GRAPH.optimization_problem.log_solver_summary = true
110 |
111 |
112 |
113 |
114 | return options
115 |
--------------------------------------------------------------------------------
/configuration_files/kitti_3d.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz/Displays
3 | Help Height: 78
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Global Options1
8 | - /Status1
9 | - /kitti_tf1/Frames1
10 | Splitter Ratio: 0.5
11 | Tree Height: 482
12 | - Class: rviz/Selection
13 | Name: Selection
14 | - Class: rviz/Tool Properties
15 | Expanded:
16 | - /2D Pose Estimate1
17 | - /2D Nav Goal1
18 | - /Publish Point1
19 | Name: Tool Properties
20 | Splitter Ratio: 0.588679016
21 | - Class: rviz/Views
22 | Expanded:
23 | - /Current View1
24 | Name: Views
25 | Splitter Ratio: 0.5
26 | - Class: rviz/Time
27 | Experimental: false
28 | Name: Time
29 | SyncMode: 0
30 | SyncSource: kitti_points2
31 | Visualization Manager:
32 | Class: ""
33 | Displays:
34 | - Alpha: 0.5
35 | Cell Size: 1
36 | Class: rviz/Grid
37 | Color: 160; 160; 164
38 | Enabled: true
39 | Line Style:
40 | Line Width: 0.0299999993
41 | Value: Lines
42 | Name: Grid
43 | Normal Cell Count: 0
44 | Offset:
45 | X: 0
46 | Y: 0
47 | Z: 0
48 | Plane: XY
49 | Plane Cell Count: 10
50 | Reference Frame:
51 | Value: true
52 | - Class: rviz/TF
53 | Enabled: true
54 | Frame Timeout: 15
55 | Frames:
56 | All Enabled: false
57 | base_link:
58 | Value: true
59 | camera_color_left:
60 | Value: false
61 | camera_color_right:
62 | Value: false
63 | camera_gray_left:
64 | Value: false
65 | camera_gray_right:
66 | Value: false
67 | imu_link:
68 | Value: true
69 | map:
70 | Value: true
71 | odom:
72 | Value: true
73 | velo_link:
74 | Value: false
75 | Marker Scale: 1
76 | Name: kitti_tf
77 | Show Arrows: true
78 | Show Axes: true
79 | Show Names: true
80 | Tree:
81 | map:
82 | odom:
83 | base_link:
84 | imu_link:
85 | camera_color_left:
86 | {}
87 | camera_color_right:
88 | {}
89 | camera_gray_left:
90 | {}
91 | camera_gray_right:
92 | {}
93 | velo_link:
94 | {}
95 | Update Interval: 0
96 | Value: true
97 | - Alpha: 1
98 | Autocompute Intensity Bounds: true
99 | Autocompute Value Bounds:
100 | Max Value: 10
101 | Min Value: -10
102 | Value: true
103 | Axis: Z
104 | Channel Name: intensity
105 | Class: rviz/PointCloud2
106 | Color: 255; 255; 255
107 | Color Transformer: Intensity
108 | Decay Time: 0
109 | Enabled: false
110 | Invert Rainbow: false
111 | Max Color: 255; 255; 255
112 | Max Intensity: 4096
113 | Min Color: 0; 0; 0
114 | Min Intensity: 0
115 | Name: kitti_points2
116 | Position Transformer: XYZ
117 | Queue Size: 10
118 | Selectable: true
119 | Size (Pixels): 3
120 | Size (m): 0.00999999978
121 | Style: Flat Squares
122 | Topic: points2
123 | Unreliable: false
124 | Use Fixed Frame: true
125 | Use rainbow: true
126 | Value: false
127 | - Class: Submaps
128 | Enabled: true
129 | Map frame: map
130 | Name: Submaps
131 | Submap query service: /submap_query
132 | Topic: ""
133 | Tracking frame: base_link
134 | Unreliable: false
135 | Value: true
136 | Enabled: true
137 | Global Options:
138 | Background Color: 48; 48; 48
139 | Fixed Frame: map
140 | Frame Rate: 30
141 | Name: root
142 | Tools:
143 | - Class: rviz/Interact
144 | Hide Inactive Objects: true
145 | - Class: rviz/MoveCamera
146 | - Class: rviz/Select
147 | - Class: rviz/FocusCamera
148 | - Class: rviz/Measure
149 | - Class: rviz/SetInitialPose
150 | Topic: /initialpose
151 | - Class: rviz/SetGoal
152 | Topic: /move_base_simple/goal
153 | - Class: rviz/PublishPoint
154 | Single click: true
155 | Topic: /clicked_point
156 | Value: true
157 | Views:
158 | Current:
159 | Class: rviz/Orbit
160 | Distance: 5.03893709
161 | Enable Stereo Rendering:
162 | Stereo Eye Separation: 0.0599999987
163 | Stereo Focal Distance: 1
164 | Swap Stereo Eyes: false
165 | Value: false
166 | Focal Point:
167 | X: -1.40499997
168 | Y: 0.319999993
169 | Z: 0.930000007
170 | Focal Shape Fixed Size: true
171 | Focal Shape Size: 0.0500000007
172 | Name: Current View
173 | Near Clip Distance: 0.00999999978
174 | Pitch: 0.375397623
175 | Target Frame: base_link
176 | Value: Orbit (rviz)
177 | Yaw: 0.192254454
178 | Saved: ~
179 | Window Geometry:
180 | Displays:
181 | collapsed: false
182 | Height: 787
183 | Hide Left Dock: false
184 | Hide Right Dock: false
185 | QMainWindow State: 000000ff00000000fd00000004000000000000023500000270fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005e00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000004100000270000000d000fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb000000140069006d006100670065005f006c00650066007401000001ce000000460000000000000000fb000000160069006d006100670065005f007200690067006800740100000205000000ac0000000000000000000000010000010f00000270fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004100000270000000a900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000077e0000003efc0100000002fb0000000800540069006d006501000000000000077e0000022400fffffffb0000000800540069006d006501000000000000045000000000000000000000042e0000027000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
186 | Selection:
187 | collapsed: false
188 | Time:
189 | collapsed: false
190 | Tool Properties:
191 | collapsed: false
192 | Views:
193 | collapsed: false
194 | Width: 1918
195 | X: 1920
196 | Y: 27
--------------------------------------------------------------------------------
/configuration_files/kitti_3d_new.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz/Displays
3 | Help Height: 78
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Status1
8 | - /kitti_tf1
9 | - /Submaps1
10 | - /MarkerArray1
11 | - /PointCloud21
12 | - /Map1
13 | Splitter Ratio: 0.5
14 | Tree Height: 1121
15 | - Class: rviz/Selection
16 | Name: Selection
17 | - Class: rviz/Tool Properties
18 | Expanded:
19 | - /2D Pose Estimate1
20 | - /2D Nav Goal1
21 | - /Publish Point1
22 | Name: Tool Properties
23 | Splitter Ratio: 0.588679016
24 | - Class: rviz/Views
25 | Expanded:
26 | - /Current View1
27 | Name: Views
28 | Splitter Ratio: 0.5
29 | - Class: rviz/Time
30 | Experimental: false
31 | Name: Time
32 | SyncMode: 0
33 | SyncSource: PointCloud2
34 | Visualization Manager:
35 | Class: ""
36 | Displays:
37 | - Alpha: 0.5
38 | Cell Size: 1
39 | Class: rviz/Grid
40 | Color: 160; 160; 164
41 | Enabled: true
42 | Line Style:
43 | Line Width: 0.0299999993
44 | Value: Lines
45 | Name: Grid
46 | Normal Cell Count: 0
47 | Offset:
48 | X: 0
49 | Y: 0
50 | Z: 0
51 | Plane: XY
52 | Plane Cell Count: 10
53 | Reference Frame:
54 | Value: true
55 | - Class: rviz/TF
56 | Enabled: true
57 | Frame Timeout: 15
58 | Frames:
59 | All Enabled: false
60 | base_link:
61 | Value: true
62 | camera_color_left:
63 | Value: false
64 | camera_color_right:
65 | Value: false
66 | camera_gray_left:
67 | Value: false
68 | camera_gray_right:
69 | Value: false
70 | imu_link:
71 | Value: true
72 | map:
73 | Value: true
74 | odom:
75 | Value: true
76 | velo_link:
77 | Value: false
78 | world:
79 | Value: true
80 | Marker Scale: 10
81 | Name: kitti_tf
82 | Show Arrows: true
83 | Show Axes: true
84 | Show Names: true
85 | Tree:
86 | map:
87 | odom:
88 | base_link:
89 | imu_link:
90 | camera_color_left:
91 | {}
92 | camera_color_right:
93 | {}
94 | camera_gray_left:
95 | {}
96 | camera_gray_right:
97 | {}
98 | velo_link:
99 | {}
100 | Update Interval: 0
101 | Value: true
102 | - Class: Submaps
103 | Enabled: false
104 | Fade-out distance: 1
105 | High Resolution: true
106 | Low Resolution: false
107 | Name: Submaps
108 | Submap query service: /submap_query
109 | Submaps:
110 | All: true
111 | Topic: ""
112 | Tracking frame: base_link
113 | Unreliable: false
114 | Value: false
115 | - Class: rviz/MarkerArray
116 | Enabled: true
117 | Marker Topic: /trajectory_node_list
118 | Name: MarkerArray
119 | Namespaces:
120 | Trajectory 0: true
121 | Queue Size: 100
122 | Value: true
123 | - Alpha: 0.5
124 | Autocompute Intensity Bounds: true
125 | Autocompute Value Bounds:
126 | Max Value: 186.708649
127 | Min Value: 88.7128525
128 | Value: true
129 | Axis: X
130 | Channel Name: intensity
131 | Class: rviz/PointCloud2
132 | Color: 255; 255; 255
133 | Color Transformer: AxisColor
134 | Decay Time: 20
135 | Enabled: true
136 | Invert Rainbow: false
137 | Max Color: 255; 255; 255
138 | Max Intensity: 4096
139 | Min Color: 0; 0; 0
140 | Min Intensity: 0
141 | Name: PointCloud2
142 | Position Transformer: XYZ
143 | Queue Size: 10
144 | Selectable: true
145 | Size (Pixels): 1
146 | Size (m): 0.100000001
147 | Style: Points
148 | Topic: /scan_matched_points2
149 | Unreliable: false
150 | Use Fixed Frame: true
151 | Use rainbow: true
152 | Value: true
153 | - Alpha: 0.699999988
154 | Class: rviz/Map
155 | Color Scheme: map
156 | Draw Behind: false
157 | Enabled: false
158 | Name: Map
159 | Topic: /map
160 | Unreliable: false
161 | Use Timestamp: false
162 | Value: false
163 | Enabled: true
164 | Global Options:
165 | Background Color: 48; 48; 48
166 | Default Light: true
167 | Fixed Frame: map
168 | Frame Rate: 30
169 | Name: root
170 | Tools:
171 | - Class: rviz/Interact
172 | Hide Inactive Objects: true
173 | - Class: rviz/MoveCamera
174 | - Class: rviz/Select
175 | - Class: rviz/FocusCamera
176 | - Class: rviz/Measure
177 | - Class: rviz/SetInitialPose
178 | Topic: /initialpose
179 | - Class: rviz/SetGoal
180 | Topic: /move_base_simple/goal
181 | - Class: rviz/PublishPoint
182 | Single click: true
183 | Topic: /clicked_point
184 | Value: true
185 | Views:
186 | Current:
187 | Class: rviz/Orbit
188 | Distance: 205.348877
189 | Enable Stereo Rendering:
190 | Stereo Eye Separation: 0.0599999987
191 | Stereo Focal Distance: 1
192 | Swap Stereo Eyes: false
193 | Value: false
194 | Focal Point:
195 | X: -4.02356291
196 | Y: 14.5377712
197 | Z: 11.0499058
198 | Focal Shape Fixed Size: true
199 | Focal Shape Size: 0.0500000007
200 | Invert Z Axis: false
201 | Name: Current View
202 | Near Clip Distance: 0.00999999978
203 | Pitch: 0.189795732
204 | Target Frame: base_link
205 | Value: Orbit (rviz)
206 | Yaw: 3.79039717
207 | Saved: ~
208 | Window Geometry:
209 | Displays:
210 | collapsed: false
211 | Height: 1456
212 | Hide Left Dock: false
213 | Hide Right Dock: false
214 | QMainWindow State: 000000ff00000000fd00000004000000000000023500000502fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006800fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003500000502000000e900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb000000140069006d006100670065005f006c00650066007401000001ce000000460000000000000000fb000000160069006d006100670065005f007200690067006800740100000205000000ac0000000000000000000000010000013a00000502fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003500000502000000ca00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000008a20000004afc0100000002fb0000000800540069006d00650100000000000008a20000046500fffffffb0000000800540069006d00650100000000000004500000000000000000000005210000050200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
215 | Selection:
216 | collapsed: false
217 | Time:
218 | collapsed: false
219 | Tool Properties:
220 | collapsed: false
221 | Views:
222 | collapsed: false
223 | Width: 2210
224 | X: 3008
225 | Y: 45
226 |
--------------------------------------------------------------------------------
/configuration_files/kitti_3d_for_debug.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz/Displays
3 | Help Height: 78
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Status1
8 | - /kitti_tf1
9 | - /Submaps1
10 | - /PointCloud21
11 | - /Map1
12 | - /Constraints1
13 | - /Constraints1/Namespaces1
14 | Splitter Ratio: 0.774545431
15 | Tree Height: 721
16 | - Class: rviz/Selection
17 | Name: Selection
18 | - Class: rviz/Tool Properties
19 | Expanded:
20 | - /2D Pose Estimate1
21 | - /2D Nav Goal1
22 | - /Publish Point1
23 | Name: Tool Properties
24 | Splitter Ratio: 0.588679016
25 | - Class: rviz/Views
26 | Expanded:
27 | - /Current View1
28 | Name: Views
29 | Splitter Ratio: 0.5
30 | - Class: rviz/Time
31 | Experimental: false
32 | Name: Time
33 | SyncMode: 0
34 | SyncSource: PointCloud2
35 | Visualization Manager:
36 | Class: ""
37 | Displays:
38 | - Alpha: 0.5
39 | Cell Size: 1
40 | Class: rviz/Grid
41 | Color: 160; 160; 164
42 | Enabled: true
43 | Line Style:
44 | Line Width: 0.0299999993
45 | Value: Lines
46 | Name: Grid
47 | Normal Cell Count: 0
48 | Offset:
49 | X: 0
50 | Y: 0
51 | Z: 0
52 | Plane: XY
53 | Plane Cell Count: 10
54 | Reference Frame:
55 | Value: true
56 | - Class: rviz/TF
57 | Enabled: true
58 | Frame Timeout: 15
59 | Frames:
60 | All Enabled: false
61 | base_link:
62 | Value: true
63 | camera_color_left:
64 | Value: false
65 | camera_color_right:
66 | Value: false
67 | camera_gray_left:
68 | Value: false
69 | camera_gray_right:
70 | Value: false
71 | imu_link:
72 | Value: true
73 | map:
74 | Value: true
75 | odom:
76 | Value: true
77 | velo_link:
78 | Value: false
79 | Marker Scale: 10
80 | Name: kitti_tf
81 | Show Arrows: true
82 | Show Axes: true
83 | Show Names: true
84 | Tree:
85 | map:
86 | odom:
87 | base_link:
88 | imu_link:
89 | camera_color_left:
90 | {}
91 | camera_color_right:
92 | {}
93 | camera_gray_left:
94 | {}
95 | camera_gray_right:
96 | {}
97 | velo_link:
98 | {}
99 | Update Interval: 0
100 | Value: true
101 | - Class: Submaps
102 | Enabled: false
103 | Fade-out distance: 1
104 | High Resolution: true
105 | Low Resolution: false
106 | Name: Submaps
107 | Submap query service: /submap_query
108 | Submaps:
109 | All: true
110 | Topic: ""
111 | Tracking frame: base_link
112 | Unreliable: false
113 | Value: false
114 | - Class: rviz/MarkerArray
115 | Enabled: true
116 | Marker Topic: /trajectory_node_list
117 | Name: MarkerArray
118 | Namespaces:
119 | Trajectory 0: true
120 | Queue Size: 100
121 | Value: true
122 | - Alpha: 0.5
123 | Autocompute Intensity Bounds: true
124 | Autocompute Value Bounds:
125 | Max Value: 138.32843
126 | Min Value: 7.30563641
127 | Value: true
128 | Axis: X
129 | Channel Name: intensity
130 | Class: rviz/PointCloud2
131 | Color: 255; 255; 255
132 | Color Transformer: AxisColor
133 | Decay Time: 0
134 | Enabled: true
135 | Invert Rainbow: false
136 | Max Color: 255; 255; 255
137 | Max Intensity: 4096
138 | Min Color: 0; 0; 0
139 | Min Intensity: 0
140 | Name: PointCloud2
141 | Position Transformer: XYZ
142 | Queue Size: 10
143 | Selectable: true
144 | Size (Pixels): 1
145 | Size (m): 0.100000001
146 | Style: Points
147 | Topic: /scan_matched_points2
148 | Unreliable: false
149 | Use Fixed Frame: true
150 | Use rainbow: true
151 | Value: true
152 | - Alpha: 0.699999988
153 | Class: rviz/Map
154 | Color Scheme: map
155 | Draw Behind: false
156 | Enabled: true
157 | Name: Map
158 | Topic: /map
159 | Unreliable: false
160 | Use Timestamp: false
161 | Value: true
162 | - Class: rviz/MarkerArray
163 | Enabled: false
164 | Marker Topic: /constraint_list
165 | Name: Constraints
166 | Namespaces:
167 | {}
168 | Queue Size: 0
169 | Value: false
170 | Enabled: true
171 | Global Options:
172 | Background Color: 48; 48; 48
173 | Default Light: true
174 | Fixed Frame: map
175 | Frame Rate: 30
176 | Name: root
177 | Tools:
178 | - Class: rviz/Interact
179 | Hide Inactive Objects: true
180 | - Class: rviz/MoveCamera
181 | - Class: rviz/Select
182 | - Class: rviz/FocusCamera
183 | - Class: rviz/Measure
184 | - Class: rviz/SetInitialPose
185 | Topic: /initialpose
186 | - Class: rviz/SetGoal
187 | Topic: /move_base_simple/goal
188 | - Class: rviz/PublishPoint
189 | Single click: true
190 | Topic: /clicked_point
191 | Value: true
192 | Views:
193 | Current:
194 | Class: rviz/Orbit
195 | Distance: 395.659119
196 | Enable Stereo Rendering:
197 | Stereo Eye Separation: 0.0599999987
198 | Stereo Focal Distance: 1
199 | Swap Stereo Eyes: false
200 | Value: false
201 | Focal Point:
202 | X: -10.9525146
203 | Y: -83.6695404
204 | Z: 11.0420084
205 | Focal Shape Fixed Size: true
206 | Focal Shape Size: 0.0500000007
207 | Invert Z Axis: false
208 | Name: Current View
209 | Near Clip Distance: 0.00999999978
210 | Pitch: 1.56979632
211 | Target Frame: base_link
212 | Value: Orbit (rviz)
213 | Yaw: 3.08539605
214 | Saved: ~
215 | Window Geometry:
216 | Displays:
217 | collapsed: false
218 | Height: 1056
219 | Hide Left Dock: false
220 | Hide Right Dock: false
221 | QMainWindow State: 000000ff00000000fd00000004000000000000023500000372fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006800fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003500000372000000e900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb000000140069006d006100670065005f006c00650066007401000001ce000000460000000000000000fb000000160069006d006100670065005f007200690067006800740100000205000000ac0000000000000000000000010000013a00000372fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003500000372000000ca00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000004afc0100000002fb0000000800540069006d006501000000000000073f0000046500fffffffb0000000800540069006d00650100000000000004500000000000000000000003be0000037200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
222 | Selection:
223 | collapsed: false
224 | Time:
225 | collapsed: false
226 | Tool Properties:
227 | collapsed: false
228 | Views:
229 | collapsed: false
230 | Width: 1855
231 | X: 2945
232 | Y: 24
233 |
--------------------------------------------------------------------------------
/configuration_files/kitti_3d_rgb.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz/Displays
3 | Help Height: 0
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Global Options1
8 | - /Status1
9 | - /kitti_tf1
10 | - /Submaps1
11 | - /MarkerArray1
12 | - /PointCloud21
13 | - /Map1
14 | - /Image1
15 | - /Image2
16 | Splitter Ratio: 0.5
17 | Tree Height: 169
18 | - Class: rviz/Selection
19 | Name: Selection
20 | - Class: rviz/Tool Properties
21 | Expanded:
22 | - /2D Pose Estimate1
23 | - /2D Nav Goal1
24 | - /Publish Point1
25 | Name: Tool Properties
26 | Splitter Ratio: 0.588679016
27 | - Class: rviz/Views
28 | Expanded:
29 | - /Current View1
30 | Name: Views
31 | Splitter Ratio: 0.5
32 | - Class: rviz/Time
33 | Experimental: false
34 | Name: Time
35 | SyncMode: 0
36 | SyncSource: PointCloud2
37 | Visualization Manager:
38 | Class: ""
39 | Displays:
40 | - Alpha: 0.5
41 | Cell Size: 1
42 | Class: rviz/Grid
43 | Color: 160; 160; 164
44 | Enabled: true
45 | Line Style:
46 | Line Width: 0.0299999993
47 | Value: Lines
48 | Name: Grid
49 | Normal Cell Count: 0
50 | Offset:
51 | X: 0
52 | Y: 0
53 | Z: 0
54 | Plane: XY
55 | Plane Cell Count: 10
56 | Reference Frame:
57 | Value: true
58 | - Class: rviz/TF
59 | Enabled: true
60 | Frame Timeout: 15
61 | Frames:
62 | All Enabled: false
63 | base_link:
64 | Value: true
65 | camera_color_left:
66 | Value: false
67 | camera_color_right:
68 | Value: false
69 | camera_gray_left:
70 | Value: false
71 | camera_gray_right:
72 | Value: false
73 | imu_link:
74 | Value: true
75 | map:
76 | Value: true
77 | odom:
78 | Value: true
79 | velo_link:
80 | Value: false
81 | Marker Scale: 10
82 | Name: kitti_tf
83 | Show Arrows: true
84 | Show Axes: true
85 | Show Names: true
86 | Tree:
87 | map:
88 | odom:
89 | base_link:
90 | imu_link:
91 | camera_color_left:
92 | {}
93 | camera_color_right:
94 | {}
95 | camera_gray_left:
96 | {}
97 | camera_gray_right:
98 | {}
99 | velo_link:
100 | {}
101 | Update Interval: 0
102 | Value: true
103 | - Class: Submaps
104 | Enabled: false
105 | Fade-out distance: 1
106 | High Resolution: true
107 | Low Resolution: false
108 | Name: Submaps
109 | Submap query service: /submap_query
110 | Submaps:
111 | All: true
112 | Topic: ""
113 | Tracking frame: base_link
114 | Unreliable: false
115 | Value: false
116 | - Class: rviz/MarkerArray
117 | Enabled: true
118 | Marker Topic: /trajectory_node_list
119 | Name: MarkerArray
120 | Namespaces:
121 | Trajectory 0: true
122 | Queue Size: 100
123 | Value: true
124 | - Alpha: 0.5
125 | Autocompute Intensity Bounds: true
126 | Autocompute Value Bounds:
127 | Max Value: -56.8210487
128 | Min Value: -98.0887756
129 | Value: true
130 | Axis: X
131 | Channel Name: intensity
132 | Class: rviz/PointCloud2
133 | Color: 150; 255; 29
134 | Color Transformer: FlatColor
135 | Decay Time: 60
136 | Enabled: true
137 | Invert Rainbow: false
138 | Max Color: 255; 255; 255
139 | Max Intensity: 4096
140 | Min Color: 0; 0; 0
141 | Min Intensity: 0
142 | Name: PointCloud2
143 | Position Transformer: XYZ
144 | Queue Size: 10
145 | Selectable: true
146 | Size (Pixels): 1
147 | Size (m): 0.100000001
148 | Style: Points
149 | Topic: /scan_matched_points2
150 | Unreliable: false
151 | Use Fixed Frame: true
152 | Use rainbow: true
153 | Value: true
154 | - Alpha: 0.699999988
155 | Class: rviz/Map
156 | Color Scheme: map
157 | Draw Behind: false
158 | Enabled: true
159 | Name: Map
160 | Topic: /map
161 | Unreliable: false
162 | Use Timestamp: false
163 | Value: true
164 | - Class: rviz/Image
165 | Enabled: true
166 | Image Topic: /kitti/camera_gray_left/image_raw
167 | Max Value: 1
168 | Median window: 5
169 | Min Value: 0
170 | Name: Image
171 | Normalize Range: true
172 | Queue Size: 2
173 | Transport Hint: raw
174 | Unreliable: false
175 | Value: true
176 | - Class: rviz/Image
177 | Enabled: true
178 | Image Topic: /kitti/camera_color_right/image_raw
179 | Max Value: 1
180 | Median window: 5
181 | Min Value: 0
182 | Name: Image
183 | Normalize Range: true
184 | Queue Size: 2
185 | Transport Hint: raw
186 | Unreliable: false
187 | Value: true
188 | Enabled: true
189 | Global Options:
190 | Background Color: 0; 0; 0
191 | Default Light: true
192 | Fixed Frame: map
193 | Frame Rate: 30
194 | Name: root
195 | Tools:
196 | - Class: rviz/Interact
197 | Hide Inactive Objects: true
198 | - Class: rviz/MoveCamera
199 | - Class: rviz/Select
200 | - Class: rviz/FocusCamera
201 | - Class: rviz/Measure
202 | - Class: rviz/SetInitialPose
203 | Topic: /initialpose
204 | - Class: rviz/SetGoal
205 | Topic: /move_base_simple/goal
206 | - Class: rviz/PublishPoint
207 | Single click: true
208 | Topic: /clicked_point
209 | Value: true
210 | Views:
211 | Current:
212 | Class: rviz/Orbit
213 | Distance: 96.6988831
214 | Enable Stereo Rendering:
215 | Stereo Eye Separation: 0.0599999987
216 | Stereo Focal Distance: 1
217 | Swap Stereo Eyes: false
218 | Value: false
219 | Focal Point:
220 | X: 12.7641706
221 | Y: 7.3783226
222 | Z: -19.8025017
223 | Focal Shape Fixed Size: true
224 | Focal Shape Size: 0.0500000007
225 | Invert Z Axis: false
226 | Name: Current View
227 | Near Clip Distance: 0.00999999978
228 | Pitch: 0.809797168
229 | Target Frame: base_link
230 | Value: Orbit (rviz)
231 | Yaw: 3.80414748
232 | Saved: ~
233 | Window Geometry:
234 | Displays:
235 | collapsed: false
236 | Height: 855
237 | Hide Left Dock: false
238 | Hide Right Dock: false
239 | Image:
240 | collapsed: false
241 | QMainWindow State: 000000ff00000000fd000000040000000000000253000002defc020000000cfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006800fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730000000000000000fc000000e900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb000000140069006d006100670065005f006c00650066007401000001ce000000460000000000000000fb000000160069006d006100670065005f007200690067006800740100000205000000ac0000000000000000fb0000000a0049006d0061006700650100000000000001580000001d00fffffffb0000000a0049006d00610067006501000001610000017d0000001d00ffffff000000010000013a0000034ffc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000350000034f000000ca00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000064d0000004afc0100000002fb0000000800540069006d006501000000000000064d0000046500fffffffb0000000800540069006d00650100000000000004500000000000000000000003f1000002de00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730000000000ffffffff0000000000000000
242 | Selection:
243 | collapsed: false
244 | Time:
245 | collapsed: false
246 | Tool Properties:
247 | collapsed: false
248 | Views:
249 | collapsed: false
250 | Width: 1613
251 | X: 2982
252 | Y: 57
253 |
--------------------------------------------------------------------------------