-
Notifications
You must be signed in to change notification settings - Fork 2
/
pointcloud_registration.launch
127 lines (109 loc) · 10.9 KB
/
pointcloud_registration.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
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
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="ambient_pointcloud_topic" default="/camera/depth_registered/points" />
<arg name="use_cloud_storage_mode" default="false" />
<arg name="use_voxel_grid_segmentation_in_cloud_storage_mode" default="true" />
<arg name="use_random_sample_segmentation_in_cloud_storage_mode" default="false" />
<arg name="use_voxel_grid" default="true" />
<arg name="use_random_sample" default="false" />
<arg name="use_noise_removal" default="false" />
<arg name="use_normal_estimation" default="true" />
<arg name="use_plane_segmentation" default="false" />
<arg name="use_euclidean_clustering_segmentation" default="true" />
<arg name="use_pca_for_initial_alignment" default="true" />
<arg name="use_feature_matching_for_initial_alignment" default="false" />
<arg name="load_initial_pose_estimation_pipeline_using_pca" default="$(eval use_pca_for_initial_alignment and not use_feature_matching_for_initial_alignment)" />
<arg name="use_cloud_matching" default="true" />
<arg name="use_iterative_closest_point_with_normals" default="true" />
<arg name="use_curvature_estimation" default="$(arg use_feature_matching_for_initial_alignment)" />
<arg name="use_transformation_aligner" default="false" />
<arg name="use_object_model_caching" default="false"/>
<arg name="cloud_matching_timeout_for_intermediate_alignment" default="10.0" />
<arg name="cloud_matching_timeout_for_final_alignment" default="5.0" />
<arg name="number_of_recognition_retries" default="3"/>
<arg name="sensor_frame_id" default="camera_link" />
<arg name="base_link_frame_id" default="base_link" />
<arg name="correction_frame_id" default="registration_correction" />
<arg name="object_frame_id_for_transforming_pointclouds" default="$(arg base_link_frame_id)" />
<arg name="object_frame_id_for_publishing_pointclouds" default="$(arg base_link_frame_id)" />
<arg name="reference_pointcloud_filename" default="" />
<arg name="reference_pointclouds_database_folder_path" default="$(find pointcloud_registration)/models/" />
<arg name="max_registration_outliers" default="0.33" />
<arg name="max_registration_outliers_reference_pointcloud" default="0.7" />
<arg name="yaml_configuration_configs_filename" default="$(find object_recognition_skill_server)/yaml/configs.yaml" />
<arg name="yaml_configuration_filters_roi_filename" default="$(find pointcloud_registration)/yaml/filters_roi.yaml" />
<arg name="yaml_configuration_filters_voxel_grid_filename" default="$(find pointcloud_registration)/yaml/filters_voxel_grid.yaml" />
<arg name="yaml_configuration_filters_noise_removal_filename" default="$(find object_recognition_skill_server)/yaml/filters_noise_removal.yaml" />
<arg name="yaml_configuration_filters_plane_segmentation_filename" default="$(find object_recognition_skill_server)/yaml/filters_plane_segmentation.yaml" />
<arg name="yaml_configuration_filters_euclidean_clustering_filename" default="$(find pointcloud_registration)/yaml/filters_euclidean_clustering.yaml" />
<arg name="yaml_configuration_normal_estimators_filename" default="$(find object_recognition_skill_server)/yaml/normal_estimators.yaml" />
<arg name="yaml_configuration_initial_pose_estimators_feature_matchers_filename" default="$(find pointcloud_registration)/yaml/initial_pose_estimators_feature_matchers.yaml" />
<arg name="yaml_configuration_initial_pose_estimators_pca_matchers_filename" default="$(find object_recognition_skill_server)/yaml/initial_pose_estimators_pca_matchers.yaml" if="$(eval base_link_frame_id == 'camera_link')" />
<arg name="yaml_configuration_initial_pose_estimators_pca_matchers_filename" default="$(find object_recognition_skill_server)/yaml/initial_pose_estimators_pca_matchers_with_base_link_axes_flip.yaml" unless="$(eval base_link_frame_id == 'camera_link')" />
<arg name="yaml_configuration_initial_pose_estimators_point_matchers_filename" default="$(find pointcloud_registration)/yaml/initial_pose_estimators_point_matchers.yaml" if="$(arg use_iterative_closest_point_with_normals)" />
<arg name="yaml_configuration_initial_pose_estimators_point_matchers_filename" default="$(find object_recognition_skill_server)/yaml/initial_pose_estimators_point_matchers.yaml" unless="$(arg use_iterative_closest_point_with_normals)" />
<arg name="yaml_configuration_outlier_detectors_filename" default="$(find pointcloud_registration)/yaml/outlier_detectors.yaml" />
<arg name="yaml_configuration_transformation_validators_filename" default="$(find pointcloud_registration)/yaml/transformation_validators.yaml" />
<arg name="yaml_configuration_custom_filename" default="" /> <!-- extra custom configurations -->
<arg name="point_matcher_intermediate_ns" default="2_iterative_closest_point_with_normals" if="$(arg use_iterative_closest_point_with_normals)" />
<arg name="point_matcher_intermediate_ns" default="2_iterative_closest_point" unless="$(arg use_iterative_closest_point_with_normals)" />
<arg name="point_matcher_final_ns" default="3_iterative_closest_point_with_normals" if="$(arg use_iterative_closest_point_with_normals)" />
<arg name="point_matcher_final_ns" default="3_iterative_closest_point" unless="$(arg use_iterative_closest_point_with_normals)" />
<arg name="reference_pointcloud_required" default="$(eval (use_feature_matching_for_initial_alignment or use_pca_for_initial_alignment or use_cloud_matching or bool(yaml_configuration_outlier_detectors_filename)) and not use_cloud_storage_mode)" />
<include file="$(find object_recognition_skill_server)/launch/object_recognition.launch">
<arg name="namespace" default="pointcloud_storage" if="$(arg use_cloud_storage_mode)" />
<arg name="namespace" default="pointcloud_registration" unless="$(arg use_cloud_storage_mode)" />
<arg name="namespace_object_recognition_skill_server" default="pointcloud_storage_server" if="$(arg use_cloud_storage_mode)" />
<arg name="namespace_object_recognition_skill_server" default="pointcloud_registration_server" unless="$(arg use_cloud_storage_mode)" />
<arg name="ambient_pointcloud_topic" default="$(arg ambient_pointcloud_topic)" />
<arg name="number_of_recognition_retries" default="$(arg number_of_recognition_retries)"/>
<!-- frame ids -->
<arg name="sensor_frame_id" default="$(arg sensor_frame_id)" />
<arg name="base_link_frame_id" default="$(arg base_link_frame_id)" />
<arg name="object_frame_id" default="$(arg correction_frame_id)" />
<arg name="object_frame_id_for_transforming_pointclouds" default="$(arg object_frame_id_for_transforming_pointclouds)" />
<arg name="object_frame_id_for_publishing_pointclouds" default="$(arg object_frame_id_for_publishing_pointclouds)" />
<!-- 3d processing pipeline parameters for cloud storage -->
<arg name="use_cloud_storage_mode" default="$(arg use_cloud_storage_mode)" />
<arg name="use_voxel_grid_segmentation_in_cloud_storage_mode" default="$(arg use_voxel_grid_segmentation_in_cloud_storage_mode)" />
<arg name="use_random_sample_segmentation_in_cloud_storage_mode" default="$(arg use_random_sample_segmentation_in_cloud_storage_mode)" />
<arg name="use_object_model_caching" default="$(arg use_object_model_caching)"/>
<!-- 3d processing pipeline parameters for cloud registration -->
<arg name="use_voxel_grid" default="$(arg use_voxel_grid)" />
<arg name="use_random_sample" default="$(arg use_random_sample)" />
<arg name="use_noise_removal" default="$(arg use_noise_removal)" />
<arg name="use_normal_estimation" default="$(arg use_normal_estimation)" />
<arg name="use_curvature_estimation" default="$(arg use_curvature_estimation)" />
<arg name="use_plane_segmentation" default="$(arg use_plane_segmentation)" />
<arg name="use_euclidean_clustering_segmentation" default="$(arg use_euclidean_clustering_segmentation)" />
<arg name="use_feature_matching_for_initial_alignment" default="$(arg use_feature_matching_for_initial_alignment)" />
<arg name="use_pca_for_initial_alignment" default="$(arg use_pca_for_initial_alignment)" />
<arg name="load_initial_pose_estimation_pipeline_using_pca" default="$(arg load_initial_pose_estimation_pipeline_using_pca)" />
<arg name="use_cloud_matching" default="$(arg use_cloud_matching)" />
<arg name="use_transformation_aligner" default="$(arg use_transformation_aligner)" />
<arg name="max_registration_outliers" default="$(arg max_registration_outliers)" />
<arg name="max_registration_outliers_reference_pointcloud" default="$(arg max_registration_outliers_reference_pointcloud)" />
<arg name="cloud_matching_timeout_for_intermediate_alignment" default="$(arg cloud_matching_timeout_for_intermediate_alignment)" />
<arg name="cloud_matching_timeout_for_final_alignment" default="$(arg cloud_matching_timeout_for_final_alignment)" />
<!-- configuration files (empty paths can be given for avoiding the rosparam load) -->
<arg name="yaml_configuration_configs_filename" default="$(arg yaml_configuration_configs_filename)" />
<arg name="yaml_configuration_filters_roi_filename" default="$(arg yaml_configuration_filters_roi_filename)" />
<arg name="yaml_configuration_filters_voxel_grid_filename" default="$(arg yaml_configuration_filters_voxel_grid_filename)" />
<arg name="yaml_configuration_filters_noise_removal_filename" default="$(arg yaml_configuration_filters_noise_removal_filename)" />
<arg name="yaml_configuration_filters_plane_segmentation_filename" default="$(arg yaml_configuration_filters_plane_segmentation_filename)" />
<arg name="yaml_configuration_filters_euclidean_clustering_filename" default="$(arg yaml_configuration_filters_euclidean_clustering_filename)" />
<arg name="yaml_configuration_normal_estimators_filename" default="$(arg yaml_configuration_normal_estimators_filename)" />
<arg name="yaml_configuration_curvature_estimators_filename" default="" />
<arg name="yaml_configuration_initial_pose_estimators_feature_matchers_filename" default="$(arg yaml_configuration_initial_pose_estimators_feature_matchers_filename)" />
<arg name="yaml_configuration_initial_pose_estimators_point_matchers_filename" default="$(arg yaml_configuration_initial_pose_estimators_point_matchers_filename)" />
<arg name="yaml_configuration_outlier_detectors_filename" default="$(arg yaml_configuration_outlier_detectors_filename)" />
<arg name="yaml_configuration_transformation_validators_filename" default="$(arg yaml_configuration_transformation_validators_filename)" />
<arg name="yaml_configuration_custom_filename" default="$(arg yaml_configuration_custom_filename)" />
<arg name="point_matcher_intermediate_ns" default="$(arg point_matcher_intermediate_ns)" />
<arg name="point_matcher_final_ns" default="$(arg point_matcher_final_ns)" />
<!-- reference map data -->
<arg name="reference_pointcloud_filename" default="$(arg reference_pointcloud_filename)" />
<arg name="reference_pointclouds_database_folder_path" default="$(arg reference_pointclouds_database_folder_path)" />
<arg name="reference_pointcloud_required" default="$(arg reference_pointcloud_required)" />
</include>
</launch>