29 #include <pcl/PointIndices.h>
38 void PointCloudObjectLocalizer::onInitPointCloudProcessor()
40 std::scoped_lock lock(pointCloudMutex);
42 pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS);
44 providerName = getProperty<std::string>(
"providerName").getValue();
48 agentName = getProperty<std::string>(
"agentName").getValue();
50 sourceNodeName = getProperty<std::string>(
"sourceNodeName").getValue();
52 icpOnly = getProperty<bool>(
"icpOnly").getValue();
54 icp.setMaximumIterations(100);
55 icp.setMaxCorrespondenceDistance(500.0);
57 modelKeypoints.reset(
new pcl::PointCloud<PointT>);
59 std::string modelFileName = getProperty<std::string>(
"modelFileName").getValue();
62 pcl::PointCloud<PointT>::Ptr cloudPtr(
new pcl::PointCloud<PointT>());
65 ARMARX_FATAL <<
"Could not find point cloud file in ArmarXDataPath: " << modelFileName;
68 else if (pcl::io::loadPCDFile<PointT>(modelFileName.c_str(), *cloudPtr) == -1)
70 ARMARX_FATAL <<
"unable to load point cloud from file " << modelFileName;
74 float leafSize = getProperty<float>(
"sceneLeafSize").getValue();
75 grid.setLeafSize(Eigen::Vector3f(leafSize, leafSize, leafSize));
77 grid.setInputCloud(cloudPtr);
78 grid.filter(*modelKeypoints);
83 modelDescriptors.reset(
new pcl::PointCloud<PointD>());
85 pcl::PointCloud<pcl::Normal>::Ptr pointCloudModelNormals(
new pcl::PointCloud<pcl::Normal>);
87 normalEstimation.setInputCloud(cloudPtr);
88 normalEstimation.setRadiusSearch(10.0);
89 normalEstimation.compute(*pointCloudModelNormals);
92 featureEstimation.setInputCloud(modelKeypoints);
93 featureEstimation.setInputNormals(pointCloudModelNormals);
94 featureEstimation.setSearchSurface(cloudPtr);
95 featureEstimation.setRadiusSearch(20.0);
96 featureEstimation.compute(*modelDescriptors);
98 matchSearchTree.setInputCloud(modelDescriptors);
100 clusterer.setGCSize(getProperty<double>(
"recGCSize").getValue());
101 clusterer.setGCThreshold(getProperty<int>(
"recGCThreshold").getValue());
102 clusterer.setInputCloud(modelKeypoints);
106 offeringTopic(getProperty<std::string>(
"DebugDrawerTopic").getValue());
108 usingPointCloudProvider(providerName);
111 void PointCloudObjectLocalizer::onConnectPointCloudProcessor()
113 std::scoped_lock lock(pointCloudMutex);
115 debugDrawerPrx = getTopic<DebugDrawerInterfacePrx>(getProperty<std::string>(
"DebugDrawerTopic").getValue());
117 enableResultPointClouds<PointT>(
"Input");
118 enableResultPointClouds<PointT>(
"BeforeICPResult");
119 enableResultPointClouds<PointT>(
"AfterICPResult");
120 enableResultPointClouds<PointT>(
"BestMatch");
123 void PointCloudObjectLocalizer::onDisconnectPointCloudProcessor()
128 void PointCloudObjectLocalizer::onExitPointCloudProcessor()
132 void PointCloudObjectLocalizer::process()
135 std::scoped_lock lock(pointCloudMutex);
137 pcl::PointCloud<PointL>::Ptr cloudPtr(
new pcl::PointCloud<PointL>());
139 if (!waitForPointClouds(providerName, 10000))
146 getPointClouds(providerName, cloudPtr);
152 pcl::PointCloud<PointT>::Ptr afterICPResultPointCloud(
new pcl::PointCloud<PointT>());
153 pcl::PointCloud<PointT>::Ptr beforeICPResultPointCloud(
new pcl::PointCloud<PointT>());
155 std::map<uint32_t, pcl::PointIndices> labeledPointMap;
156 visionx::tools::fillLabelMap<pcl::PointCloud<PointL>::Ptr>(cloudPtr, labeledPointMap);
158 for (
auto& it : labeledPointMap)
163 pcl::PointCloud<PointT>::Ptr segment(
new pcl::PointCloud<PointT>());
164 copyPointCloud(*cloudPtr, it.second, *segment);
166 pcl::PointCloud<PointT>::Ptr transformedCloudPtr(
new pcl::PointCloud<PointT>());
167 pcl::PointCloud<PointT>::Ptr cloudDownsampledPtr(
new pcl::PointCloud<PointT>());
168 pcl::PointCloud<pcl::Normal>::Ptr normalPtr(
new pcl::PointCloud<pcl::Normal>());
169 pcl::PointCloud<PointD>::Ptr descriptorPtr(
new pcl::PointCloud<PointD>());
170 pcl::CorrespondencesPtr correspondencesPtr(
new pcl::Correspondences());
172 pcl::copyPointCloud(*segment, *transformedCloudPtr);
174 grid.setInputCloud(transformedCloudPtr);
175 grid.filter(*cloudDownsampledPtr);
177 provideResultPointClouds(cloudDownsampledPtr,
"Input");
179 std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > transformations;
183 Eigen::Vector4f centroid;
184 pcl::compute3DCentroid(*cloudDownsampledPtr, centroid);
186 for (
float i = 0.0; i < 360.0; i += 45.0)
188 Eigen::Affine3f
transform(Eigen::AngleAxisf(i * 180.0 /
M_PI, Eigen::Vector3f::UnitZ()));
191 transform2.col(3) = centroid;
192 transformations.push_back(transform2);
198 normalEstimation.setInputCloud(transformedCloudPtr);
199 normalEstimation.compute(*normalPtr);
202 featureEstimation.setInputCloud(cloudDownsampledPtr);
203 featureEstimation.setInputNormals(normalPtr);
204 featureEstimation.setSearchSurface(transformedCloudPtr);
205 featureEstimation.compute(*descriptorPtr);
206 ARMARX_LOG <<
"found " << descriptorPtr->size() <<
" features";
210 for (
PointD& d : descriptorPtr->points)
217 std::vector<int> k_indices(k);
218 std::vector<float> k_sqr_distances(k);
219 int numNeighborsFound = matchSearchTree.nearestKSearch(d, k, k_indices, k_sqr_distances);
221 if (numNeighborsFound == 1)
223 pcl::Correspondence corr(k_indices[0], i, k_sqr_distances[0]);
224 correspondencesPtr->push_back(corr);
229 std::vector<pcl::Correspondences> clusteredCorrespondences;
231 clusterer.setSceneCloud(cloudDownsampledPtr);
232 clusterer.setModelSceneCorrespondences(correspondencesPtr);
233 clusterer.recognize(transformations, clusteredCorrespondences);
235 ARMARX_LOG <<
" found " << transformations.size() <<
" transformations";
242 pcl::PointCloud<PointT>::Ptr transformedModelPtr3(
new pcl::PointCloud<PointT>());
243 pcl::transformPointCloud(*modelKeypoints, *transformedModelPtr3, t);
245 *beforeICPResultPointCloud += *transformedModelPtr3;
247 icp.setInputTarget(cloudDownsampledPtr);
248 icp.setInputSource(modelKeypoints);
249 pcl::PointCloud<PointT>::Ptr registered(
new pcl::PointCloud<PointT>);
250 icp.align(*registered, t);
252 if (icp.hasConverged())
254 float fitnessScore = icp.getFitnessScore();
258 ARMARX_LOG <<
"fitness score " << fitnessScore;
260 pcl::PointCloud<PointT>::Ptr transformedModelPtr2(
new pcl::PointCloud<PointT>());
261 pcl::transformPointCloud(*modelKeypoints, *transformedModelPtr2,
transform);
263 *afterICPResultPointCloud += *transformedModelPtr2;
265 if (fitnessScore <= bestFitnessScore)
267 bestFitnessScore = fitnessScore;
270 std::scoped_lock lock(localizeMutex);
277 debugDrawerPrx->setPoseVisu(
"PointCloudLocalizer",
"label " + it.first, pose);
285 provideResultPointClouds(beforeICPResultPointCloud,
"BeforeICPResult");
286 provideResultPointClouds(afterICPResultPointCloud,
"AfterICPResult");
288 if (bestFitnessScore < 2000.0)
290 ARMARX_LOG <<
"best transformation " << bestTransform;
291 pcl::PointCloud<PointT>::Ptr BestResultPointCloud(
new pcl::PointCloud<PointT>());
292 pcl::transformPointCloud(*modelKeypoints, *BestResultPointCloud, bestTransform);
293 provideResultPointClouds(BestResultPointCloud,
"BestMatch");
302 memoryx::ObjectLocalizationResultList PointCloudObjectLocalizer::localizeObjectClasses(
const memoryx::ObjectClassNameList& objectClassNames,
const Ice::Current&
c)
304 std::scoped_lock lock(localizeMutex);
307 memoryx::ObjectLocalizationResultList resultList;
309 std::string objectClassName = getProperty<std::string>(
"objectClassName").getValue();
311 for (std::string name : objectClassNames)
313 if (name == objectClassName && pose)
315 memoryx::ObjectLocalizationResult result;
316 result.position = pose->getPosition();
317 result.orientation = pose->getOrientation();
318 result.objectClassName = objectClassName;
319 result.recognitionCertainty = 1.0f;
320 Eigen::Vector3f
mean;
321 mean << 0.0, 0.0, 0.0;
324 result.positionNoise = dummy;
325 resultList.push_back(result);
333 void PointCloudObjectLocalizer::getLocation(FramedOrientationBasePtr& orientation, FramedPositionBasePtr& position,
const Ice::Current&
c)
335 std::scoped_lock lock(localizeMutex);
337 orientation = this->pose->getOrientation();
338 position = this->pose->getPosition();
345 getConfigIdentifier()));