This repository was archived by the owner on Jan 25, 2022. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 3
Expand file tree
/
Copy pathpreprocess.launch
More file actions
112 lines (100 loc) · 6.1 KB
/
preprocess.launch
File metadata and controls
112 lines (100 loc) · 6.1 KB
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
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
<launch>
<rosparam file="$(find objsearch_toplevel)/config/global_params.yaml" command="load" />
<!-- Input/output parameters -->
<arg name="output" default="NULL" />
<param name="/preprocess/output_dir" value="$(arg output)" />
<arg name="cloud" />
<param name="/preprocess/cloud" value="$(arg cloud)" />
<!-- Use this to set an offset on the index of clouds to preprocess, useful if
something crashes in the middle of a preprocessing run on lots of files -->
<arg name="cloud_offset" default="0"/>
<param name="/preprocess/cloud_offset" value="$(arg cloud_offset)" />
<!-- Use this when a directory is passed to cloud - the clouds which contain
the given string will be processed -->
<arg name="match" default="NULL"/>
<param name="/preprocess/match" value="$(arg match)" />
<!-- Parameters defining the behaviour of RANSAC and plane extraction -->
<arg name="distance_threshold" default="0.05" />
<param name="/preprocess/RANSAC_distance_threshold" value="$(arg distance_threshold)" />
<arg name="iterations" default="300" />
<param name="/preprocess/RANSAC_iterations" value="$(arg iterations)" />
<!-- The maximum number of planes to extract. Depending on the cloud structure
and min_plane_prop, a smaller number may be extracted. -->
<arg name="planes_to_extract" default="10" />
<param name="/preprocess/planes_to_extract" value="$(arg planes_to_extract)" />
<!-- A plane must have at least cloud.npoints * min_plane_prop points in it to
be considered. The full room clouds have about 13,000,000 points when not
downsampled. With downsampling of 0.01 leaf size, this is reduced to
around 10% of that -->
<arg name="min_plane_prop_complete" default="0.02" />
<param name="/preprocess/min_plane_prop_complete" value="$(arg min_plane_prop_complete)" />
<arg name="min_plane_prop_intermediate" default="0.05" />
<param name="/preprocess/min_plane_prop_intermediate" value="$(arg min_plane_prop_intermediate)" />
<!-- Additional minimum limit on the number of points in an extracted plane.
The final minimum is the larger value of this and min_plane_prop *
cloud.size -->
<arg name="min_plane_points_complete" default="20000" />
<param name="/preprocess/min_plane_points_complete" value="$(arg min_plane_points_complete)" />
<arg name="min_plane_points_intermediate" default="4500" />
<param name="/preprocess/min_plane_points_intermediate" value="$(arg min_plane_points_intermediate)" />
<!-- The maximum number of times in a row that plane extraction can be skipped
before it is abandoned -->
<arg name="plane_skip_limit" default="2" />
<param name="/preprocess/plane_skip_limit" value="$(arg plane_skip_limit)" />
<!-- Save individual planes extracted or just the combined cloud of all the planes? -->
<arg name="planesave" default="false"/>
<param name="/preprocess/save_planes" value="$(arg planesave)" />
<!-- These values are used to further adjust the floor and ceiling z-value
which is used to remove points which make up those parts of the cloud -->
<arg name="ceiling_offset" default="0.2" />
<param name="/preprocess/ceiling_offset" value="$(arg ceiling_offset)" />
<arg name="floor_offset" default="0.2" />
<param name="/preprocess/floor_offset" value="$(arg floor_offset)" />
<!-- Additional cutoffs that can be used to filter points in the cloud. These
filters are applied after the cloud is transformed -->
<!-- Set to true to perform additional filtering -->
<arg name="filter_y" default="false" />
<param name="/preprocess/filter_y" value="$(arg filter_y)" />
<arg name="y_filter_max" default="NULL" />
<param name="/preprocess/y_filter_max" value="$(arg y_filter_max)" />
<arg name="y_filter_min" default="NULL" />
<param name="/preprocess/y_filter_min" value="$(arg y_filter_min)" />
<!-- Set this to true to perform the filtering -->
<arg name="filter_x" default="true" />
<param name="/preprocess/filter_x" value="$(arg filter_x)" />
<!-- Defaults are set for the annotated dataset -->
<arg name="x_filter_max" default="-1" />
<param name="/preprocess/x_filter_max" value="$(arg x_filter_max)" />
<arg name="x_filter_min" default="-10" />
<param name="/preprocess/x_filter_min" value="$(arg x_filter_min)" />
<!-- Normal computation parameters. A larger radius means that regions with
high rate of change of the normal are likely to be smoothed over-->
<arg name="normal_radius_plane" default="0.08" />
<param name="/preprocess/normal_radius_plane" value="$(arg normal_radius_plane)" />
<!-- Compute a separate set of normals for use when computing features, with a
smaller radius -->
<arg name="normal_radius_feature" default="0.03" />
<param name="/preprocess/normal_radius_feature" value="$(arg normal_radius_feature)" />
<!-- Downsampling parameters -->
<!-- Size to use for all dimensions in the voxel grid -->
<arg name="downsample_leafsize" default="0.01"/>
<param name="/preprocess/downsample_leafsize" value="$(arg downsample_leafsize)" />
<!-- Sometimes the voxel grid downsampling doesn't work due to an overflow
(PCL 1.7.1). Still need to downsample, so mitigate this by trying again
and increasing the leafsize by this amount until it actually works. -->
<arg name="downsample_increment" default="0.005"/>
<param name="/preprocess/downsample_increment" value="$(arg downsample_increment)" />
<!-- Parameters to define whether or not some parts of the preprocessing are
carried out -->
<arg name="downsample" default="true"/>
<param name="/preprocess/downsample" value="$(arg downsample)" />
<arg name="planes" default="true"/>
<param name="/preprocess/extract_planes" value="$(arg planes)" />
<arg name="trim" default="true"/>
<param name="/preprocess/trim_cloud" value="$(arg trim)" />
<arg name="annotations" default="true"/>
<param name="/preprocess/rotate_annotations" value="$(arg annotations)" />
<arg name="normals" default="true"/>
<param name="/preprocess/compute_normals" value="$(arg normals)" />
<node name="preprocess" pkg="preprocess" type="preprocess" output="screen" required="true"/>
</launch>