PointCloudObjectLocalizer.h
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 
25 #pragma once
26 
27 
28 #include <Eigen/Core>
29 
32 
33 #include <RobotAPI/interface/core/PoseBase.h>
34 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
36 
39 #include <VisionX/interface/components/SimpleLocation.h>
40 
42 #include <MemoryX/interface/core/ProbabilityMeasures.h>
43 
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
63 
64 #include <limits>
65 
66 namespace visionx
67 {
68 
69 
70  using PointT = pcl::PointXYZRGBA;
71  using PointL = pcl::PointXYZRGBL;
72  using PointD = pcl::FPFHSignature33;
73 
74  //using PointD = pcl::SHOT352;
75 
76  /**
77  * @class PointCloudObjectLocalizerPropertyDefinitions
78  * @brief
79  */
81  {
82  public:
85  {
86  defineOptionalProperty<std::string>(
87  "agentName",
88  "Armar3",
89  "Name of the agent for which the sensor values are provided");
90  defineOptionalProperty<std::string>(
91  "modelFileName",
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>(
104  "sourceNodeName",
106  "the robot node to use as source coordinate system for the captured point clouds");
107  defineOptionalProperty<std::string>(
108  "objectClassName",
109  "wateringcan",
110  "Name of the objectClass this component localizes.");
111  }
112  };
113 
114  /**
115 
116  http://pointclouds.org/documentation/tutorials/global_hypothesis_verification.php
117  * @class PointCloudObjectLocalizer
118  *
119  * @ingroup VisionX-Components
120  * @brief A brief description
121  *
122  *
123  * Detailed Description
124  */
126  virtual public armarx::SimpleLocationInterface,
127  virtual public PointCloudProcessor
128  {
129  public:
130  /**
131  * @see armarx::ManagedIceObject::getDefaultName()
132  */
133  std::string
134  getDefaultName() const override
135  {
136  return "PointCloudObjectLocalizer";
137  }
138 
139  void getLocation(armarx::FramedOrientationBasePtr& orientation,
140  armarx::FramedPositionBasePtr& position,
141  const Ice::Current& c = Ice::emptyCurrent) override;
142 
143  memoryx::ObjectLocalizationResultList
144  localizeObjectClasses(const memoryx::ObjectClassNameList& objectClassNames,
145  const Ice::Current& c = Ice::emptyCurrent) override;
146 
147  protected:
148  /**
149  * @see visionx::PointCloudProcessor::onInitPointCloudProcessor()
150  */
151  void onInitPointCloudProcessor() override;
152 
153  /**
154  * @see visionx::PointCloudProcessor::onConnectPointCloudProcessor()
155  */
156  void onConnectPointCloudProcessor() override;
157 
158  /**
159  * @see visionx::PointCloudProcessor::onDisconnectPointCloudProcessor()
160  */
161  void onDisconnectPointCloudProcessor() override;
162 
163  /**
164  * @see visionx::PointCloudProcessor::onExitPointCloudProcessor()
165  */
166  void onExitPointCloudProcessor() override;
167 
168  /**
169  * @see visionx::PointCloudProcessor::process()
170  */
171  void process() override;
172 
173  /**
174  * @see PropertyUser::createPropertyDefinitions()
175  */
177 
178 
179  private:
180  std::mutex pointCloudMutex;
181 
182  bool icpOnly;
183 
184  std::string agentName;
185 
186  std::string providerName;
187  std::string sourceNodeName;
188 
189  pcl::NormalEstimationOMP<PointT, pcl::Normal> normalEstimation;
190  pcl::FPFHEstimationOMP<PointT, pcl::Normal, PointD> featureEstimation;
191  //pcl::SHOTEstimationOMP<PointT, pcl::Normal, PointD> featureEstimation;
192 
193  pcl::KdTreeFLANN<PointD> matchSearchTree;
194  pcl::GeometricConsistencyGrouping<PointT, PointT> clusterer;
195  pcl::IterativeClosestPoint<PointT, PointT> icp;
196 
197  //pcl::GeneralizedIterativeClosestPoint6D icp;
198 
199  pcl::PointCloud<PointD>::Ptr modelDescriptors;
200  pcl::PointCloud<PointT>::Ptr modelKeypoints;
201 
202  pcl::ApproximateVoxelGrid<PointT> grid;
203 
204  std::mutex localizeMutex;
205 
207 
208  armarx::DebugDrawerInterfacePrx debugDrawerPrx;
209  };
210 } // namespace visionx
visionx::PointCloudObjectLocalizer::localizeObjectClasses
memoryx::ObjectLocalizationResultList localizeObjectClasses(const memoryx::ObjectClassNameList &objectClassNames, const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudObjectLocalizer.cpp:306
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
visionx::PointCloudObjectLocalizer::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: PointCloudObjectLocalizer.cpp:351
armarx::GlobalFrame
const std::string GlobalFrame
Definition: FramedPose.h:65
armarx::PropertyDefinitionContainer::prefix
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
Definition: PropertyDefinitionContainer.h:345
visionx::PointD
pcl::FPFHSignature33 PointD
Definition: MaskRCNNPointCloudObjectLocalizer.h:79
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:46
visionx::PointCloudObjectLocalizer::onExitPointCloudProcessor
void onExitPointCloudProcessor() override
Definition: PointCloudObjectLocalizer.cpp:133
visionx::PointCloudObjectLocalizer::process
void process() override
Definition: PointCloudObjectLocalizer.cpp:138
visionx::PointCloudObjectLocalizerPropertyDefinitions::PointCloudObjectLocalizerPropertyDefinitions
PointCloudObjectLocalizerPropertyDefinitions(std::string prefix)
Definition: PointCloudObjectLocalizer.h:83
visionx::PointCloudObjectLocalizer::onConnectPointCloudProcessor
void onConnectPointCloudProcessor() override
Definition: PointCloudObjectLocalizer.cpp:114
IceInternal::Handle< FramedPose >
visionx::PointCloudProcessor
The PointCloudProcessor class provides an interface for access to PointCloudProviders via Ice and sha...
Definition: PointCloudProcessor.h:177
PCLUtilities.h
FramedPose.h
visionx::PointCloudObjectLocalizerPropertyDefinitions
Definition: PointCloudObjectLocalizer.h:80
MemoryXCoreObjectFactories.h
visionx::PointCloudObjectLocalizer::getLocation
void getLocation(armarx::FramedOrientationBasePtr &orientation, armarx::FramedPositionBasePtr &position, const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudObjectLocalizer.cpp:340
PointCloudProcessor.h
Component.h
visionx::PointL
pcl::PointXYZRGBL PointL
Definition: MaskRCNNPointCloudObjectLocalizer.h:78
armarx::ComponentPropertyDefinitions
Default component property definition container.
Definition: Component.h:69
IceUtil::Handle< class PropertyDefinitionContainer >
IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface >
armarx::ComponentPropertyDefinitions::ComponentPropertyDefinitions
ComponentPropertyDefinitions(std::string prefix, bool hasObjectNameParameter=true)
Definition: Component.cpp:35
visionx::PointCloudObjectLocalizer::getDefaultName
std::string getDefaultName() const override
Definition: PointCloudObjectLocalizer.h:134
visionx::PointCloudObjectLocalizer::onDisconnectPointCloudProcessor
void onDisconnectPointCloudProcessor() override
Definition: PointCloudObjectLocalizer.cpp:128
visionx::PointCloudObjectLocalizer::onInitPointCloudProcessor
void onInitPointCloudProcessor() override
Definition: PointCloudObjectLocalizer.cpp:39
ArmarXDataPath.h
visionx::PointCloudObjectLocalizer
http://pointclouds.org/documentation/tutorials/global_hypothesis_verification.php
Definition: PointCloudObjectLocalizer.h:125
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:27
visionx::PointT
pcl::PointXYZRGBA PointT
Definition: MaskRCNNPointCloudObjectLocalizer.h:77