ImageToPointCloud.cpp
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 #include "ImageToPointCloud.h"
25 
26 
27 
28 #include <Eigen/Core>
29 #include <Eigen/Geometry>
30 
31 #include <pcl/common/transforms.h>
32 
33 #include <VisionX/interface/components/Calibration.h>
37 
38 
39 using namespace armarx;
40 
41 
42 
44 {
45  offeringTopicFromProperty("DebugObserverName");
46 
47  providerName = getProperty<std::string>("ProviderName").getValue();
48  usingImageProvider(providerName);
49 
50  fovH = getProperty<float>("HorizontalViewAngle").getValue();
51  fovV = getProperty<float>("VerticalViewAngle").getValue();
52  if (!getProperty<std::string>("CalibrationProviderName").getValue().empty())
53  {
54  usingProxy(getProperty<std::string>("CalibrationProviderName").getValue());
55  }
56  nanValue = getProperty<float>("NaNValue").getValue();
57  maxDist = getProperty<float>("MaxDist").getValue();
58  minDist = getProperty<float>("MinDist").getValue();
59 }
60 
62 {
63  ARMARX_VERBOSE << "onConnectImageProcessor()";
64  imageProviderInfo = getImageProvider(providerName);
65  ARMARX_VERBOSE << "after getImageProvider('" << providerName << "')";
66 
67  ARMARX_CHECK_GREATER_EQUAL(imageProviderInfo.numberImages, 2);
68  numImages = std::min(imageProviderInfo.numberImages, 3);
69 
70  images = new CByteImage*[numImages];
71  for (size_t i = 0 ; i < numImages ; i++)
72  {
73  images[i] = visionx::tools::createByteImage(imageProviderInfo);
74  }
75 
76  getTopicFromProperty(debugObserver, "DebugObserverName");
77 
78 
79  auto applyCalibration = [&](visionx::StereoCalibrationInterfacePrx prx)
80  {
81  if (getProperty<bool>("ComputeViewAngleFromCalibration").getValue())
82  {
83  visionx::StereoCalibration stereoCalibration = prx->getStereoCalibration();
84  float fx = stereoCalibration.calibrationRight.cameraParam.focalLength[0];
85  float fy = stereoCalibration.calibrationRight.cameraParam.focalLength[1];
86  fovV = 180.0 / M_PI * 2.0 * std::atan(images[0]->height / (2.0 * fy));
87  fovH = 180.0 / M_PI * 2.0 * std::atan(images[0]->width / (2.0 * fx));
88  ARMARX_INFO << " Using provided HorizontalViewAngle/VerticalViewAngle parameters from calibration";
89  }
90  };
91  if (!getProperty<std::string>("CalibrationProviderName").getValue().empty())
92  {
93  calibrationPrx = getProxy<visionx::StereoCalibrationInterfacePrx>(getProperty<std::string>("CalibrationProviderName").getValue());
94 
95  if (calibrationPrx)
96  {
97  applyCalibration(calibrationPrx);
98  }
99  else
100  {
101  ARMARX_WARNING << "Property CalibrationProviderName was given, but the proxy is not a StereoCalibrationInterfacePrx. Calibration not available!";
102  }
103  }
104  else
105  {
106  visionx::StereoCalibrationInterfacePrx calibrationInterface = visionx::StereoCalibrationInterfacePrx::checkedCast(imageProviderInfo.proxy);
107  if (calibrationInterface)
108  {
109  applyCalibration(calibrationInterface);
110  }
111  }
112 
113  ARMARX_INFO << "HorizontalViewAngle: " << fovH << " VerticalViewAngle: " << fovV;
114  cloud.reset(new pcl::PointCloud<PointL>());
115  transformedCloud.reset(new pcl::PointCloud<PointL>());
116 
117  debugObserver->setDebugDatafield(getName(), "processCount", new Variant(processCounter));
118 }
119 
121 {
124  for (size_t i = 0 ; i < numImages ; i++)
125  {
126  delete images[i];
127  }
128  delete [] images;
129 }
130 
132 {
133 
134 }
135 
136 
138 {
139  std::unique_lock lock(mutex);
140 
141  if (!waitForImages(1000))
142  {
143  ARMARX_INFO << deactivateSpam(300) << "Timeout or error while waiting for image data";
144  return;
145  }
146 
147  if (getImages(providerName, images, imageMetaInfo) != static_cast<int>(numImages))
148  {
149  ARMARX_WARNING << "Unable to transfer or read images";
150  return;
151  }
152 
153 
154  cloud->width = images[0]->width;
155  cloud->height = images[0]->height;
156  cloud->header.stamp = imageMetaInfo->timeProvided;
157  ARMARX_CHECK_EQUAL(getProperty<int>("PointCloudWidth").getValue(), images[0]->width);
158  ARMARX_CHECK_EQUAL(getProperty<int>("PointCloudHeight").getValue(), images[0]->height);
159  cloud->points.resize(images[0]->width * images[0]->height);
160  cloud->is_dense = true;
161 
162 
163  const float scaleX = std::tan(fovH * M_PI / 180.0 / 2.0) * 2.0;
164  const float scaleY = std::tan(fovV * M_PI / 180.0 / 2.0) * 2.0;
165 
166  const size_t width = static_cast<size_t>(images[0]->width);
167  const size_t height = static_cast<size_t>(images[0]->height);
168  const float halfWidth = (width / 2.0);
169  const float halfHeight = (height / 2.0);
170  const auto& image0Data = images[0]->pixels;
171  const auto& image1Data = images[1]->pixels;
172 
173  for (size_t j = 0; j < height; j++)
174  {
175  for (size_t i = 0; i < width; i++)
176  {
177  auto coord = j * width + i;
178  // unsigned short value = images[1]->pixels[3 * coord + 0]
179  // + (images[1]->pixels[3 * coord + 1] << 8);
180  auto value = visionx::tools::rgbToDepthValue(image1Data[3 * coord + 0], image1Data[3 * coord + 1], image1Data[3 * coord + 2]);
181 
182  if (maxDist > 0 && value > maxDist)
183  {
184  value = -1.0f;
185  }
186  else if (value < minDist)
187  {
188  value = -1.0f;
189  }
190 
191 
192  PointL& p = cloud->points.at(coord);
193  auto index = 3 * (coord);
194  p.r = image0Data[index + 0];
195  p.g = image0Data[index + 1];
196  p.b = image0Data[index + 2];
197 
198  if (value < 0)
199  {
200  if (nanValue >= 0)
201  {
202  p.z = static_cast<float>(nanValue);
203  //p.z /= 1000.0;
204  p.x = -1.0 * (i - halfWidth) / width * p.z * scaleX;
205  p.y = (halfHeight - j) / height * p.z * scaleY;
206  }
207  else
208  {
209  p.x = p.y = p.z = std::numeric_limits<float>::quiet_NaN();
210  }
211  }
212  else
213  {
214  p.z = static_cast<float>(value);
215  p.x = -1.0 * (i - halfWidth) / width * p.z * scaleX;
216  p.y = (halfHeight - j) / height * p.z * scaleY;
217  }
218 
219  if (numImages > 2)
220  {
221  auto& image2Data = images[2]->pixels;
222 
223  if (images[2]->bytesPerPixel == 3)
224  {
225  p.label = static_cast<unsigned int>(image2Data[index + 0] + (image2Data[index + 1] << 8) + (image2Data[index + 2] << 16));
226  }
227  else
228  {
229  p.label = static_cast<unsigned int>(image2Data[coord]);
230  }
231  }
232  else
233  {
234  p.label = 0;
235  }
236 
237 
238  }
239  }
240 
241  processCounter++;
242  debugObserver->setDebugDatafield(getName(), "processCount", new Variant(processCounter));
243 
244  float angle = getProperty<float>("PointCloudRotationZ").getValue() / 180.f * M_PI;
245  if (angle != 0.0f)
246  {
248  Eigen::Matrix3f m;
249  m = Eigen::AngleAxisf(angle,
250  Eigen::Vector3f::UnitZ());
251  transform2.block<3, 3>(0, 0) *= m;
252  pcl::transformPointCloud(*cloud, *transformedCloud, transform2);
253  transformedCloud->header.stamp = imageMetaInfo->timeProvided;
254  providePointCloud(transformedCloud);
255  }
256  else
257  {
258  providePointCloud(cloud);
259  }
260  // pcl::PointCloud<PointL>::Ptr temp(new pcl::PointCloud<PointL>());
261 
262 
263 }
264 
265 
266 
267 
268 visionx::MetaPointCloudFormatPtr ImageToPointCloud::getDefaultPointCloudFormat()
269 {
270  visionx::MetaPointCloudFormatPtr info = new visionx::MetaPointCloudFormat();
271  info->size = getProperty<int>("PointCloudWidth").getValue() * getProperty<int>("PointCloudHeight").getValue() * sizeof(PointL);
272  info->capacity = info->size;
273  info->type = visionx::PointContentType::eColoredLabeledPoints;
274  return info;
275 }
276 
277 
278 
279 
281 {
284 }
285 
armarx::Variant
The Variant class is described here: Variants.
Definition: Variant.h:224
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:180
visionx::ImageProviderInfo::numberImages
int numberImages
Number of images.
Definition: ImageProcessor.h:506
index
uint8_t index
Definition: EtherCATFrame.h:59
visionx::ImageProcessor::getImageProvider
ImageProviderInfo getImageProvider(std::string name, ImageType destinationImageType=eRgb, bool waitForProxy=false)
Select an ImageProvider.
Definition: ImageProcessor.cpp:152
armarx::Component::offeringTopicFromProperty
void offeringTopicFromProperty(const std::string &propertyName)
Offer a topic whose name is specified by the given property.
Definition: Component.cpp:154
armarx::ImageToPointCloud::createPropertyDefinitions
virtual armarx::PropertyDefinitionsPtr createPropertyDefinitions()
Definition: ImageToPointCloud.cpp:280
visionx::tools::createByteImage
CByteImage * createByteImage(const ImageFormatInfo &imageFormat, const ImageType imageType)
Creates a ByteImage for the destination type specified in the given imageProviderInfo.
visionx::PointCloudProvider::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: PointCloudProvider.cpp:95
cxxopts::empty
bool empty(const std::string &s)
Definition: cxxopts.hpp:255
armarx::Component::getTopicFromProperty
TopicProxyType getTopicFromProperty(const std::string &propertyName)
Get a topic proxy whose name is specified by the given property.
Definition: Component.h:218
armarx::ImageToPointCloud::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: ImageToPointCloud.cpp:120
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:523
armarx::ImageToPointCloud::process
void process() override
Process the vision component.
Definition: ImageToPointCloud.cpp:137
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:926
M_PI
#define M_PI
Definition: MathTools.h:17
armarx::ImageToPointCloudPropertyDefinitions
Definition: ImageToPointCloud.h:56
PCLUtilities.h
visionx::ImageProcessor::usingImageProvider
void usingImageProvider(std::string name)
Registers a delayed topic subscription and a delayed provider proxy retrieval which all will be avail...
Definition: ImageProcessor.cpp:117
visionx::ImageProcessor::getImages
int getImages(CByteImage **ppImages)
Poll images from provider.
Definition: ImageProcessor.cpp:351
ARMARX_CHECK_GREATER_EQUAL
#define ARMARX_CHECK_GREATER_EQUAL(lhs, rhs)
This macro evaluates whether lhs is greater or equal (>=) rhs and if it turns out to be false it will...
Definition: ExpressionException.h:123
armarx::ImageToPointCloud::onConnectImageProcessor
void onConnectImageProcessor() override
Implement this method in the ImageProcessor in order execute parts when the component is fully initia...
Definition: ImageToPointCloud.cpp:61
armarx::ImageToPointCloud::onInitImageProcessor
void onInitImageProcessor() override
Setup the vision component.
Definition: ImageToPointCloud.cpp:43
armarx::Component::getConfigIdentifier
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition: Component.cpp:74
GfxTL::Matrix3f
MatrixXX< 3, 3, float > Matrix3f
Definition: MatrixXX.h:600
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
visionx::ImageProviderInfo::proxy
ImageProviderInterfacePrx proxy
proxy to image provider
Definition: ImageProcessor.h:472
visionx::PointCloudProvider::providePointCloud
void providePointCloud(PointCloudPtrT pointCloudPtr)
offer the new point cloud.
Definition: PointCloudProvider.h:122
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
IceUtil::Handle< class PropertyDefinitionContainer >
ImageToPointCloud.h
ImageUtil.h
visionx::tools::rgbToDepthValue
float rgbToDepthValue(unsigned char r, unsigned char g, unsigned char b, bool noiseResistant=false)
Definition: ImageUtil.h:142
angle
double angle(const Point &a, const Point &b, const Point &c)
Definition: point.hpp:100
armarx::Logging::deactivateSpam
SpamFilterDataPtr deactivateSpam(float deactivationDurationSec=10.0f, const std::string &identifier="", bool deactivate=true) const
disables the logging for the current line for the given amount of seconds.
Definition: Logging.cpp:92
armarx::ManagedIceObject::getName
std::string getName() const
Retrieve name of object.
Definition: ManagedIceObject.cpp:107
min
T min(T t1, T t2)
Definition: gdiam.h:42
ARMARX_CHECK_EQUAL
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
Definition: ExpressionException.h:130
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
Variant.h
armarx::PointL
pcl::PointXYZRGBL PointL
Definition: TabletopSegmentation.h:75
armarx::ManagedIceObject::usingProxy
bool usingProxy(const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list.
Definition: ManagedIceObject.cpp:151
visionx::ImageProcessor::onDisconnectComponent
void onDisconnectComponent() override
Definition: ImageProcessor.cpp:83
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
armarx::ImageToPointCloud::getDefaultPointCloudFormat
virtual visionx::MetaPointCloudFormatPtr getDefaultPointCloudFormat()
default point cloud format used to initialize shared memory
Definition: ImageToPointCloud.cpp:268
armarx::ImageToPointCloud::onExitImageProcessor
void onExitImageProcessor() override
Exit the ImapeProcessor component.
Definition: ImageToPointCloud.cpp:131
visionx::ImageProcessor::waitForImages
bool waitForImages(int milliseconds=1000)
Wait for new images.
Definition: ImageProcessor.cpp:275