PointCloudObjectLocalizer.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2011-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5  *
6  * ArmarX is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License version 2 as
8  * published by the Free Software Foundation.
9  *
10  * ArmarX is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  *
18  * @package VisionX::ArmarXObjects::PointCloudObjectLocalizer
19  * @author Markus Grotz ( markus dot grotz at kit dot edu )
20  * @date 2015
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 
26 
28 
29 #include <pcl/PointIndices.h>
30 
31 
32 using namespace armarx;
33 
34 namespace visionx
35 {
36 
37 
38  void PointCloudObjectLocalizer::onInitPointCloudProcessor()
39  {
40  std::scoped_lock lock(pointCloudMutex);
41 
42  pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS);
43 
44  providerName = getProperty<std::string>("providerName").getValue();
45 
46  ARMARX_LOG << "using point cloud provider " << providerName << flush;
47 
48  agentName = getProperty<std::string>("agentName").getValue();
49 
50  sourceNodeName = getProperty<std::string>("sourceNodeName").getValue();
51 
52  icpOnly = getProperty<bool>("icpOnly").getValue();
53 
54  icp.setMaximumIterations(100);
55  icp.setMaxCorrespondenceDistance(500.0);
56 
57  modelKeypoints.reset(new pcl::PointCloud<PointT>);
58 
59  std::string modelFileName = getProperty<std::string>("modelFileName").getValue();
60  armarx::CMakePackageFinder finder("VisionX");
62  pcl::PointCloud<PointT>::Ptr cloudPtr(new pcl::PointCloud<PointT>());
63  if (!ArmarXDataPath::getAbsolutePath(modelFileName, modelFileName))
64  {
65  ARMARX_FATAL << "Could not find point cloud file in ArmarXDataPath: " << modelFileName;
66  return;
67  }
68  else if (pcl::io::loadPCDFile<PointT>(modelFileName.c_str(), *cloudPtr) == -1)
69  {
70  ARMARX_FATAL << "unable to load point cloud from file " << modelFileName;
71  return;
72  }
73 
74  float leafSize = getProperty<float>("sceneLeafSize").getValue();
75  grid.setLeafSize(Eigen::Vector3f(leafSize, leafSize, leafSize));
76 
77  grid.setInputCloud(cloudPtr);
78  grid.filter(*modelKeypoints);
79 
80  if (!icpOnly)
81 
82  {
83  modelDescriptors.reset(new pcl::PointCloud<PointD>());
84 
85  pcl::PointCloud<pcl::Normal>::Ptr pointCloudModelNormals(new pcl::PointCloud<pcl::Normal>);
86  ARMARX_DEBUG << "computing normals";
87  normalEstimation.setInputCloud(cloudPtr);
88  normalEstimation.setRadiusSearch(10.0);
89  normalEstimation.compute(*pointCloudModelNormals);
90 
91  ARMARX_DEBUG << "computing features";
92  featureEstimation.setInputCloud(modelKeypoints);
93  featureEstimation.setInputNormals(pointCloudModelNormals);
94  featureEstimation.setSearchSurface(cloudPtr);
95  featureEstimation.setRadiusSearch(20.0);
96  featureEstimation.compute(*modelDescriptors);
97 
98  matchSearchTree.setInputCloud(modelDescriptors);
99 
100  clusterer.setGCSize(getProperty<double>("recGCSize").getValue());
101  clusterer.setGCThreshold(getProperty<int>("recGCThreshold").getValue());
102  clusterer.setInputCloud(modelKeypoints);
103  }
104 
105 
106  offeringTopic(getProperty<std::string>("DebugDrawerTopic").getValue());
107 
108  usingPointCloudProvider(providerName);
109  }
110 
111  void PointCloudObjectLocalizer::onConnectPointCloudProcessor()
112  {
113  std::scoped_lock lock(pointCloudMutex);
114 
115  debugDrawerPrx = getTopic<DebugDrawerInterfacePrx>(getProperty<std::string>("DebugDrawerTopic").getValue());
116 
117  enableResultPointClouds<PointT>("Input");
118  enableResultPointClouds<PointT>("BeforeICPResult");
119  enableResultPointClouds<PointT>("AfterICPResult");
120  enableResultPointClouds<PointT>("BestMatch");
121  }
122 
123  void PointCloudObjectLocalizer::onDisconnectPointCloudProcessor()
124  {
125 
126  }
127 
128  void PointCloudObjectLocalizer::onExitPointCloudProcessor()
129  {
130  }
131 
132  void PointCloudObjectLocalizer::process()
133  {
134 
135  std::scoped_lock lock(pointCloudMutex);
136 
137  pcl::PointCloud<PointL>::Ptr cloudPtr(new pcl::PointCloud<PointL>());
138 
139  if (!waitForPointClouds(providerName, 10000))
140  {
141  ARMARX_WARNING << "Timeout or error while waiting for point cloud data" << armarx::flush;
142  return;
143  }
144  else
145  {
146  getPointClouds(providerName, cloudPtr);
147  }
148 
149  float bestFitnessScore = std::numeric_limits<float>::max();
150  Eigen::Matrix4f bestTransform = Eigen::Matrix4f::Identity();
151 
152  pcl::PointCloud<PointT>::Ptr afterICPResultPointCloud(new pcl::PointCloud<PointT>());
153  pcl::PointCloud<PointT>::Ptr beforeICPResultPointCloud(new pcl::PointCloud<PointT>());
154 
155  std::map<uint32_t, pcl::PointIndices> labeledPointMap;
156  visionx::tools::fillLabelMap<pcl::PointCloud<PointL>::Ptr>(cloudPtr, labeledPointMap);
157 
158  for (auto& it : labeledPointMap)
159  {
160 
161  ARMARX_LOG << " checking label " << it.first;
162 
163  pcl::PointCloud<PointT>::Ptr segment(new pcl::PointCloud<PointT>());
164  copyPointCloud(*cloudPtr, it.second, *segment);
165 
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());
171 
172  pcl::copyPointCloud(*segment, *transformedCloudPtr);
173 
174  grid.setInputCloud(transformedCloudPtr);
175  grid.filter(*cloudDownsampledPtr);
176 
177  provideResultPointClouds(cloudDownsampledPtr, "Input");
178 
179  std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > transformations;
180 
181  if (icpOnly)
182  {
183  Eigen::Vector4f centroid;
184  pcl::compute3DCentroid(*cloudDownsampledPtr, centroid);
185 
186  for (float i = 0.0; i < 360.0; i += 45.0)
187  {
188  Eigen::Affine3f transform(Eigen::AngleAxisf(i * 180.0 / M_PI, Eigen::Vector3f::UnitZ()));
189 
190  Eigen::Matrix4f transform2 = transform.matrix();
191  transform2.col(3) = centroid;
192  transformations.push_back(transform2);
193  }
194  }
195  else
196  {
197  ARMARX_LOG << "computing normals";
198  normalEstimation.setInputCloud(transformedCloudPtr);
199  normalEstimation.compute(*normalPtr);
200 
201  ARMARX_LOG << "computing features";
202  featureEstimation.setInputCloud(cloudDownsampledPtr);
203  featureEstimation.setInputNormals(normalPtr);
204  featureEstimation.setSearchSurface(transformedCloudPtr);
205  featureEstimation.compute(*descriptorPtr);
206  ARMARX_LOG << "found " << descriptorPtr->size() << " features";
207 
208  int i = 0;
209  const int k = 1;
210  for (PointD& d : descriptorPtr->points)
211  {
212  // if (!std::isfinite(d.descriptor[0])) //skipping NaNs
213  // {
214  // continue;
215  // }
216 
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);
220 
221  if (numNeighborsFound == 1) // && k_sqr_distances[0] < 0.25f)
222  {
223  pcl::Correspondence corr(k_indices[0], i, k_sqr_distances[0]);
224  correspondencesPtr->push_back(corr);
225  }
226  i++;
227  }
228 
229  std::vector<pcl::Correspondences> clusteredCorrespondences;
230 
231  clusterer.setSceneCloud(cloudDownsampledPtr);
232  clusterer.setModelSceneCorrespondences(correspondencesPtr);
233  clusterer.recognize(transformations, clusteredCorrespondences);
234 
235  ARMARX_LOG << " found " << transformations.size() << " transformations";
236  }
237 
238 
239 
240  for (Eigen::Matrix4f& t : transformations)
241  {
242  pcl::PointCloud<PointT>::Ptr transformedModelPtr3(new pcl::PointCloud<PointT>());
243  pcl::transformPointCloud(*modelKeypoints, *transformedModelPtr3, t);
244  visionx::tools::colorizeSegment(transformedModelPtr3);
245  *beforeICPResultPointCloud += *transformedModelPtr3;
246 
247  icp.setInputTarget(cloudDownsampledPtr);
248  icp.setInputSource(modelKeypoints);
249  pcl::PointCloud<PointT>::Ptr registered(new pcl::PointCloud<PointT>);
250  icp.align(*registered, t);
251 
252  if (icp.hasConverged())
253  {
254  float fitnessScore = icp.getFitnessScore();
255  Eigen::Matrix4f transform = icp.getFinalTransformation();
256 
257  ARMARX_LOG << "transformation after ICP " << transform;
258  ARMARX_LOG << "fitness score " << fitnessScore;
259 
260  pcl::PointCloud<PointT>::Ptr transformedModelPtr2(new pcl::PointCloud<PointT>());
261  pcl::transformPointCloud(*modelKeypoints, *transformedModelPtr2, transform);
262  visionx::tools::colorizeSegment(transformedModelPtr2);
263  *afterICPResultPointCloud += *transformedModelPtr2;
264 
265  if (fitnessScore <= bestFitnessScore)
266  {
267  bestFitnessScore = fitnessScore;
268  bestTransform = transform;
269 
270  std::scoped_lock lock(localizeMutex);
271 
272  //pose = new armarx::FramedPose(bestTransform, poseInRootFrame->frame, agentName);
273  //FramedPosePtr::dynamicCast(pose)->changeFrame(robotStateComponent->getSynchronizedRobot(), sourceNodeName);
274 
275  pose = new armarx::FramedPose(bestTransform, sourceNodeName, agentName);
276 
277  debugDrawerPrx->setPoseVisu("PointCloudLocalizer", "label " + it.first, pose);
278 
279  }
280  }
281  }
282 
283  }
284 
285  provideResultPointClouds(beforeICPResultPointCloud, "BeforeICPResult");
286  provideResultPointClouds(afterICPResultPointCloud, "AfterICPResult");
287 
288  if (bestFitnessScore < 2000.0)
289  {
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");
294  }
295 
296  }
297 
298 
299 
300 
301 
302  memoryx::ObjectLocalizationResultList PointCloudObjectLocalizer::localizeObjectClasses(const memoryx::ObjectClassNameList& objectClassNames, const Ice::Current& c)
303  {
304  std::scoped_lock lock(localizeMutex);
305  ARMARX_LOG << "localizing object...";
306 
307  memoryx::ObjectLocalizationResultList resultList;
308 
309  std::string objectClassName = getProperty<std::string>("objectClassName").getValue();
310 
311  for (std::string name : objectClassNames)
312  {
313  if (name == objectClassName && pose)
314  {
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;
323  memoryx::MultivariateNormalDistributionBasePtr dummy(new memoryx::MultivariateNormalDistribution(mean, covar));
324  result.positionNoise = dummy;
325  resultList.push_back(result);
326  }
327  }
328 
329  return resultList;
330  }
331 
332 
333  void PointCloudObjectLocalizer::getLocation(FramedOrientationBasePtr& orientation, FramedPositionBasePtr& position, const Ice::Current& c)
334  {
335  std::scoped_lock lock(localizeMutex);
336 
337  orientation = this->pose->getOrientation();
338  position = this->pose->getPosition();
339  }
340 
341 
342  PropertyDefinitionsPtr PointCloudObjectLocalizer::createPropertyDefinitions()
343  {
345  getConfigIdentifier()));
346  }
347 }
PointCloudObjectLocalizer.h
visionx::tools::colorizeSegment
std::tuple< uint8_t, uint8_t, uint8_t > colorizeSegment(PointCloudPtrT &segment)
Definition: PCLUtilities.h:48
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
armarx::VariantType::FramedPose
const VariantTypeId FramedPose
Definition: FramedPose.h:37
visionx::PointD
pcl::FPFHSignature33 PointD
Definition: MaskRCNNPointCloudObjectLocalizer.h:81
armarx::CMakePackageFinder
The CMakePackageFinder class provides an interface to the CMake Package finder capabilities.
Definition: CMakePackageFinder.h:53
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:43
ARMARX_FATAL
#define ARMARX_FATAL
Definition: Logging.h:192
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:523
armarx::mean
std::optional< float > mean(const boost::circular_buffer< NameValueMap > &buffer, const std::string &key)
Definition: KinematicUnitGuiPlugin.cpp:1615
M_PI
#define M_PI
Definition: MathTools.h:17
memoryx::MultivariateNormalDistribution
The MultivariateNormalDistribution class.
Definition: ProbabilityMeasures.h:236
armarx::flush
const LogSender::manipulator flush
Definition: LogSender.h:251
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:177
armarx::CMakePackageFinder::getDataDir
std::string getDataDir() const
Definition: CMakePackageFinder.h:176
visionx::PointCloudObjectLocalizerPropertyDefinitions
Definition: PointCloudObjectLocalizer.h:87
max
T max(T t1, T t2)
Definition: gdiam.h:48
ARMARX_LOG
#define ARMARX_LOG
Definition: Logging.h:163
CMakePackageFinder.h
GfxTL::Matrix3f
MatrixXX< 3, 3, float > Matrix3f
Definition: MatrixXX.h:600
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
armarx::ArmarXDataPath::addDataPaths
static void addDataPaths(const std::string &dataPathList)
Definition: ArmarXDataPath.cpp:559
IceUtil::Handle< class PropertyDefinitionContainer >
armarx::transform
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT > >
Convenience function (with less typing) to transform a container of type InputT into the same contain...
Definition: algorithm.h:315
armarx::ArmarXDataPath::getAbsolutePath
static bool getAbsolutePath(const std::string &relativeFilename, std::string &storeAbsoluteFilename, const std::vector< std::string > &additionalSearchPaths={}, bool verbose=true)
Definition: ArmarXDataPath.cpp:111
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
armarx::PropertyDefinitionsPtr
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
Definition: forward_declarations.h:34
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28