/
in_bin_each_object.launch
52 lines (44 loc) · 1.99 KB
/
in_bin_each_object.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
<launch>
<arg name="BIN_NAME" />
<arg name="INPUT_CLOUD" />
<include file="$(find jsk_apc2015_common)/launch/kiva_pod_filter.launch">
<arg name="INPUT_CLOUD" value="$(arg INPUT_CLOUD)" />
<arg name="OUTPUT_CLOUD" value="$(arg INPUT_CLOUD)_pod_filtered" />
</include>
<node name="bin_clipper"
pkg="nodelet" type="nodelet"
args="standalone jsk_pcl/AttentionClipper">
<remap from="~input/points" to="$(arg INPUT_CLOUD)_pod_filtered" />
<rosparam>
use_multiple_attention: true
initial_pos_list: [[-0.21, 0.29, 0.36], [-0.21, 0, 0.36], [-0.21, -0.29, 0.36], [-0.21, 0.29, 0.11], [-0.21, 0, 0.11], [-0.21, -0.29, 0.11]]
initial_rot_list: [[0,0,0], [0,0,0], [0,0,0], [0,0,0], [0,0,0], [0,0,0]]
dimensions: [[0.37, 0.25, 0.22],[0.37, 0.29, 0.22],[0.37, 0.25, 0.22], [0.37, 0.25, 0.22],[0.37, 0.29, 0.22],[0.37, 0.25, 0.22]]
frame_id_list: [kiva_pod_base, kiva_pod_base, kiva_pod_base, kiva_pod_base, kiva_pod_base, kiva_pod_base]
prefixes: [bin_a, bin_b, bin_c, bin_d, bin_e, bin_f]
</rosparam>
</node>
<node name="bin_$(arg BIN_NAME)_extract_pi"
pkg="nodelet" type="nodelet"
args="standalone jsk_pcl/ExtractIndices">
<remap from="~input" to="$(arg INPUT_CLOUD)_pod_filtered" />
<remap from="~indices" to="bin_clipper/bin_$(arg BIN_NAME)/point_indices" />
<rosparam>
keep_organized: true
</rosparam>
</node>
<node name="bin_$(arg BIN_NAME)_euclid_clustering"
pkg="nodelet" type="nodelet"
args="standalone jsk_pcl/EuclideanClustering">
<remap from="~input" to="bin_$(arg BIN_NAME)_extract_pi/output" />
<rosparam>
max_size: 100000
</rosparam>
</node>
<node name="bin_$(arg BIN_NAME)_cpi_decomposer"
pkg="nodelet" type="nodelet"
args="standalone jsk_pcl/ClusterPointIndicesDecomposer">
<remap from="~input" to="bin_$(arg BIN_NAME)_extract_pi/output" />
<remap from="~target" to="bin_$(arg BIN_NAME)_euclid_clustering/output" />
</node>
</launch>