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 
34 #include <RobotAPI/interface/core/PoseBase.h>
36 
37 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
38 
39 #include <MemoryX/interface/core/ProbabilityMeasures.h>
41 
44 #include <VisionX/interface/components/SimpleLocation.h>
45 
46 #pragma GCC diagnostic push
47 #pragma GCC diagnostic ignored "-Wpedantic"
48 #include <pcl/point_types.h>
49 
50 #include <pcl/common/transforms.h>
51 
52 #include <pcl/io/pcd_io.h>
53 
54 #include <pcl/filters/filter.h>
55 #include <pcl/filters/passthrough.h>
56 #include <pcl/filters/approximate_voxel_grid.h>
57 
58 #include <pcl/features/normal_3d.h>
59 #include <pcl/features/normal_3d_omp.h>
60 #include <pcl/features/fpfh_omp.h>
61 #include <pcl/features/shot_omp.h>
62 #include <pcl/search/kdtree.h>
63 #include <pcl/kdtree/kdtree_flann.h>
64 
65 #include <pcl/registration/icp.h>
66 #include <pcl/registration/gicp6d.h>
67 
68 #include <pcl/correspondence.h>
69 #include <pcl/recognition/cg/geometric_consistency.h>
70 #pragma GCC diagnostic pop
71 
72 #include <limits>
73 
74 namespace visionx
75 {
76 
77 
78  using PointT = pcl::PointXYZRGBA;
79  using PointL = pcl::PointXYZRGBL;
80  using PointD = pcl::FPFHSignature33;
81  //using PointD = pcl::SHOT352;
82 
83  /**
84  * @class PointCloudObjectLocalizerPropertyDefinitions
85  * @brief
86  */
89  {
90  public:
93  {
94  defineOptionalProperty<std::string>("agentName", "Armar3", "Name of the agent for which the sensor values are provided");
95  defineOptionalProperty<std::string>("modelFileName", "VisionX/examples/point_cloud_models/wateringcan2.pcd", "path to the model to match");
96  defineOptionalProperty<std::string>("providerName", "PointCloudSegmenterResult", "name of the point cloud provider");
97  defineOptionalProperty<double>("recGCSize", 5.0f, "the consensus set resolution");
98  defineOptionalProperty<int>("recGCThreshold", 20, "minimum cluster size");
99  defineOptionalProperty<float>("leafSize", 6.0f, "the voxel grid leaf size");
100  defineOptionalProperty<float>("sceneLeafSize", 3.0f, "the voxel grid leaf size");
101  defineOptionalProperty<bool>("icpOnly", true, "");
102  defineOptionalProperty<std::string>("DebugDrawerTopic", "DebugDrawerUpdates", "Name of the DebugDrawerTopic");
103  defineOptionalProperty<std::string>("sourceNodeName", armarx::GlobalFrame, "the robot node to use as source coordinate system for the captured point clouds");
104  defineOptionalProperty<std::string>("objectClassName", "wateringcan", "Name of the objectClass this component localizes.");
105 
106  }
107  };
108 
109  /**
110 
111  http://pointclouds.org/documentation/tutorials/global_hypothesis_verification.php
112  * @class PointCloudObjectLocalizer
113  *
114  * @ingroup VisionX-Components
115  * @brief A brief description
116  *
117  *
118  * Detailed Description
119  */
121  virtual public armarx::SimpleLocationInterface,
122  virtual public PointCloudProcessor
123  {
124  public:
125  /**
126  * @see armarx::ManagedIceObject::getDefaultName()
127  */
128  std::string getDefaultName() const override
129  {
130  return "PointCloudObjectLocalizer";
131  }
132 
133 
134  void getLocation(armarx::FramedOrientationBasePtr& orientation, armarx::FramedPositionBasePtr& position, const Ice::Current& c = Ice::emptyCurrent) override;
135 
136  memoryx::ObjectLocalizationResultList localizeObjectClasses(const memoryx::ObjectClassNameList& objectClassNames, const Ice::Current& c = Ice::emptyCurrent) override;
137 
138  protected:
139  /**
140  * @see visionx::PointCloudProcessor::onInitPointCloudProcessor()
141  */
142  void onInitPointCloudProcessor() override;
143 
144  /**
145  * @see visionx::PointCloudProcessor::onConnectPointCloudProcessor()
146  */
147  void onConnectPointCloudProcessor() override;
148 
149  /**
150  * @see visionx::PointCloudProcessor::onDisconnectPointCloudProcessor()
151  */
152  void onDisconnectPointCloudProcessor() override;
153 
154  /**
155  * @see visionx::PointCloudProcessor::onExitPointCloudProcessor()
156  */
157  void onExitPointCloudProcessor() override;
158 
159  /**
160  * @see visionx::PointCloudProcessor::process()
161  */
162  void process() override;
163 
164  /**
165  * @see PropertyUser::createPropertyDefinitions()
166  */
168 
169 
170  private:
171  std::mutex pointCloudMutex;
172 
173  bool icpOnly;
174 
175  std::string agentName;
176 
177  std::string providerName;
178  std::string sourceNodeName;
179 
180  pcl::NormalEstimationOMP<PointT, pcl::Normal> normalEstimation;
181  pcl::FPFHEstimationOMP<PointT, pcl::Normal, PointD> featureEstimation;
182  //pcl::SHOTEstimationOMP<PointT, pcl::Normal, PointD> featureEstimation;
183 
184  pcl::KdTreeFLANN<PointD> matchSearchTree;
185  pcl::GeometricConsistencyGrouping<PointT, PointT> clusterer;
186  pcl::IterativeClosestPoint<PointT, PointT> icp;
187 
188  //pcl::GeneralizedIterativeClosestPoint6D icp;
189 
190  pcl::PointCloud<PointD>::Ptr modelDescriptors;
191  pcl::PointCloud<PointT>::Ptr modelKeypoints;
192 
193  pcl::ApproximateVoxelGrid<PointT> grid;
194 
195  std::mutex localizeMutex;
196 
198 
199  armarx::DebugDrawerInterfacePrx debugDrawerPrx;
200 
201  };
202 }
203 
visionx::PointCloudObjectLocalizer::localizeObjectClasses
memoryx::ObjectLocalizationResultList localizeObjectClasses(const memoryx::ObjectClassNameList &objectClassNames, const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudObjectLocalizer.cpp:302
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
visionx::PointCloudObjectLocalizer::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: PointCloudObjectLocalizer.cpp:342
armarx::GlobalFrame
const std::string GlobalFrame
Definition: FramedPose.h:62
armarx::PropertyDefinitionContainer::prefix
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
Definition: PropertyDefinitionContainer.h:333
visionx::PointD
pcl::FPFHSignature33 PointD
Definition: MaskRCNNPointCloudObjectLocalizer.h:81
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:43
visionx::PointCloudObjectLocalizer::onExitPointCloudProcessor
void onExitPointCloudProcessor() override
Definition: PointCloudObjectLocalizer.cpp:128
visionx::PointCloudObjectLocalizer::process
void process() override
Definition: PointCloudObjectLocalizer.cpp:132
visionx::PointCloudObjectLocalizerPropertyDefinitions::PointCloudObjectLocalizerPropertyDefinitions
PointCloudObjectLocalizerPropertyDefinitions(std::string prefix)
Definition: PointCloudObjectLocalizer.h:91
visionx::PointCloudObjectLocalizer::onConnectPointCloudProcessor
void onConnectPointCloudProcessor() override
Definition: PointCloudObjectLocalizer.cpp:111
IceInternal::Handle< FramedPose >
visionx::PointCloudProcessor
The PointCloudProcessor class provides an interface for access to PointCloudProviders via Ice and sha...
Definition: PointCloudProcessor.h:186
PCLUtilities.h
FramedPose.h
visionx::PointCloudObjectLocalizerPropertyDefinitions
Definition: PointCloudObjectLocalizer.h:87
MemoryXCoreObjectFactories.h
visionx::PointCloudObjectLocalizer::getLocation
void getLocation(armarx::FramedOrientationBasePtr &orientation, armarx::FramedPositionBasePtr &position, const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudObjectLocalizer.cpp:333
PointCloudProcessor.h
Component.h
visionx::PointL
pcl::PointXYZRGBL PointL
Definition: MaskRCNNPointCloudObjectLocalizer.h:80
armarx::ComponentPropertyDefinitions
Default component property definition container.
Definition: Component.h:70
IceUtil::Handle< class PropertyDefinitionContainer >
IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface >
armarx::ComponentPropertyDefinitions::ComponentPropertyDefinitions
ComponentPropertyDefinitions(std::string prefix, bool hasObjectNameParameter=true)
Definition: Component.cpp:37
visionx::PointCloudObjectLocalizer::getDefaultName
std::string getDefaultName() const override
Definition: PointCloudObjectLocalizer.h:128
visionx::PointCloudObjectLocalizer::onDisconnectPointCloudProcessor
void onDisconnectPointCloudProcessor() override
Definition: PointCloudObjectLocalizer.cpp:123
visionx::PointCloudObjectLocalizer::onInitPointCloudProcessor
void onInitPointCloudProcessor() override
Definition: PointCloudObjectLocalizer.cpp:38
ArmarXDataPath.h
visionx::PointCloudObjectLocalizer
http://pointclouds.org/documentation/tutorials/global_hypothesis_verification.php
Definition: PointCloudObjectLocalizer.h:120
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
visionx::PointT
pcl::PointXYZRGBA PointT
Definition: MaskRCNNPointCloudObjectLocalizer.h:79