ImageToPointCloud.h
Go to the documentation of this file.
1/*
2 * This file is part of ArmarX.
3 *
4 * ArmarX is free software; you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License version 2 as
6 * published by the Free Software Foundation.
7 *
8 * ArmarX is distributed in the hope that it will be useful, but
9 * WITHOUT ANY WARRANTY; without even the implied warranty of
10 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 * GNU General Public License for more details.
12 *
13 * You should have received a copy of the GNU General Public License
14 * along with this program. If not, see <http://www.gnu.org/licenses/>.
15 *
16 * @package ActiveVision::ArmarXObjects::ImageToPointCloud
17 * @author Markus Grotz ( markus dot grotz at kit dot edu )
18 * @author Mirko Waechter ( waechter at kit dot edu )
19 * @date 2019
20 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
21 * GNU General Public License
22 */
23
24#pragma once
25
26#include <mutex>
27
28#include <pcl/point_types.h>
29
31#include <ArmarXCore/interface/observers/ObserverInterface.h>
32
33#include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
34
37#include <VisionX/interface/components/ImageToPointCloud.h>
40
41#include "DepthImageUtils.h"
42
43namespace armarx
44{
45
46
47 typedef pcl::PointXYZRGBL PointL;
48
49 /**
50 * @class ImageToPointCloudPropertyDefinitions
51 * @brief
52 */
54 {
55 public:
58 {
59 defineOptionalProperty<std::string>("DebugObserverName",
60 "DebugObserver",
61 "Name of the topic the DebugObserver listens on");
62 // defineOptionalProperty<std::string>("DebugDrawerTopicName", "DebugDrawerUpdates", "Name of the DebugDrawerTopic");
63 defineOptionalProperty<int>("PointCloudWidth",
64 640,
65 "Must match the image width (cannot be read automaically "
66 "from imageprovider as early as needed)");
67 defineOptionalProperty<int>("PointCloudHeight",
68 480,
69 "Must match the image height (cannot be read automaically "
70 "from imageprovider as early as needed)");
71
72 defineOptionalProperty<float>("VerticalViewAngle",
73 43.0f,
74 "The vertical viewing angle of the camera. Only used "
75 "when no calibration can be retrieved.");
76 defineOptionalProperty<float>("HorizontalViewAngle",
77 57.0f,
78 "The horizontal viewing angle of the camera. Only used "
79 "when no calibration can be retrieved.");
81 "ComputeViewAngleFromCalibration",
82 true,
83 "Use the field of view provided by the calibration provider");
84
85
87 "NaNValue", -1.0, "NaN value to use if reported disparity is not available.");
89 "MaxDist",
90 -1.0,
91 "The maximum distance for measurements. Ignored if smaller than zero");
93 "MinDist", 0.0, "The minimum distance for measurements. ");
94
95 defineOptionalProperty<float>("PointCloudRotationZ",
96 180.0f,
97 "Rotation around Z of the provided pointcloud",
99
101 "ProviderName",
102 "ImageProvider name. image[0]: rgb image, image[1]: depth image, "
103 "image[2](optional): label integer");
104 defineOptionalProperty<std::string>("CalibrationProviderName",
105 "",
106 "CalibrationProvider name. Optional. Useful if the "
107 "images are processed and forwarded.");
108 }
109 };
110
111 /**
112 * @defgroup Component-ImageToPointCloud ImageToPointCloud
113 * @ingroup VisionX-Components
114 * A description of the component ImageToPointCloud.
115 *
116 * @class ImageToPointCloud
117 * @ingroup Component-ImageToPointCloud
118 * @brief Brief description of class ImageToPointCloud.
119 *
120 * Detailed description of class ImageToPointCloud.
121 */
123 virtual public visionx::PointCloudProvider,
124 virtual public visionx::ImageProcessor,
125 virtual public armarx::ImageToPointCloudInterface
126 {
127 public:
128 /**
129 * @see armarx::ManagedIceObject::getDefaultName()
130 */
131 std::string
132 getDefaultName() const override
133 {
134 return "ImageToPointCloud";
135 }
136
137 void
141
142 void
146
147 visionx::StereoCalibration
148 getStereoCalibration(const Ice::Current& c = Ice::emptyCurrent) override
149 {
150 return calibrationPrx->getStereoCalibration();
151 }
152
153 bool
154 getImagesAreUndistorted(const Ice::Current& c = Ice::emptyCurrent) override
155 {
156 return calibrationPrx->getImagesAreUndistorted();
157 }
158
159 std::string
160 getReferenceFrame(const Ice::Current& c = Ice::emptyCurrent) override
161 {
162 return calibrationPrx->getReferenceFrame();
163 }
164
165
166 protected:
167 void onInitImageProcessor() override;
168 void onConnectImageProcessor() override;
169 void onExitImageProcessor() override;
170 void process() override;
171
172 virtual visionx::MetaPointCloudFormatPtr getDefaultPointCloudFormat();
173
174 void
180
181 void
187
188 void
194
195 void onDisconnectComponent() override;
196
197 /**
198 * @see PropertyUser::createPropertyDefinitions()
199 */
201
202 private:
203 // armarx::DebugDrawerInterfacePrx debugDrawer;
205 visionx::StereoCalibrationInterfacePrx calibrationPrx;
206
207 armarx::MetaInfoSizeBasePtr imageMetaInfo;
208
209 float fovH;
210 float fovV;
211
212 std::mutex mutex;
213 float nanValue;
214 float maxDist;
215 float minDist;
216 int processCounter = 0;
217
218 std::string providerName;
219 CByteImage** images;
220 size_t numImages;
221 visionx::ImageProviderInfo imageProviderInfo;
222 DepthImageUtils depthImageUtils;
223 pcl::PointCloud<PointL>::Ptr cloud, transformedCloud;
224 };
225} // namespace armarx
constexpr T c
Brief description of class ImageToPointCloud.
std::string getReferenceFrame(const Ice::Current &c=Ice::emptyCurrent) override
virtual armarx::PropertyDefinitionsPtr createPropertyDefinitions()
void onInitComponent() override
Pure virtual hook for the subclass.
virtual visionx::MetaPointCloudFormatPtr getDefaultPointCloudFormat()
default point cloud format used to initialize shared memory
void onConnectImageProcessor() override
Implement this method in the ImageProcessor in order execute parts when the component is fully initia...
void onDisconnectComponent() override
Hook for subclass.
void onExitImageProcessor() override
Exit the ImapeProcessor component.
visionx::StereoCalibration getStereoCalibration(const Ice::Current &c=Ice::emptyCurrent) override
void process() override
Process the vision component.
void onInitImageProcessor() override
Setup the vision component.
bool getImagesAreUndistorted(const Ice::Current &c=Ice::emptyCurrent) override
void onConnectComponent() override
Pure virtual hook for the subclass.
void onInitPointCloudProvider()
This is called when the Component::onInitComponent() is called.
void onExitComponent() override
Hook for subclass.
void onExitPointCloudProvider()
This is called when the Component::onExitComponent() setup is called.
std::string getDefaultName() const override
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
PropertyDefinition< PropertyType > & defineOptionalProperty(const std::string &name, PropertyType defaultValue, const std::string &description="", PropertyDefinitionBase::PropertyConstness constness=PropertyDefinitionBase::eConstant)
PropertyDefinition< PropertyType > & defineRequiredProperty(const std::string &name, const std::string &description="", PropertyDefinitionBase::PropertyConstness constness=PropertyDefinitionBase::eConstant)
ImageProcessorPropertyDefinitions(std::string prefix)
The ImageProcessor class provides an interface for access to ImageProviders via Ice and shared memory...
void onInitComponent() override
void onConnectComponent() override
void onExitComponent() override
PointCloudProvider abstract class defines a component which provide point clouds via ice or shared me...
This file offers overloads of toIce() and fromIce() functions for STL container types.
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface > DebugObserverInterfacePrx
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
pcl::PointXYZRGBL PointL
ArmarX headers.