RCPointCloudProvider.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 VisionX::ArmarXObjects::RCPointCloudProvider
17  * @author Markus Grotz ( markus dot grotz at kit dot edu )
18  * @date 2017
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
23 #include "RCPointCloudProvider.h"
24 
25 #include <stdlib.h>
26 
27 #include <pcl/common/transforms.h>
28 
29 #include <VirtualRobot/MathTools.h>
30 
32 
34 
37 
38 #include <Calibration/Calibration.h>
39 #include <Calibration/StereoCalibration.h>
40 #include <Image/ImageProcessor.h>
41 #include <rc_genicam_api/buffer.h>
42 #include <rc_genicam_api/config.h>
43 #include <rc_genicam_api/image.h>
44 #include <rc_genicam_api/interface.h>
45 #include <rc_genicam_api/pixel_formats.h>
46 #include <rc_genicam_api/system.h>
47 
48 
49 using namespace visionx;
50 
51 namespace visionx
52 {
53 
54  using Point = pcl::PointXYZRGBA;
55  using PointCloud = pcl::PointCloud<Point>;
56 
57  // Our installed version is missing the getColor method
58  // From: https://github.com/roboception/rc_genicam_api/blob/f7f1621fc3ac5d638292e3d5d1ea9393959ecd9d/rc_genicam_api/image.cc
59  static void
60  rcg_getColor(uint8_t rgb[3],
61  const std::shared_ptr<const rcg::Image>& img,
62  uint32_t ds,
63  uint32_t i,
64  uint32_t k)
65  {
66  i *= ds;
67  k *= ds;
68 
69  if (img->getPixelFormat() == Mono8) // convert from monochrome
70  {
71  size_t lstep = img->getWidth() + img->getXPadding();
72  const uint8_t* p = img->getPixels() + k * lstep + i;
73 
74  uint32_t g = 0, n = 0;
75 
76  for (uint32_t kk = 0; kk < ds; kk++)
77  {
78  for (uint32_t ii = 0; ii < ds; ii++)
79  {
80  g += p[ii];
81  n++;
82  }
83 
84  p += lstep;
85  }
86 
87  rgb[2] = rgb[1] = rgb[0] = static_cast<uint8_t>(g / n);
88  }
89  else if (img->getPixelFormat() == YCbCr411_8) // convert from YUV
90  {
91  size_t lstep = (img->getWidth() >> 2) * 6 + img->getXPadding();
92  const uint8_t* p = img->getPixels() + k * lstep;
93 
94  uint32_t r = 0;
95  uint32_t g = 0;
96  uint32_t b = 0;
97  uint32_t n = 0;
98 
99  for (uint32_t kk = 0; kk < ds; kk++)
100  {
101  for (uint32_t ii = 0; ii < ds; ii++)
102  {
103  uint8_t v[3];
104  rcg::convYCbCr411toRGB(v, p, static_cast<int>(i + ii));
105 
106  r += v[0];
107  g += v[1];
108  b += v[2];
109  n++;
110  }
111 
112  p += lstep;
113  }
114 
115  rgb[0] = static_cast<uint8_t>(r / n);
116  rgb[1] = static_cast<uint8_t>(g / n);
117  rgb[2] = static_cast<uint8_t>(b / n);
118  }
119  }
120 
121  // Adapted from: https://github.com/roboception/rc_genicam_api/blob/master/tools/gc_pointcloud.cc
122  static void
123  storePointCloud(double f,
124  double t,
125  double scale,
126  std::shared_ptr<const rcg::Image> intensityCombined,
127  std::shared_ptr<const rcg::Image> disp,
128  PointCloud* outPoints)
129  {
130  // intensityCombined: Top half is the left image, bottom half the right image
131  // get size and scale factor between left image and disparity image
132 
133  size_t width = disp->getWidth();
134  size_t height = disp->getHeight();
135  bool bigendian = disp->isBigEndian();
136  size_t leftWidth = intensityCombined->getWidth();
137  size_t ds = (leftWidth + disp->getWidth() - 1) / disp->getWidth();
138 
139  // convert focal length factor into focal length in (disparity) pixels
140 
141  f *= width;
142 
143  // get pointer to disparity data and size of row in bytes
144 
145  const uint8_t* dps = disp->getPixels();
146  size_t dstep = disp->getWidth() * sizeof(uint16_t) + disp->getXPadding();
147 
148  // count number of valid disparities
149 
150  int n = 0;
151  for (size_t k = 0; k < height; k++)
152  {
153  int j = 0;
154  for (size_t i = 0; i < width; i++)
155  {
156  if ((dps[j] | dps[j + 1]) != 0)
157  {
158  n++;
159  }
160  j += 2;
161  }
162 
163  dps += dstep;
164  }
165 
166  dps = disp->getPixels();
167 
168  outPoints->clear();
169  outPoints->reserve(height * width);
170 
171  // create point cloud
172 
173  for (size_t k = 0; k < height; k++)
174  {
175  for (size_t i = 0; i < width; i++)
176  {
177  // convert disparity from fixed comma 16 bit integer into float value
178 
179  double d;
180  if (bigendian)
181  {
182  size_t j = i << 1;
183  d = scale * ((dps[j] << 8) | dps[j + 1]);
184  }
185  else
186  {
187  size_t j = i << 1;
188  d = scale * ((dps[j + 1] << 8) | dps[j]);
189  }
190 
191  // if disparity is valid and color can be obtained
192 
193  if (d > 0)
194  {
195  // reconstruct 3D point from disparity value
196 
197  double x = (i + 0.5 - 0.5 * width) * t / d;
198  double y = (k + 0.5 - 0.5 * height) * t / d;
199  double z = f * t / d;
200 
201  // compute size of reconstructed point
202 
203  // double x2=(i-0.5*width)*t/d;
204  // double size=2*1.4*std::abs(x2-x); // unused
205 
206  // get corresponding color value
207 
208  uint8_t rgb[3] = {0, 0, 0};
209  // FIXME: Replace with rcg::getColor once available
210  ::rcg_getColor(rgb,
211  intensityCombined,
212  static_cast<uint32_t>(ds),
213  static_cast<uint32_t>(i),
214  static_cast<uint32_t>(k));
215 
216  // store colored point
217  Point point;
218  const double meterToMillimeter = 1000.0f;
219  point.x = x * meterToMillimeter;
220  point.y = y * meterToMillimeter;
221  point.z = z * meterToMillimeter;
222  point.r = rgb[0];
223  point.g = rgb[1];
224  point.b = rgb[2];
225  point.a = 255;
226 
227  outPoints->push_back(point);
228  }
229  }
230 
231  dps += dstep;
232  }
233  }
234 
235  RCPointCloudProvider::RCPointCloudProvider() : intensityBuffer(50), disparityBuffer(25)
236  {
237  }
238 
239  void
241  {
244 
245  updateFinalCloudTransform(getProperty<float>("PointCloud_Scale_X").getValue(),
246  getProperty<float>("PointCloud_Scale_Y").getValue(),
247  getProperty<float>("PointCloud_Scale_Z").getValue(),
248  getProperty<float>("PointCloud_Rotate_Roll").getValue(),
249  getProperty<float>("PointCloud_Rotate_Pitch").getValue(),
250  getProperty<float>("PointCloud_Rotate_Yaw").getValue(),
251  getProperty<float>("PointCloud_Translate_X").getValue(),
252  getProperty<float>("PointCloud_Translate_Y").getValue(),
253  getProperty<float>("PointCloud_Translate_Z").getValue());
254  }
255 
256  void
258  {
261  createOrUpdateRemoteGuiTab(buildGui(),
262  [this](armarx::RemoteGui::TabProxy& prx) { processGui(prx); });
263  }
264 
265  void
267  {
270  }
271 
272  void
274  {
277  }
278 
279  void
281  {
282  using namespace visionx::roboception;
283 
284  if (!initDevice(getProperty<std::string>("DeviceId")))
285  {
286  getArmarXManager()->asyncShutdown();
287  return;
288  }
289  enableIntensity(false);
291  enableDisparity(true);
292  enableConfidence(false);
293  enableError(false);
294 
295  rcg::setString(nodemap, GC_COMPONENT_SELECTOR, "IntensityCombined", true);
296 
297  // Color format
298  if (rcg::setEnum(nodemap, "PixelFormat", "YCbCr411_8", false))
299  {
300  ARMARX_INFO << "Enabling color mode";
301  }
302  else
303  {
304  ARMARX_INFO << "Falling back to monochrome mode";
305  }
306 
307  setupStreamAndCalibration(getProperty<float>("ScaleFactor"),
308  "/tmp/armar6_rc_point_cloud_calibration.txt");
309 
310  std::string depthQuality = getProperty<std::string>("DepthImageResolution").getValue();
311  try
312  {
313  rcg::setEnum(nodemap, GC_DEPTH_QUALITY, depthQuality.c_str(), true);
314  }
315  catch (std::invalid_argument& e)
316  {
317  ARMARX_INFO << e.what();
318  ARMARX_WARNING << "Selected DepthImageResolution '" << depthQuality.c_str()
319  << "' is currently not available for this device. "
320  << "Falling back to '" << GC_DEPTH_QUALITY_HIGH << "' (640x480@3FPS).";
321  rcg::setEnum(nodemap, GC_DEPTH_QUALITY, GC_DEPTH_QUALITY_HIGH, true);
322  }
323  ARMARX_INFO << "Setting depth quality to " << rcg::getEnum(nodemap, GC_DEPTH_QUALITY)
324  << " (out of Low, Medium, High, Full)";
326 
327  frameRate = std::min(frameRate, getProperty<float>("framerate").getValue());
328  rcg::setFloat(nodemap, "AcquisitionFrameRate", frameRate);
330 
331  scan3dCoordinateScale =
332  rcg::getFloat(nodemap, "Scan3dCoordinateScale", nullptr, nullptr, true);
333 
335  setImageFormat(dimensions, visionx::eRgb, visionx::eBayerPatternRg);
336  setPointCloudSyncMode(visionx::eCaptureSynchronization);
337  }
338 
339  void
341  {
342  cleanupRC();
343  }
344 
345  void
347  {
348  startRC();
349  }
350 
351  void
353  {
354  stopRC();
355  }
356 
357  bool
359  {
360  const rcg::Buffer* buffer = stream->grab(10000);
361  if (!buffer)
362  {
363  ARMARX_WARNING << deactivateSpam(10) << "Unable to get image";
364  return false;
365  }
366 
367  // check for a complete image in the buffer
368 
369  if (buffer->getIsIncomplete() || !buffer->getImagePresent(0))
370  {
371  ARMARX_INFO << deactivateSpam(1) << "Waiting for image";
372  return false;
373  }
374 
375  // store image in the corresponding list
376 
377  uint64_t pixelformat = buffer->getPixelFormat(0);
378  if (pixelformat == Mono8 || pixelformat == YCbCr411_8)
379  {
380  intensityBuffer.add(buffer, 0);
381  }
382  else if (pixelformat == Coord3D_C16)
383  {
384  disparityBuffer.add(buffer, 0);
385  }
386  else
387  {
388  ARMARX_WARNING << "Unexpected pixel format: " << pixelformat;
389  return false;
390  }
391  // check if both lists contain an image with the current timestamp
392 
393  uint64_t timestamp = buffer->getTimestampNS();
394 
395  std::shared_ptr<const rcg::Image> intensityCombined = intensityBuffer.find(timestamp);
396  std::shared_ptr<const rcg::Image> disparity = disparityBuffer.find(timestamp);
397 
398  if (!intensityCombined || !disparity)
399  {
400  // Waiting for second synchronized image
401  return false;
402  }
403  updateTimestamp(buffer->getTimestamp());
404 
405  // compute and store point cloud from synchronized image pair
406 
407  PointCloud::Ptr pointCloud(new PointCloud());
408  storePointCloud(focalLengthFactor,
409  baseline,
410  scan3dCoordinateScale,
411  intensityCombined,
412  disparity,
413  pointCloud.get());
414 
415 
416  // Provide images
417  {
418  visionx::ImageFormatInfo imageFormat = getImageFormat();
419 
420  // ARMARX_LOG << "grabbing image " << imageFormat.dimension.width << "x" << imageFormat.dimension.height << " vs " << buffer->getWidth() << "x" << buffer->getHeight();
421 
422  int width = imageFormat.dimension.width;
423  int height = imageFormat.dimension.height;
424  if (scaleFactor > 1.0)
425  {
426  width *= scaleFactor;
427  height *= scaleFactor;
428  }
429 
430  //const int imageSize = imageFormat.dimension.width * imageFormat.dimension.height * imageFormat.bytesPerPixel;
431  const uint8_t* p = intensityCombined->getPixels();
432 
433  size_t px = intensityCombined->getXPadding();
434  uint64_t format = intensityCombined->getPixelFormat();
435 
436  for (size_t n = 0; n < numImages; n++)
437  {
438  //fillCameraImageRGB(cameraImages[n]->pixels, n, *intensityCombined);
439  fillCameraImageRGB(cameraImages[n]->pixels, n, p, width, height, format, px);
440  }
441 
442 
443  if (scaleFactor > 1.0)
444  {
445  ::ImageProcessor::Resize(cameraImages[0], smallImages[0]);
446  ::ImageProcessor::Resize(cameraImages[1], smallImages[1]);
448 
449  // armarx::SharedMemoryScopedWriteLockPtr lock(this->ImageProvider::sharedMemoryProvider->getScopedWriteLock());
450 
451  // for (size_t i = 0; i < numImages; i++)
452  // {
453  // memcpy(ppImageBuffers[i], smallImages[i]->pixels, imageSize);
454  // }
455  }
456  else
457  {
459  // for (size_t i = 0; i < numImages; i++)
460  // {
461  // memcpy(ppImageBuffers[i], cameraImages[i]->pixels, imageSize);
462  // }
463  }
464  }
465 
466  PointCloud::Ptr transformedPointCloud(new PointCloud());
467  const auto& tr = getFinalCloudTransform();
468  ARMARX_DEBUG << deactivateSpam(0.5) << "final transform =\n" << tr;
469  pcl::transformPointCloud(*pointCloud, *transformedPointCloud, tr);
470 
471  providePointCloud(transformedPointCloud);
472 
473  // remove all images from the buffer with the current or an older time stamp
474  intensityBuffer.removeOld(timestamp);
475  disparityBuffer.removeOld(timestamp);
476 
477  return true;
478  }
479 
482  {
485  }
486 
487  void
489  {
490  throw std::runtime_error("Not yet implemented");
491  }
492 
493  void
495  {
496  }
497 
498  void
500  {
501  }
502 
504  std::string prefix) :
505  armarx::ComponentPropertyDefinitions(prefix)
506  {
507  using namespace visionx::roboception;
508 
509  defineOptionalProperty<std::string>("DeviceId", "00_14_2d_2c_6e_ed", "");
510  defineOptionalProperty<float>("ScaleFactor", 2.0, "Image down scale factor");
511  defineOptionalProperty<float>("framerate",
512  25.0f,
513  "Frames per second, actual framerate is equal to min(this "
514  "framerate, framerate provided by the device)")
515  .setMatchRegex("\\d+(.\\d*)?")
516  .setMin(0.0f)
517  .setMax(25.0f);
518  defineOptionalProperty<bool>("isEnabled", true, "enable the capturing process immediately");
519  defineOptionalProperty<std::string>(
520  "DepthImageResolution",
521  "640x480@3Fps",
522  "Resolution of the depth image. "
523  "The higher the resolution, the lower the framerate provided by the device")
524  .setCaseInsensitive(true)
525  .map("214x160@25Fps", GC_DEPTH_QUALITY_LOW)
526  .map("320x240@15Fps", GC_DEPTH_QUALITY_MEDIUM)
527  .map("640x480@3Fps", GC_DEPTH_QUALITY_HIGH)
528  .map("1280x960@0.8Fps", GC_DEPTH_QUALITY_FULL);
529 
530  defineOptionalProperty<std::string>(
531  "ReferenceFrameName", "Roboception_LeftCamera", "Optional reference frame name.");
532 
533  defineOptionalProperty<float>("PointCloud_Scale_X", 1.0, "");
534  defineOptionalProperty<float>("PointCloud_Scale_Y", 1.0, "");
535  defineOptionalProperty<float>("PointCloud_Scale_Z", 1.0, "");
536  defineOptionalProperty<float>("PointCloud_Translate_X", 0, "");
537  defineOptionalProperty<float>("PointCloud_Translate_Y", 0, "");
538  defineOptionalProperty<float>("PointCloud_Translate_Z", 0, "");
539  defineOptionalProperty<float>("PointCloud_Rotate_Roll", 0, "");
540  defineOptionalProperty<float>("PointCloud_Rotate_Pitch", 0, "");
541  defineOptionalProperty<float>("PointCloud_Rotate_Yaw", 0, "");
542  }
543 
545  RCPointCloudProvider::buildGui()
546  {
547  const auto& srt = finalCloudTransform.getWriteBuffer();
548  ;
550  .cols(5)
551  .addTextLabel("Scale x/y/z")
552  .addChild(armarx::RemoteGui::makeFloatSpinBox("sx").decimals(4).min(0).max(1000).value(
553  srt(0)))
554  .addChild(armarx::RemoteGui::makeFloatSpinBox("sy").decimals(4).min(0).max(1000).value(
555  srt(1)))
556  .addChild(armarx::RemoteGui::makeFloatSpinBox("sz").decimals(4).min(0).max(1000).value(
557  srt(2)))
558  .addChild(new armarx::RemoteGui::HSpacer)
559 
560  .addTextLabel("Roll / Pitch / Yaw")
564  .addChild(new armarx::RemoteGui::HSpacer)
565 
566  .addTextLabel("Translate x/y/z")
567  .addChild(armarx::RemoteGui::makeFloatSpinBox("tx").value(srt(6)).min(-1000).max(1000))
568  .addChild(armarx::RemoteGui::makeFloatSpinBox("ty").value(srt(7)).min(-1000).max(1000))
569  .addChild(armarx::RemoteGui::makeFloatSpinBox("tz").value(srt(8)).min(-1000).max(1000))
570  .addChild(new armarx::RemoteGui::HSpacer);
571  }
572 
573  void
574  RCPointCloudProvider::processGui(armarx::RemoteGui::TabProxy& prx)
575  {
576  prx.receiveUpdates();
577  updateFinalCloudTransform(prx.getValue<float>("sx").get(),
578  prx.getValue<float>("sy").get(),
579  prx.getValue<float>("sz").get(),
580  prx.getValue<float>("rx").get(),
581  prx.getValue<float>("ry").get(),
582  prx.getValue<float>("rz").get(),
583  prx.getValue<float>("tx").get(),
584  prx.getValue<float>("ty").get(),
585  prx.getValue<float>("tz").get());
586  }
587 
588  void
589  RCPointCloudProvider::updateFinalCloudTransform(float sx,
590  float sy,
591  float sz,
592  float rx,
593  float ry,
594  float rz,
595  float tx,
596  float ty,
597  float tz)
598  {
599  finalCloudTransform.getWriteBuffer()(0) = sx;
600  finalCloudTransform.getWriteBuffer()(1) = sy;
601  finalCloudTransform.getWriteBuffer()(2) = sz;
602 
603  finalCloudTransform.getWriteBuffer()(3) = rx;
604  finalCloudTransform.getWriteBuffer()(4) = ry;
605  finalCloudTransform.getWriteBuffer()(5) = rz;
606 
607  finalCloudTransform.getWriteBuffer()(6) = tx;
608  finalCloudTransform.getWriteBuffer()(7) = ty;
609  finalCloudTransform.getWriteBuffer()(8) = tz;
610 
611  finalCloudTransform.commitWrite();
612  }
613 
615  RCPointCloudProvider::getFinalCloudTransform()
616  {
617  const auto& srt = finalCloudTransform.getUpToDateReadBuffer();
618  return VirtualRobot::MathTools::posrpy2eigen4f(
619  srt(6), srt(7), srt(8), srt(4), srt(5), srt(6)) *
620  Eigen::Vector4f{srt(0), srt(1), srt(2), 1.f}.asDiagonal();
621  }
622 } // namespace visionx
visionx::RoboceptionUser::stream
rcg::StreamPtr stream
Definition: RoboceptionUser.h:97
visionx::roboception::GC_DEPTH_QUALITY_HIGH
const char *const GC_DEPTH_QUALITY_HIGH
Definition: roboception_constants.h:17
visionx::RCPointCloudProvider::doCapture
bool doCapture() override
Main capturing function.
Definition: RCPointCloudProvider.cpp:358
visionx::PointCloudProvider::onConnectComponent
void onConnectComponent() override
Definition: PointCloudProvider.cpp:80
visionx::RoboceptionUser::cleanupRC
void cleanupRC()
Definition: RoboceptionUser.cpp:254
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
MiscLib::Vector::push_back
void push_back(const T &v)
Definition: Vector.h:354
visionx::RoboceptionUser::dimensions
visionx::ImageDimension dimensions
Definition: RoboceptionUser.h:108
visionx::roboception::GC_DEPTH_QUALITY
const char *const GC_DEPTH_QUALITY
Definition: roboception_constants.h:14
visionx::roboception::GC_DEPTH_QUALITY_MEDIUM
const char *const GC_DEPTH_QUALITY_MEDIUM
Definition: roboception_constants.h:16
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:650
visionx::CapturingPointCloudProvider::setPointCloudSyncMode
void setPointCloudSyncMode(ImageSyncMode pointCloudSyncMode)
Sets the point cloud synchronization mode.
Definition: CapturingPointCloudProvider.cpp:198
visionx::RoboceptionUser::nodemap
std::shared_ptr< GenApi::CNodeMapRef > nodemap
Definition: RoboceptionUser.h:98
WidgetBuilder.h
armarx::ManagedIceObject::getArmarXManager
ArmarXManagerPtr getArmarXManager() const
Returns the ArmarX manager used to add and remove components.
Definition: ManagedIceObject.cpp:360
visionx::ImageProvider::onExitComponent
void onExitComponent() override
Definition: ImageProvider.cpp:161
armarx::RemoteGui::detail::SimpleGridLayoutBuilder::addChild
SimpleGridLayoutBuilder & addChild(WidgetPtr const &child, int colspan)
Definition: LayoutWidgets.h:139
visionx::RCPointCloudProvider::onExitCapturingPointCloudProvider
void onExitCapturingPointCloudProvider() override
This is called when the Component::onExitComponent() setup is called.
Definition: RCPointCloudProvider.cpp:340
visionx::RoboceptionUser::enableError
void enableError(bool enabled)
Definition: RoboceptionUser.cpp:137
armarx::RemoteGuiComponentPluginUser::createOrUpdateRemoteGuiTab
void createOrUpdateRemoteGuiTab(Ts &&... ts)
Definition: RemoteGuiComponentPlugin.h:239
visionx::ImageProvider::setImageFormat
void setImageFormat(ImageDimension imageDimension, ImageType imageType, BayerPatternType bayerPatternType=visionx::eBayerPatternRg)
Sets the image basic format data.
Definition: ImageProvider.cpp:305
visionx::roboception
Definition: roboception_constants.h:6
magic_enum::detail::n
constexpr auto n() noexcept
Definition: magic_enum.hpp:418
visionx::roboception::GC_DEPTH_QUALITY_LOW
const char *const GC_DEPTH_QUALITY_LOW
Definition: roboception_constants.h:15
visionx::ImageProvider::getImageFormat
ImageFormatInfo getImageFormat(const Ice::Current &c=Ice::emptyCurrent) override
Returns the entire image format info struct via Ice.
Definition: ImageProvider.cpp:76
visionx::roboception::GC_DEPTH_QUALITY_FULL
const char *const GC_DEPTH_QUALITY_FULL
Definition: roboception_constants.h:18
armarx::RemoteGui::makeSimpleGridLayout
detail::SimpleGridLayoutBuilder makeSimpleGridLayout(std::string const &name="")
Definition: LayoutWidgets.h:274
visionx::ImageProvider::updateTimestamp
void updateTimestamp(Ice::Long timestamp, bool threadSafe=true)
Updates the timestamp of the currently captured image.
Definition: ImageProvider.cpp:175
visionx::PointCloudProvider::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: PointCloudProvider.cpp:101
visionx::PointCloudProvider::onExitComponent
void onExitComponent() override
Definition: PointCloudProvider.cpp:112
visionx::ImageProvider::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: ImageProvider.cpp:149
visionx::RCPointCloudProvider::onStartCapture
void onStartCapture(float frameRate) override
This is called when the point cloud provider capturing has been started.
Definition: RCPointCloudProvider.cpp:346
armarx::RemoteGui::TabProxy
Definition: WidgetProxy.h:17
visionx::RoboceptionUser::initDevice
bool initDevice(const std::string &dname)
Definition: RoboceptionUser.cpp:56
visionx::RCPointCloudProvider::onExitImageProvider
void onExitImageProvider() override
This is called when the Component::onExitComponent() setup is called.
Definition: RCPointCloudProvider.cpp:499
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:855
roboception_constants.h
visionx::RCPointCloudProvider::onInitComponent
void onInitComponent() override
Pure virtual hook for the subclass.
Definition: RCPointCloudProvider.cpp:240
armarx::RemoteGui::TabProxy::receiveUpdates
void receiveUpdates()
Definition: WidgetProxy.h:135
visionx::CapturingPointCloudProvider::frameRate
float frameRate
Required frame rate.
Definition: CapturingPointCloudProvider.h:220
M_PI
#define M_PI
Definition: MathTools.h:17
visionx::RCPointCloudProvider::startCaptureForNumFrames
void startCaptureForNumFrames(Ice::Int, const Ice::Current &) override
Definition: RCPointCloudProvider.cpp:488
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:184
visionx::RCPointCloudProvider::onExitComponent
void onExitComponent() override
Hook for subclass.
Definition: RCPointCloudProvider.cpp:273
Point
Definition: PointCloud.h:21
visionx::RCPointCloudProvider::onInitImageProvider
void onInitImageProvider() override
This is called when the Component::onInitComponent() is called.
Definition: RCPointCloudProvider.cpp:494
visionx::RoboceptionUser::enableDisparity
void enableDisparity(bool enabled)
Definition: RoboceptionUser.cpp:123
visionx::PointCloudProvider::onInitComponent
void onInitComponent() override
Definition: PointCloudProvider.cpp:61
visionx::RoboceptionUser::cameraImages
CByteImage ** cameraImages
Definition: RoboceptionUser.h:105
timestamp
std::string timestamp()
Definition: CartographerAdapter.cpp:85
visionx::roboception::DepthQualityToFPS
const std::map< std::string, float > DepthQualityToFPS
Definition: roboception_constants.cpp:5
visionx::RoboceptionUser::baseline
double baseline
Definition: RoboceptionUser.h:103
visionx::RoboceptionUser::numImages
size_t numImages
Definition: RoboceptionUser.h:100
max
T max(T t1, T t2)
Definition: gdiam.h:51
visionx::RCPointCloudProvider::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: RCPointCloudProvider.cpp:481
visionx::roboception::GC_COMPONENT_SELECTOR
const char *const GC_COMPONENT_SELECTOR
Definition: roboception_constants.h:9
armarx::RemoteGui::detail::SimpleGridLayoutBuilder::addTextLabel
SimpleGridLayoutBuilder & addTextLabel(std::string const &text, int colspan)
Definition: LayoutWidgets.h:150
visionx::ImageProvider::provideImages
void provideImages(void **inputBuffers, const IceUtil::Time &imageTimestamp=IceUtil::Time())
send images raw.
Definition: ImageProvider.cpp:351
visionx::RCPointCloudProvider::onConnectComponent
void onConnectComponent() override
Pure virtual hook for the subclass.
Definition: RCPointCloudProvider.cpp:257
visionx::RoboceptionUser::startRC
void startRC()
Definition: RoboceptionUser.cpp:237
armarx::WidgetDescription::WidgetPtr
::IceInternal::Handle<::armarx::WidgetDescription::Widget > WidgetPtr
Definition: NJointControllerBase.h:67
visionx::PointCloud
pcl::PointCloud< Point > PointCloud
Definition: RCPointCloudProvider.cpp:55
visionx::ImageProvider::setNumberImages
void setNumberImages(int numberImages)
Sets the number of images on each capture.
Definition: ImageProvider.cpp:344
armarx::RemoteGui::TabProxy::getValue
ValueProxy< T > getValue(std::string const &name)
Definition: WidgetProxy.h:167
PointCloud
Definition: PointCloud.h:85
armarx::Component::getConfigIdentifier
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition: Component.cpp:79
MiscLib::Vector::reserve
void reserve(size_type s)
Definition: Vector.h:189
armarx::ctrlutil::v
double v(double t, double v0, double a0, double j)
Definition: CtrlUtil.h:39
visionx::PointCloudProvider::providePointCloud
void providePointCloud(PointCloudPtrT pointCloudPtr)
offer the new point cloud.
Definition: PointCloudProvider.h:122
visionx::ImageProvider::onConnectComponent
void onConnectComponent() override
Definition: ImageProvider.cpp:107
RCPointCloudProvider.h
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:181
visionx::RCPointCloudProvider::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: RCPointCloudProvider.cpp:266
VAROUT
#define VAROUT(x)
Definition: StringHelpers.h:198
visionx::RoboceptionUser::enableIntensity
void enableIntensity(bool enabled)
Definition: RoboceptionUser.cpp:109
IceUtil::Handle< class PropertyDefinitionContainer >
armarx::RemoteGui::detail::SimpleGridLayoutBuilder::cols
SimpleGridLayoutBuilder & cols(int n)
Definition: LayoutWidgets.h:123
visionx::ImageProvider::onInitComponent
void onInitComponent() override
Definition: ImageProvider.cpp:91
visionx::RoboceptionUser::enableConfidence
void enableConfidence(bool enabled)
Definition: RoboceptionUser.cpp:130
armarx::VariantType::Int
const VariantTypeId Int
Definition: Variant.h:917
visionx::RoboceptionUser::enableIntensityCombined
void enableIntensityCombined(bool enabled)
Definition: RoboceptionUser.cpp:116
visionx::RCPointCloudProvider::RCPointCloudProvider
RCPointCloudProvider()
Definition: RCPointCloudProvider.cpp:235
visionx::RoboceptionUser::smallImages
CByteImage ** smallImages
Definition: RoboceptionUser.h:106
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:99
visionx::RoboceptionUser::setupStreamAndCalibration
void setupStreamAndCalibration(float scalefactor, const std::string &calibSavePath)
Definition: RoboceptionUser.cpp:144
TypeMapping.h
visionx::RoboceptionUser::focalLengthFactor
double focalLengthFactor
Definition: RoboceptionUser.h:102
visionx::RCPointCloudProviderPropertyDefinitions
Definition: RCPointCloudProvider.h:58
min
T min(T t1, T t2)
Definition: gdiam.h:44
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:193
armarx::PropertyDefinitionsPtr
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
Definition: forward_declarations.h:35
visionx::RCPointCloudProvider::onStopCapture
void onStopCapture() override
This is called when the point cloud provider capturing has been stopped.
Definition: RCPointCloudProvider.cpp:352
ArmarXDataPath.h
visionx::RoboceptionUser::fillCameraImageRGB
static void fillCameraImageRGB(unsigned char *outputPixels, size_t nImage, const uint8_t *inputPixels, size_t width, size_t height, uint64_t pixelFormat, size_t xpadding)
Definition: RoboceptionUser.cpp:296
armarx::RemoteGui::makeFloatSpinBox
detail::FloatSpinBoxBuilder makeFloatSpinBox(std::string const &name)
Definition: FloatWidgets.h:58
visionx::RCPointCloudProviderPropertyDefinitions::RCPointCloudProviderPropertyDefinitions
RCPointCloudProviderPropertyDefinitions(std::string prefix)
Definition: RCPointCloudProvider.cpp:503
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:27
MiscLib::Vector::clear
void clear()
Definition: Vector.h:175
visionx::RoboceptionUser::stopRC
void stopRC()
Definition: RoboceptionUser.cpp:246
visionx::RoboceptionUser::scaleFactor
float scaleFactor
Definition: RoboceptionUser.h:101
visionx::RCPointCloudProvider::onInitCapturingPointCloudProvider
void onInitCapturingPointCloudProvider() override
This is called when the Component::onInitComponent() is called.
Definition: RCPointCloudProvider.cpp:280