StereoImagePointCloudProvider.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::StereoImagePointCloudProvider
19  * @author David Schiebener (schiebener 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 <climits>
29 #include <cmath>
30 #include <mutex>
31 #include <vector>
32 
33 #include <pcl/point_types.h>
34 
37 
40 #include <VisionX/interface/components/PointCloudAndImageAndCalibrationProviderInterface.h>
41 
42 
43 class CStereoCalibration;
44 
45 namespace visionx
46 {
47 
48  /**
49  * @class StereoImagePointCloudProviderPropertyDefinitions
50  * @brief
51  */
54  {
55  public:
58  {
59  defineOptionalProperty<std::string>(
60  "ImageProviderAdapterName",
61  "Armar3ImageProvider",
62  "Name of the stereo image provider for the camera images and the calibration");
63  defineOptionalProperty<int>(
64  "DownsamplingRate", 1, "Create a point only at every n-th pixel");
65  defineOptionalProperty<bool>(
66  "SmoothDisparity",
67  true,
68  "Smooth the disparity image to filter out noise, but loose sharp edges");
69  }
70  };
71 
72  /**
73  * @class StereoImagePointCloudProvider
74  * @ingroup VisionX-Components
75  * @brief A brief description
76  *
77  * Detailed Description
78  */
80  virtual public StereoImagePointCloudProviderInterface,
81  virtual public CapturingPointCloudProvider,
82  virtual public ImageProcessor,
83  virtual public ImageProvider
84  {
85  public:
86  /**
87  * @see armarx::ManagedIceObject::getDefaultName()
88  */
89  std::string
90  getDefaultName() const override
91  {
92  return "StereoImagePointCloudProvider";
93  }
94 
95  MetaPointCloudFormatPtr getDefaultPointCloudFormat() override;
96 
97  protected:
98  /**
99  * @see visionx::PointCloudProviderBase::onInitPointCloudProvider()
100  */
101  void onInitCapturingPointCloudProvider() override;
102 
103  /**
104  * @see visionx::PointCloudProviderBase::onExitPointCloudProvider()
105  */
106  void onExitCapturingPointCloudProvider() override;
107 
108  /**
109  * @see visionx::PointCloudProviderBase::onStartCapture()
110  */
111  void onStartCapture(float frameRate) override;
112 
113  /**
114  * @see visionx::PointCloudProviderBase::onStopCapture()
115  */
116  void onStopCapture() override;
117 
118  /**
119  * @see visionx::PointCloudProviderBase::doCapture()
120  */
121  bool doCapture() override;
122 
123  // ImageProcessor functions
124  void onInitImageProcessor() override;
125  void onConnectImageProcessor() override;
126  void onExitImageProcessor() override;
127 
128  void
129  process() override
130  {
131  }
132 
133  /**
134  * @see visionx::CapturingImageProvider::onInitImageProvider()
135  */
136  void onInitImageProvider() override;
137 
138  /**
139  * @see visionx::CapturingImageProvider::onExitImageProvider()
140  */
141  void
143  {
144  }
145 
146  /**
147  * @see PropertyUser::createPropertyDefinitions()
148  */
150 
151  // mixed inherited stuff
152  void onInitComponent() override;
153  void onConnectComponent() override;
154  void onDisconnectComponent() override;
155  void onExitComponent() override;
156 
157  bool
158  getImagesAreUndistorted(const ::Ice::Current& c = Ice::emptyCurrent) override
159  {
160  return imagesAreUndistorted;
161  }
162 
163  visionx::MonocularCalibration
164  getMonocularCalibration(const ::Ice::Current& c = Ice::emptyCurrent) override;
165 
166  bool
167  hasSharedMemorySupport(const Ice::Current& c = Ice::emptyCurrent) override
168  {
169  return true;
170  }
171 
172 
173  private:
174  ImageProviderInterfacePrx imageProviderPrx;
175  std::string providerName;
176  CStereoCalibration* stereoCalibration;
177  CByteImage** cameraImages;
178  CByteImage** cameraImagesGrey;
179  CByteImage** resultImages;
180  CByteImage *disparityImage, *disparityImageRGB;
181  float frameRate;
182  int width, height;
183  bool imagesAreUndistorted;
184  int downsamplingRate;
185  bool smoothDisparity;
186 
187  std::mutex captureLock;
188  };
189 } // namespace visionx
CapturingPointCloudProvider.h
visionx::StereoImagePointCloudProvider::process
void process() override
Process the vision component.
Definition: StereoImagePointCloudProvider.h:129
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
visionx::ImageProcessor
The ImageProcessor class provides an interface for access to ImageProviders via Ice and shared memory...
Definition: ImageProcessor.h:98
visionx::StereoImagePointCloudProvider::doCapture
bool doCapture() override
Definition: StereoImagePointCloudProvider.cpp:195
visionx::StereoImagePointCloudProvider::onExitImageProvider
void onExitImageProvider() override
Definition: StereoImagePointCloudProvider.h:142
visionx::StereoImagePointCloudProvider::onInitComponent
void onInitComponent() override
Definition: StereoImagePointCloudProvider.cpp:43
visionx::StereoImagePointCloudProvider::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: StereoImagePointCloudProvider.cpp:254
armarx::PropertyDefinitionContainer::prefix
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
Definition: PropertyDefinitionContainer.h:345
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:46
visionx::StereoImagePointCloudProvider::onExitComponent
void onExitComponent() override
Definition: StereoImagePointCloudProvider.cpp:69
visionx::StereoImagePointCloudProviderPropertyDefinitions
Definition: StereoImagePointCloudProvider.h:52
visionx::StereoImagePointCloudProvider::getDefaultName
std::string getDefaultName() const override
Definition: StereoImagePointCloudProvider.h:90
ImageProcessor.h
visionx::StereoImagePointCloudProvider::getImagesAreUndistorted
bool getImagesAreUndistorted(const ::Ice::Current &c=Ice::emptyCurrent) override
Definition: StereoImagePointCloudProvider.h:158
visionx::CapturingPointCloudProviderPropertyDefinitions
Definition: CapturingPointCloudProvider.h:39
visionx::StereoImagePointCloudProvider::onConnectImageProcessor
void onConnectImageProcessor() override
Implement this method in the ImageProcessor in order execute parts when the component is fully initia...
Definition: StereoImagePointCloudProvider.cpp:116
visionx::StereoImagePointCloudProvider::onConnectComponent
void onConnectComponent() override
Definition: StereoImagePointCloudProvider.cpp:53
visionx::StereoImagePointCloudProvider
A brief description.
Definition: StereoImagePointCloudProvider.h:79
visionx::StereoImagePointCloudProvider::onExitCapturingPointCloudProvider
void onExitCapturingPointCloudProvider() override
Definition: StereoImagePointCloudProvider.cpp:92
visionx::StereoImagePointCloudProvider::getDefaultPointCloudFormat
MetaPointCloudFormatPtr getDefaultPointCloudFormat() override
default point cloud format used to initialize shared memory
Definition: StereoImagePointCloudProvider.cpp:97
Component.h
visionx::CapturingPointCloudProvider
The CapturingPointCloudProvider provides a callback function to trigger the capturing of point clouds...
Definition: CapturingPointCloudProvider.h:58
visionx::StereoImagePointCloudProvider::getMonocularCalibration
visionx::MonocularCalibration getMonocularCalibration(const ::Ice::Current &c=Ice::emptyCurrent) override
Definition: StereoImagePointCloudProvider.cpp:189
visionx::ImageProvider
ImageProvider abstract class defines a component which provide images via ice or shared memory.
Definition: ImageProvider.h:66
visionx::StereoImagePointCloudProvider::onStartCapture
void onStartCapture(float frameRate) override
Definition: StereoImagePointCloudProvider.cpp:82
visionx::StereoImagePointCloudProvider::onExitImageProcessor
void onExitImageProcessor() override
Exit the ImapeProcessor component.
Definition: StereoImagePointCloudProvider.cpp:168
visionx::StereoImagePointCloudProvider::onInitImageProcessor
void onInitImageProcessor() override
Setup the vision component.
Definition: StereoImagePointCloudProvider.cpp:108
IceUtil::Handle< class PropertyDefinitionContainer >
visionx::StereoImagePointCloudProvider::onStopCapture
void onStopCapture() override
Definition: StereoImagePointCloudProvider.cpp:87
visionx::StereoImagePointCloudProvider::onInitCapturingPointCloudProvider
void onInitCapturingPointCloudProvider() override
Definition: StereoImagePointCloudProvider.cpp:77
visionx::StereoImagePointCloudProviderPropertyDefinitions::StereoImagePointCloudProviderPropertyDefinitions
StereoImagePointCloudProviderPropertyDefinitions(std::string prefix)
Definition: StereoImagePointCloudProvider.h:56
ArmarXDataPath.h
visionx::StereoImagePointCloudProvider::hasSharedMemorySupport
bool hasSharedMemorySupport(const Ice::Current &c=Ice::emptyCurrent) override
Definition: StereoImagePointCloudProvider.h:167
visionx::StereoImagePointCloudProvider::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: StereoImagePointCloudProvider.cpp:61
visionx::StereoImagePointCloudProvider::onInitImageProvider
void onInitImageProvider() override
Definition: StereoImagePointCloudProvider.cpp:182