forked from atenpas/gpd
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathur5_15_channels.launch
70 lines (54 loc) · 3.02 KB
/
ur5_15_channels.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
<launch>
<!-- Load hand geometry parameters -->
<include file="$(find gpd)/launch/ur5_hand_geometry.launch">
<arg name="node" value="detect_grasps" />
</include>
<!-- Load classifier parameters -->
<include file="$(find gpd)/launch/caffe/ur5_classifier_15channels.launch">
<arg name="node" value="detect_grasps" />
</include>
<node name="detect_grasps" pkg="gpd" type="detect_grasps" output="screen">
<!-- If sequential importance sampling is used (default: false) -->
<param name="use_importance_sampling" value="false" />
<!-- What type of point cloud is used and what ROS topic it comes from -->
<param name="cloud_type" value="2" /> <!-- 0: PointCloud2, 1: CloudIndexed, 2: CloudSamples -->
<param name="cloud_topic" value="/cloud_stitched" />
<!-- (optional) The ROS topic that the samples come from (default: an empty string) -->
<param name="samples_topic" value="" />
<!-- Plotting parameters -->
<param name="plot_normals" value="false" />
<param name="plot_samples" value="false" />
<param name="plot_candidates" value="false" />
<param name="plot_filtered_grasps" value="false" />
<param name="plot_valid_grasps" value="false" />
<param name="plot_clusters" value="false" />
<param name="plot_selected_grasps" value="false" />
<!-- Preprocessing of point cloud -->
<param name="voxelize" value="false"/>
<param name="remove_outliers" value="false"/>
<!--<rosparam param="workspace"> [0.4, 0.5, 0.00, 0.20, 0, 0.1] </rosparam>-->
<!--<rosparam param="workspace"> [0.30, 0.90, -0.30, 0.30, -0.12, 0.40] </rosparam>-->
<rosparam param="workspace"> [-1, 1, -1, 1, -1, 1] </rosparam>
<rosparam param="camera_position"> [0, 0, 0] </rosparam>
<!-- General parameters -->
<param name="num_samples" value="1000" />
<param name="num_threads" value="8" />
<!-- Parameters for local grasp candidate search -->
<param name="nn_radius" value="0.01" />
<param name="num_orientations" value="8" /> <!-- Number of orientations to consider -->
<!-- Filtering of grasp candidates -->
<param name="filter_grasps" value="false" /> <!-- on workspace and robot hand aperture -->
<rosparam param="workspace_grasps"> [0.30, 0.90, -0.30, 0.30, -0.12, 0.40] </rosparam>
<param name="filter_half_antipodal" value="false"/> <!-- on half antipodal -->
<!-- Grasp image creation -->
<param name="create_image_batches" value="false" /> <!-- creates grasp images in batches (less memory usage) -->
<param name="remove_plane_before_image_calculation" value="true" /> <!-- removes table plane from point cloud to speed up shadow computations -->
<!-- Clustering of grasps -->
<param name="min_inliers" value="0" />
<!-- Grasp selection -->
<param name="min_score_diff" value="50" />
<param name="min_aperture" value="0.0" />
<param name="max_aperture" value="0.085" />
<param name="num_selected" value="100" />
</node>
</launch>