33 #include <RobotAPI/interface/core/PoseBase.h>
34 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
39 #include <VisionX/interface/components/SimpleLocation.h>
42 #include <MemoryX/interface/core/ProbabilityMeasures.h>
44 #pragma GCC diagnostic push
45 #pragma GCC diagnostic ignored "-Wpedantic"
46 #include <pcl/common/transforms.h>
47 #include <pcl/correspondence.h>
48 #include <pcl/features/fpfh_omp.h>
49 #include <pcl/features/normal_3d.h>
50 #include <pcl/features/normal_3d_omp.h>
51 #include <pcl/features/shot_omp.h>
52 #include <pcl/filters/approximate_voxel_grid.h>
53 #include <pcl/filters/filter.h>
54 #include <pcl/filters/passthrough.h>
55 #include <pcl/io/pcd_io.h>
56 #include <pcl/kdtree/kdtree_flann.h>
57 #include <pcl/point_types.h>
58 #include <pcl/recognition/cg/geometric_consistency.h>
59 #include <pcl/registration/gicp6d.h>
60 #include <pcl/registration/icp.h>
61 #include <pcl/search/kdtree.h>
62 #pragma GCC diagnostic pop
70 using PointT = pcl::PointXYZRGBA;
71 using PointL = pcl::PointXYZRGBL;
72 using PointD = pcl::FPFHSignature33;
86 defineOptionalProperty<std::string>(
89 "Name of the agent for which the sensor values are provided");
90 defineOptionalProperty<std::string>(
92 "VisionX/examples/point_cloud_models/wateringcan2.pcd",
93 "path to the model to match");
94 defineOptionalProperty<std::string>(
95 "providerName",
"PointCloudSegmenterResult",
"name of the point cloud provider");
96 defineOptionalProperty<double>(
"recGCSize", 5.0f,
"the consensus set resolution");
97 defineOptionalProperty<int>(
"recGCThreshold", 20,
"minimum cluster size");
98 defineOptionalProperty<float>(
"leafSize", 6.0f,
"the voxel grid leaf size");
99 defineOptionalProperty<float>(
"sceneLeafSize", 3.0f,
"the voxel grid leaf size");
100 defineOptionalProperty<bool>(
"icpOnly",
true,
"");
101 defineOptionalProperty<std::string>(
102 "DebugDrawerTopic",
"DebugDrawerUpdates",
"Name of the DebugDrawerTopic");
103 defineOptionalProperty<std::string>(
106 "the robot node to use as source coordinate system for the captured point clouds");
107 defineOptionalProperty<std::string>(
110 "Name of the objectClass this component localizes.");
126 virtual public armarx::SimpleLocationInterface,
136 return "PointCloudObjectLocalizer";
139 void getLocation(armarx::FramedOrientationBasePtr& orientation,
140 armarx::FramedPositionBasePtr& position,
141 const Ice::Current&
c = Ice::emptyCurrent)
override;
143 memoryx::ObjectLocalizationResultList
145 const Ice::Current&
c = Ice::emptyCurrent)
override;
180 std::mutex pointCloudMutex;
184 std::string agentName;
186 std::string providerName;
187 std::string sourceNodeName;
189 pcl::NormalEstimationOMP<PointT, pcl::Normal> normalEstimation;
190 pcl::FPFHEstimationOMP<PointT, pcl::Normal, PointD> featureEstimation;
193 pcl::KdTreeFLANN<PointD> matchSearchTree;
194 pcl::GeometricConsistencyGrouping<PointT, PointT> clusterer;
195 pcl::IterativeClosestPoint<PointT, PointT> icp;
199 pcl::PointCloud<PointD>::Ptr modelDescriptors;
200 pcl::PointCloud<PointT>::Ptr modelKeypoints;
202 pcl::ApproximateVoxelGrid<PointT> grid;
204 std::mutex localizeMutex;