PointCloudFilter.cpp
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::PointCloudFilter
19  * @author Markus Grotz ( markus dot grotz at kit dot edu )
20  * @date 2016
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 
25 #include "PointCloudFilter.h"
26 
27 #include <pcl/common/colors.h>
28 #include <pcl/filters/statistical_outlier_removal.h>
29 #include <pcl/surface/convex_hull.h>
30 
31 #include <SimoxUtility/math/convert/mat4f_to_pos.h>
32 #include <SimoxUtility/math/convert/mat4f_to_rpy.h>
33 #include <SimoxUtility/math/convert/pos_rpy_to_mat4f.h>
34 #include <VirtualRobot/CollisionDetection/CollisionModel.h>
35 #include <VirtualRobot/MathTools.h>
36 #include <VirtualRobot/math/Helpers.h>
37 
39 
42 
45 
47 
48 
49 using namespace armarx;
50 
51 namespace visionx
52 {
53 
54  PointCloudFilterPropertyDefinitions::PointCloudFilterPropertyDefinitions(std::string prefix) :
56  {
57  defineOptionalProperty<std::string>(
58  "RobotStateComponentName", "RobotStateComponent", "Name of the robot state component.");
59 
60  defineOptionalProperty<bool>(
61  "sourceFrameNameAuto",
62  true,
63  "If enabled, try to get and use source frame name from point cloud provider.");
64  defineOptionalProperty<std::string>(
65  "sourceFrameName", "DepthCamera", "The source frame name.");
66  defineOptionalProperty<std::string>("targetFrameName", "Global", "The target frame name.");
67 
68  defineOptionalProperty<std::string>(
69  "PointCloudFormat",
70  "XYZRGBA",
71  "Format of the input and output point cloud (XYZRGBA, XYZL, XYZRGBL).");
72 
73  defineOptionalProperty<bool>("EnableDownsampling", true, "Enable/disable downsampling.");
74  defineOptionalProperty<float>("leafSize", 5.0f, "The voxel grid leaf size.");
75 
76 
77  defineOptionalProperty<bool>("StatisticalOutlierRemoval_enabled",
78  false,
79  "Enable StatisticalOutlierRemoval (pre downsampling)");
80  defineOptionalProperty<int>(
81  "StatisticalOutlierRemoval_MeanK",
82  50,
83  "(pcl parameter) number of nearest neighbors to use for mean distance estimation. ");
84  defineOptionalProperty<float>("StatisticalOutlierRemoval_StddevMulThresh",
85  1,
86  "(pcl parameter) standard deviation multiplier for the "
87  "distance threshold calculation. ");
88 
89  defineOptionalProperty<bool>("EnableCropping", true, "Enable/disable cropping.");
90  defineOptionalPropertyVector<Eigen::Vector3f>("minPoint",
91  Eigen::Vector3f(-1000.0f, -1000.0f, 0.0f),
92  "Minimal point of cropping box.",
93  ',');
94  defineOptionalPropertyVector<Eigen::Vector3f>("maxPoint",
95  Eigen::Vector3f(4800.0f, 11500.0f, 1800.0f),
96  "Maximal point of cropping box.",
97  ',');
98  defineOptionalPropertyVector<Eigen::Vector3f>(
99  "rpy",
100  {0, 0, 0},
101  "Roll, Pitch and Yaw applied to the points in the croping frame",
102  ',');
103 
104  defineOptionalPropertyVector<Eigen::Vector3f>(
105  "ProviderFrameTranslation", Eigen::Vector3f(0.0f, 0.0f, 0.0f), "", ',');
106  defineOptionalPropertyVector<Eigen::Vector3f>(
107  "ProviderFrameRotation", Eigen::Vector3f(0.0f, 0.0f, 0.0f), "", ',');
108 
109  defineOptionalProperty<std::string>(
110  "croppingFrame", "Global", "The coordinate frame in which cropping is applied.");
111 
112  defineOptionalProperty<bool>("applyCollisionModelFilter",
113  true,
114  "Discard points that appear to belong to the robot itself.");
115 
116  defineOptionalProperty<std::string>(
117  "RemoteGuiName", "RemoteGuiProvider", "Name of the remote GUI provider");
118 
119  defineOptionalProperty<bool>("reportCloudOutsideOfCroppingArea",
120  false,
121  "If cropping is enabled, the points outside of the area are "
122  "reported in a separate cloud");
123  }
124 
125  std::string
127  {
128  return "PointCloudFilter";
129  }
130 
131  std::string
133  {
134  std::unique_lock lock(parametersMutex);
135  return parameters.targetFrameName;
136  }
137 
138  void
140  const Vector3BasePtr& max,
141  const std::string& frame,
142  const Ice::Current&)
143  {
144  std::unique_lock lock(parametersMutex);
145  parameters.croppingEnabled = true;
146  parameters.croppingMinPoint = Vector3Ptr::dynamicCast(min)->toEigen();
147  parameters.croppingMaxPoint = Vector3Ptr::dynamicCast(max)->toEigen();
148  parameters.croppingFrameName = frame;
149  }
150 
151  void
153  {
154  getProperty(pointCloudFormat, "PointCloudFormat");
155 
156 
157  getProperty(parameters.sourceFrameName, "sourceFrameName");
158  getProperty(parameters.targetFrameName, "targetFrameName");
159 
160  getProperty(parameters.croppingEnabled, "EnableCropping");
161  getProperty(parameters.croppingFrameName, "croppingFrame");
162  getProperty(parameters.croppingMinPoint, "minPoint");
163  getProperty(parameters.croppingMaxPoint, "maxPoint");
164  getProperty(parameters.croppingRPY, "rpy");
165 
166  getProperty(parameters.downsamplingEnabled, "EnableDownsampling");
167  getProperty(parameters.gridLeafSize, "leafSize");
168 
169  getProperty(parameters.statisticalOutlierRemoval.enabled,
170  "StatisticalOutlierRemoval_enabled");
171  getProperty(parameters.statisticalOutlierRemoval.meanK, "StatisticalOutlierRemoval_MeanK");
172  getProperty(parameters.statisticalOutlierRemoval.stddevMulThresh,
173  "StatisticalOutlierRemoval_StddevMulThresh");
174 
175  {
176  parameters.providerFrameTransformation = simox::math::pos_rpy_to_mat4f(
177  getProperty<Eigen::Vector3f>("ProviderFrameTranslation").getValue(),
178  getProperty<Eigen::Vector3f>("ProviderFrameRotation").getValue());
179  }
180 
181  std::string robotStateComponentName = getProperty<std::string>("RobotStateComponentName");
182  if (!robotStateComponentName.empty())
183  {
184  usingProxyFromProperty("RobotStateComponentName");
185  }
186  else
187  {
188  ARMARX_INFO << "No RobotStateComponent configured, not performing any point cloud "
189  "transformations.";
190  }
191 
192  getProperty(parameters.applyCollisionModelFilter, "applyCollisionModelFilter");
193  getProperty(parameters.reportCloudOutsideOfCroppingArea,
194  "reportCloudOutsideOfCroppingArea");
195  if (parameters.applyCollisionModelFilter && robotStateComponentName.empty())
196  {
197  ARMARX_WARNING << "Collision model filter activated, but no RobotStateComponent "
198  "configured, deactivating collision model filtering";
199  parameters.applyCollisionModelFilter = false;
200  }
201 
202  debugDrawer.setLayer(getName());
203  debugDrawer.offeringTopic(*this);
204  debugDrawer.setEnabled(false);
205  }
206 
207  void
209  {
210  const std::string robotStateComponentName =
211  getProperty<std::string>("RobotStateComponentName");
212  if (!robotStateComponentName.empty())
213  {
214  getProxy(robotStateComponent, robotStateComponentName);
215  localRobot = RemoteRobot::createLocalCloneFromFile(
216  robotStateComponent, VirtualRobot::RobotIO::RobotDescription::eStructure);
217  }
218 
219  {
220  const std::vector<std::string> providerNames = getPointCloudProviderNames();
221  ARMARX_CHECK_EQUAL(providerNames.size(), 1);
222 
223  this->providerSourceFrameName = getPointCloudFrame(providerNames.front());
224  if (getProperty<bool>("sourceFrameNameAuto") && !providerSourceFrameName.empty())
225  {
226  ARMARX_INFO << "Using source frame '" << providerSourceFrameName
227  << "' from provider '" << providerNames.front() << "'.";
228  this->parameters.sourceFrameName = providerSourceFrameName;
229  }
230  }
231 
232  if (pointCloudFormat == "XYZRGBA")
233  {
234  enableResultPointClouds<pcl::PointXYZRGBA>(getName() + "Result");
235  enableResultPointClouds<pcl::PointXYZRGBA>(getName() + "Outside");
236  }
237  else if (pointCloudFormat == "XYZL")
238  {
239  enableResultPointClouds<pcl::PointXYZL>(getName() + "Result");
240  enableResultPointClouds<pcl::PointXYZL>(getName() + "Outside");
241  }
242  else if (pointCloudFormat == "XYZRGBL")
243  {
244  enableResultPointClouds<pcl::PointXYZRGBL>(getName() + "Result");
245  enableResultPointClouds<pcl::PointXYZRGBL>(getName() + "Outside");
246  }
247  else
248  {
249  ARMARX_ERROR << "Could not initialize point cloud, because format '" << pointCloudFormat
250  << "' is unknown."
251  << "\nKnown formats are: XYZL, XYZRGBA, XYZGBL.";
252  }
253 
254  getProxyFromProperty(remoteGui, "RemoteGuiName", false, "", false);
255  if (remoteGui)
256  {
257  remoteGuiCreate();
258  remoteGuiTask = new armarx::SimpleRunningTask<>([this]() { this->remoteGuiRun(); },
259  "RemoteGuiTask");
260  remoteGuiTask->start();
261  }
262 
263  debugDrawer.getTopic(*this);
264  // Clear the layer (disregarding whether debug drawer is enabled).
265  debugDrawer.getTopic()->clearLayer(debugDrawer.getLayer());
266  }
267 
268  void
270  {
271  }
272 
273  void
275  {
276  if (pointCloudFormat == "XYZRGBA")
277  {
278  processPointCloud<pcl::PointXYZRGBA>();
279  }
280  else if (pointCloudFormat == "XYZL")
281  {
282  processPointCloud<pcl::PointXYZL>();
283  }
284  else if (pointCloudFormat == "XYZRGBL")
285  {
286  processPointCloud<pcl::PointXYZRGBL>();
287  }
288  else
289  {
290  ARMARX_ERROR << "Could not process point cloud, because format '" << pointCloudFormat
291  << "' is unknown."
292  << "\nKnown formats are: XYZL, XYZRGBA, XYZRGBL.";
293  }
294  }
295 
296  void
298  {
299  if (remoteGuiTask)
300  {
301  remoteGuiTask->stop();
302  remoteGuiTask = nullptr;
303  }
304  if (remoteGui)
305  {
306  remoteGui->removeTab(getName());
307  }
308  }
309 
310  static std::string
311  toUpper(const std::string& string)
312  {
313  std::string upper;
314  std::transform(string.begin(), string.end(), std::back_inserter(upper), ::toupper);
315  return upper;
316  }
317 
318  template <typename PointT>
319  void
321  {
322  using PointCloudPtr = typename pcl::PointCloud<PointT>::Ptr;
323 
324  // Get current parameters.
325  Parameters params;
326  {
327  std::unique_lock lock(parametersMutex);
328  params = this->parameters;
329  }
330 
331  // Only input cloud manages frame.
332  FramedPointCloud<PointT> inputCloud(params.sourceFrameName);
333  PointCloudPtr tempCloud(new pcl::PointCloud<PointT>());
334  FramedPointCloud<PointT> outsideCloud(params.sourceFrameName);
335 
336  if (waitForPointClouds(10000))
337  {
338  getPointClouds(inputCloud.cloud);
339  }
340  else
341  {
342  ARMARX_VERBOSE << "Timeout or error while waiting for point cloud data.";
343  return;
344  }
345 
346  const uint32_t originalWidth = inputCloud.cloud->width;
347  const uint32_t originalHeight = inputCloud.cloud->height;
348 
349  // Synchronize robot.
350  if (robotStateComponent)
351  {
352  // visionx::MetaPointCloudFormatPtr format = getPointCloudFormat(providerName);
353  // Use timestamp from point cloud instead of format->timeProvided
354 
355  long timestampMicroseconds = static_cast<long>(inputCloud.cloud->header.stamp);
356  // RemoteRobot::synchronizeLocalCloneToTimestamp(localRobot, robotStateComponent, timestampMicroseconds);
357  (void)timestampMicroseconds;
358  RemoteRobot::synchronizeLocalClone(localRobot, robotStateComponent);
359  }
360 
361  if (params.statisticalOutlierRemoval.enabled)
362  {
363  // Perform downsampling.
364  ARMARX_DEBUG << "statisticalOutlierRemoval ...";
365  pcl::StatisticalOutlierRemoval<PointT> sor;
366  sor.setMeanK(params.statisticalOutlierRemoval.meanK);
367  sor.setStddevMulThresh(params.statisticalOutlierRemoval.stddevMulThresh);
368 
369  sor.setInputCloud(inputCloud.cloud);
370  tempCloud->clear();
371  sor.filter(*tempCloud);
372  tempCloud.swap(inputCloud.cloud);
373  }
374 
375  if (params.downsamplingEnabled)
376  {
377  // Perform downsampling.
378  ARMARX_DEBUG << "Downsample ...";
379  pcl::ApproximateVoxelGrid<PointT> grid;
380  grid.setLeafSize(params.gridLeafSize, params.gridLeafSize, params.gridLeafSize);
381  grid.setInputCloud(inputCloud.cloud);
382 
383  tempCloud->clear();
384  grid.filter(*tempCloud);
385 
386  tempCloud.swap(inputCloud.cloud);
387  }
388 
389  drawFrame(inputCloud.getFramedPose(localRobot), "source");
390 
391  ARMARX_DEBUG << "transformBy\n" << params.providerFrameTransformation;
392  inputCloud.transformBy(params.providerFrameTransformation);
393 
394 
395  if (params.croppingEnabled)
396  {
397  try
398  {
399  // Transform to cropping frame.
400  changePointCloudFrame(inputCloud, "cropping", params.croppingFrameName);
401  }
402  catch (const armarx::LocalException& e)
403  {
405  << "Caught armarx::LocalException (stopping processing).\n"
406  << e.what();
407  return;
408  }
409 
410 
411  // Perform cropping.
412  ARMARX_DEBUG << "Crop ...";
413 
414  tempCloud->clear();
415  outsideCloud.cloud->clear();
416  outsideCloud.setFrameWithoutTransformation(inputCloud.getFrame());
417  const Eigen::Matrix3f transform =
418  VirtualRobot::MathTools::rpy2eigen3f(params.croppingRPY).inverse();
419  for (const auto& p : inputCloud.cloud->points)
420  {
421  const Eigen::Vector3f transfed = transform * Eigen::Vector3f{p.x, p.y, p.z};
422  if (transfed(0) >= params.croppingMinPoint(0) &&
423  transfed(0) <= params.croppingMaxPoint(0) &&
424  transfed(1) >= params.croppingMinPoint(1) &&
425  transfed(1) <= params.croppingMaxPoint(1) &&
426  transfed(2) >= params.croppingMinPoint(2) &&
427  transfed(2) <= params.croppingMaxPoint(2))
428  {
429  tempCloud->push_back(p);
430  }
431  else if (params.reportCloudOutsideOfCroppingArea)
432  {
433  outsideCloud.cloud->push_back(p);
434  }
435  }
436  tempCloud.swap(inputCloud.cloud);
437  }
438 
439  if (debugDrawer.enabled())
440  {
441  // Draw crop box.
442  Eigen::Matrix32f aabb;
443  aabb.col(0) = params.croppingMinPoint;
444  aabb.col(1) = params.croppingMaxPoint;
445  debugDrawer.drawBoxEdges("cropBox",
446  aabb,
447  inputCloud.getGlobalPose(localRobot) *
448  VirtualRobot::MathTools::rpy2eigen4f(params.croppingRPY));
449  }
450  else
451  {
452  debugDrawer.removeboxEdges("cropBox");
453  }
454 
455  const bool collisionModelFilterEnabled =
456  params.applyCollisionModelFilter && robotStateComponent;
457  if (collisionModelFilterEnabled)
458  {
459  // This requires inputCloud to be in global frame.
460  changePointCloudFrame(inputCloud, "collision model filter", armarx::GlobalFrame);
461  if (params.reportCloudOutsideOfCroppingArea)
462  {
463  changePointCloudFrame(outsideCloud, "collision model filter", armarx::GlobalFrame);
464  }
465 
466  ARMARX_DEBUG << "Apply collision model filter ...";
467 
468  PointCloudPtr collisionCloudPtr(new pcl::PointCloud<PointT>());
469 
470  for (VirtualRobot::CollisionModelPtr collisionModel : localRobot->getCollisionModels())
471  {
472  std::vector<Eigen::Vector3f> vertices = collisionModel->getModelVeticesGlobal();
473 
474  pcl::PointCloud<PointT> hullCloud;
475  hullCloud.width = static_cast<uint32_t>(vertices.size());
476  hullCloud.height = 1;
477  hullCloud.points.resize(vertices.size());
478  for (size_t i = 0; i < vertices.size(); ++i)
479  {
480  hullCloud.points[i].getVector3fMap() = vertices[i].cast<float>();
481  }
482 
483  (*collisionCloudPtr) += hullCloud;
484  }
485 
486  pcl::ConvexHull<PointT> hull;
487  hull.setInputCloud(collisionCloudPtr);
488  hull.setDimension(3);
489 
490  std::vector<pcl::Vertices> polygons;
491  PointCloudPtr surfaceHull(new pcl::PointCloud<PointT>);
492  hull.reconstruct(*surfaceHull, polygons);
493 
494  pcl::CropHull<PointT> cropHull;
495  cropHull.setDim(3);
496  cropHull.setHullIndices(polygons);
497  cropHull.setHullCloud(surfaceHull);
498  cropHull.setCropOutside(false); // Remove points inside hull.
499  cropHull.setInputCloud(inputCloud.cloud);
500 
501  tempCloud->clear();
502  cropHull.filter(*tempCloud);
503 
504  tempCloud.swap(inputCloud.cloud);
505 
506  if (params.reportCloudOutsideOfCroppingArea)
507  {
508  cropHull.setInputCloud(outsideCloud.cloud);
509  tempCloud->clear();
510  cropHull.filter(*tempCloud);
511  tempCloud.swap(outsideCloud.cloud);
512  }
513  }
514 
515  // Transform to target.
516  try
517  {
518  // Transform to target frame.
519  changePointCloudFrame(inputCloud, "target", params.targetFrameName);
520  if (params.reportCloudOutsideOfCroppingArea)
521  {
522  changePointCloudFrame(
523  outsideCloud, "collision model filter", params.targetFrameName);
524  }
525  }
526  catch (const armarx::LocalException& e)
527  {
529  << "Caught armarx::LocalException (stopping processing).\n"
530  << e.what();
531  return;
532  }
533 
534  // Provide result.
535  PointCloudPtr resultCloud = inputCloud.cloud;
536 
537  ARMARX_DEBUG << deactivateSpam(5) << "Input cloud " << originalWidth << " x "
538  << originalHeight << " --> Filtered cloud " << resultCloud->width << " x "
539  << resultCloud->height;
540 
541  provideResultPointClouds(getName() + "Result", resultCloud);
542  provideResultPointClouds(getName() + "Outside", outsideCloud.cloud);
543  }
544 
545  void
546  PointCloudFilter::drawFrame(const FramedPose& frame, const std::string& role)
547  {
548  if (debugDrawer.enabled())
549  {
550  debugDrawer.drawPose(toUpper(role) + " (" + frame.getFrame() + ")", frame.toEigen());
551  }
552  }
553 
554  template <typename PointT>
555  void
556  PointCloudFilter::changePointCloudFrame(FramedPointCloud<PointT>& pointCloud,
557  const std::string& role,
558  const std::string& frame)
559  {
560  ARMARX_DEBUG << "Transform from " << pointCloud.getFrame() << " to " << toUpper(role)
561  << " (" << frame << ")";
562  pointCloud.changeFrame(frame, localRobot);
563  drawFrame(pointCloud.getFramedPose(localRobot), role);
564  }
565 
568  {
571  }
572 
573  void
574  PointCloudFilter::remoteGuiCreate()
575  {
576  using namespace armarx::RemoteGui;
577 
578  const auto& p = parameters;
579 
580  auto rootLayout = makeVBoxLayout();
581 
582  // Misc
583  {
584  rootLayout.addChild(
586  .cols(2)
587  .addChild(makeTextLabel("Source Frame: "))
588  .addChild(makeHBoxLayout()
589  .addChild(makeCheckBox("SourceFrameAutoEnabled")
590  .label("Auto")
591  .value(getProperty<bool>("sourceFrameNameAuto")))
592  .addChild(makeComboBox("SourceFrame")
593  .addOptions({armarx::GlobalFrame, "root"})
594  .addOptions(localRobot->getRobotNodeNames())
595  .value(p.sourceFrameName)))
596 
597  .addChild(makeTextLabel("Target Frame: "))
598  .addChild(makeComboBox("TargetFrame")
599  .options({armarx::GlobalFrame, "root"})
600  .addOptions(localRobot->getRobotNodeNames())
601  .value(p.targetFrameName))
602 
603  .addChild(makeTextLabel("StatisticalOutlierRemoval: "))
604  .addChild(
606  .addChild(makeCheckBox("StatisticalOutlierRemoval_enabled")
607  .label("Enabled")
608  .value(p.statisticalOutlierRemoval.enabled))
609  .addChild(makeTextLabel("MeanK"))
610  .addChild(makeIntSpinBox("StatisticalOutlierRemoval_MeanK")
611  .min(1)
612  .max(1000)
613  .value(p.statisticalOutlierRemoval.meanK))
614  .addChild(makeTextLabel("StddevMulThresh"))
615  .addChild(makeFloatSpinBox("StatisticalOutlierRemoval_StddevMulThresh")
616  .min(0.001f)
617  .max(100.f)
618  .decimals(3)
619  .value(p.statisticalOutlierRemoval.stddevMulThresh)))
620 
621  .addChild(makeTextLabel("Downsampling: "))
622  .addChild(makeHBoxLayout()
623  .addChild(makeCheckBox("DownsamplingEnabled")
624  .label("Enabled")
625  .value(p.downsamplingEnabled))
626  .addChild(makeTextLabel("Grid Leaf Size: "))
627  .addChild(makeFloatSpinBox("DownsamplingGridLeafSize")
628  .min(0.1f)
629  .max(1000.f)
630  .decimals(1)
631  .value(p.gridLeafSize)))
632 
633  .addChild(makeTextLabel("Collision Model Filter: "))
634  .addChild(makeCheckBox("CollisionModelFilterEnabled")
635  .label("Enabled")
636  .value(p.applyCollisionModelFilter)));
637  }
638 
639  //transform
640  {
641  const Eigen::Vector3f pos = simox::math::mat4f_to_pos(p.providerFrameTransformation);
642  const Eigen::Vector3f rpy = simox::math::mat4f_to_rpy(p.providerFrameTransformation);
643 
644  rootLayout.addChild(makeGroupBox("Transform")
645  .addChild(makeSimpleGridLayout()
646  .cols(2)
647  .addTextLabel("XYC")
648  .addChild(makeVector3fSpinBoxes("transform.XYC")
649  .value(pos)
650  .min(-10000)
651  .max(10000)
652  .decimals(3))
653  .addTextLabel("RPY")
654  .addChild(makeVector3fSpinBoxes("transform.RPY")
655  .value(rpy)
656  .min(-2 * M_PI)
657  .max(2 * M_PI)
658  .decimals(3))));
659  }
660 
661  // Cropping
662  {
663  auto cropGroupLayout = makeVBoxLayout();
664 
665  WidgetPtr frameLabel = makeTextLabel("Frame: ");
666  WidgetPtr minLabel = makeTextLabel("Minimum: ");
667  WidgetPtr maxLabel = makeTextLabel("Maximum: ");
668  WidgetPtr rpyLabel = makeTextLabel("Roll / Pitch / Yaw: ");
669 
670  WidgetPtr enabledCheckBox =
671  makeCheckBox("CropEnabled").value(p.croppingEnabled).label("Enabled");
672  WidgetPtr reportAllBox = makeCheckBox("reportCloudOutsideOfCroppingArea")
673  .value(p.reportCloudOutsideOfCroppingArea)
674  .label("Report points outside");
675 
676  WidgetPtr frameLine = makeComboBox("CropFrame")
677  .options({armarx::GlobalFrame, "root"})
678  .addOptions(localRobot->getRobotNodeNames())
679  .value(p.croppingFrameName);
680  WidgetPtr minVector3Spin =
681  makeVector3fSpinBoxes("CropMin").value(p.croppingMinPoint).min(-100000).max(100000);
682  WidgetPtr maxVector3Spin =
683  makeVector3fSpinBoxes("CropMax").value(p.croppingMaxPoint).min(-100000).max(100000);
684  WidgetPtr rpyVector3Spin = makeVector3fSpinBoxes("CropRPY")
685  .value(p.croppingRPY)
686  .min(-M_PI)
687  .max(M_PI)
688  .decimals(3);
689 
690  cropGroupLayout.addChild(makeSimpleGridLayout().cols(2).children({enabledCheckBox,
691  reportAllBox,
692  frameLabel,
693  frameLine,
694  minLabel,
695  minVector3Spin,
696  maxLabel,
697  maxVector3Spin,
698  rpyLabel,
699  rpyVector3Spin}));
700 
701  rootLayout.addChild(makeGroupBox("CropGroup").label("Cropping").child(cropGroupLayout));
702  }
703 
704  // Visualization
705  {
706  auto visuGroupLayout = makeVBoxLayout();
707 
708  WidgetPtr enabledCheckBox =
709  makeCheckBox("VisuEnabled").label("Enabled").value(debugDrawer.enabled());
710 
711  visuGroupLayout.addChild(makeSimpleGridLayout().cols(2).addChild(enabledCheckBox));
712 
713  rootLayout.addChild(
714  makeGroupBox("VisuGroup").label("Visualization").child(visuGroupLayout));
715  }
716 
717 
718  const std::string tabName = getName();
719  remoteGui->createTab(tabName, rootLayout);
720  remoteGuiTab = armarx::RemoteGui::TabProxy(remoteGui, tabName);
721  }
722 
723  void
724  PointCloudFilter::remoteGuiRun()
725  {
726  int cycleDurationMs = 50;
727  CycleUtil c(cycleDurationMs);
728  while (!remoteGuiTask->isStopped())
729  {
730  remoteGuiTab.receiveUpdates();
731 
732  remoteGuiUpdate(remoteGuiTab);
733 
734  remoteGuiTab.sendUpdates();
735  c.waitForCycleDuration();
736  }
737  }
738 
739  void
740  PointCloudFilter::remoteGuiUpdate(RemoteGui::TabProxy& tab)
741  {
742  using namespace armarx::RemoteGui;
743 
744  {
745  std::unique_lock lock(parametersMutex);
746 
747  // Frames
748  ValueProxy<std::string> sourceFrame = tab.getValue<std::string>("SourceFrame");
749 
750  if (tab.getValue<bool>("SourceFrameAutoEnabled").get())
751  {
752  parameters.sourceFrameName = this->providerSourceFrameName;
753  sourceFrame.set(parameters.sourceFrameName);
754  // sourceFrame.setDisabled(true); // Seems not to do the right thing.
755  }
756  else
757  {
758  parameters.sourceFrameName = sourceFrame.get();
759  // sourceFrame.setDisabled(false); // Seems not to do the right thing.
760  }
761 
762  tab.getValue(parameters.targetFrameName, "TargetFrame");
763 
764  // Misc
765  tab.getValue(parameters.downsamplingEnabled, "DownsamplingEnabled");
766  tab.getValue(parameters.gridLeafSize, "DownsamplingGridLeafSize");
767  tab.getValue(parameters.applyCollisionModelFilter, "CollisionModelFilterEnabled");
768  tab.getValue(parameters.reportCloudOutsideOfCroppingArea,
769  "reportCloudOutsideOfCroppingArea");
770  tab.getValue(parameters.statisticalOutlierRemoval.enabled,
771  "StatisticalOutlierRemoval_enabled");
772  tab.getValue(parameters.statisticalOutlierRemoval.meanK,
773  "StatisticalOutlierRemoval_MeanK");
774  tab.getValue(parameters.statisticalOutlierRemoval.stddevMulThresh,
775  "StatisticalOutlierRemoval_StddevMulThresh");
776 
777  // Cropping
778  tab.getValue(parameters.croppingEnabled, "CropEnabled");
779  tab.getValue(parameters.croppingFrameName, "CropFrame");
780  tab.getValue(parameters.croppingMinPoint, "CropMin");
781  tab.getValue(parameters.croppingMaxPoint, "CropMax");
782  tab.getValue(parameters.croppingRPY, "CropRPY");
783 
784  parameters.providerFrameTransformation =
785  simox::math::pos_rpy_to_mat4f(tab.getValue<Eigen::Vector3f>("transform.XYC").get(),
786  tab.getValue<Eigen::Vector3f>("transform.RPY").get());
787  }
788 
789  // Visu
790  bool visuEnabled = tab.getValue<bool>("VisuEnabled").get();
791  if (!visuEnabled)
792  {
793  // This will clear the layer if the visualization was enabled before.
794  debugDrawer.clearLayer(false);
795  }
796  // This has to come *after* clearing.
797  debugDrawer.setEnabled(visuEnabled);
798  }
799 
800 
801 } // namespace visionx
armarx::SimpleRunningTask
Usage:
Definition: TaskUtil.h:85
RemoteRobot.h
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:187
visionx::FramedPointCloud::getFramedPose
armarx::FramedPose getFramedPose(const std::string &agentName) const
Get the current pose as FramedPose.
Definition: FramedPointCloud.h:77
armarx::DebugDrawerTopic::offeringTopic
void offeringTopic(ManagedIceObject &component, const std::string &topicNameOverride="") const
Call offeringTopic([topicName]) on the given component.
Definition: DebugDrawerTopic.cpp:80
visionx::PointCloudFilter::onInitPointCloudProcessor
virtual void onInitPointCloudProcessor() override
Definition: PointCloudFilter.cpp:152
armarx::WidgetDescription::makeGroupBox
GroupBoxPtr makeGroupBox(std::string label, WidgetPtr child, bool framed)
Definition: DefaultWidgetDescriptions.cpp:115
armarx::RemoteGui::makeVector3fSpinBoxes
detail::Vector3fSpinBoxesBuilder makeVector3fSpinBoxes(std::string const &name, float limpos=1000)
Definition: Vector3fWidgets.h:140
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
armarx::DebugDrawerTopic::enabled
bool enabled() const
Indicate whether visualization is enabled, i.e. a topic is set and enabled flag is set.
Definition: DebugDrawerTopic.cpp:74
armarx::FramedPose
The FramedPose class.
Definition: FramedPose.h:280
armarx::RemoteGui
Definition: LightweightRemoteGuiComponentPlugin.h:30
visionx::PointCloudFilter::setCroppingParameters
virtual void setCroppingParameters(const armarx::Vector3BasePtr &min, const armarx::Vector3BasePtr &max, const std::string &frame, const Ice::Current &=Ice::emptyCurrent) override
Definition: PointCloudFilter.cpp:139
armarx::DebugDrawerTopic::removeboxEdges
void removeboxEdges(const VisuID &id)
Remove box edges (as a line set).
Definition: DebugDrawerTopic.cpp:414
WidgetBuilder.h
armarx::RemoteGui::detail::Vector3fSpinBoxesBuilder::decimals
Vector3fSpinBoxesBuilder & decimals(const Eigen::Vector3i decimals)
Definition: Vector3fWidgets.h:111
armarx::GlobalFrame
const std::string GlobalFrame
Definition: FramedPose.h:65
armarx::WidgetDescription::makeHBoxLayout
HBoxLayoutPtr makeHBoxLayout(std::vector< WidgetPtr > elements)
Definition: DefaultWidgetDescriptions.cpp:31
FramedPointCloud.h
visionx::FramedPointCloud::getGlobalPose
Eigen::Matrix4f getGlobalPose(const VirtualRobot::RobotPtr &robot) const
Get the current global pose.
Definition: FramedPointCloud.h:90
armarx::CycleUtil
This util class helps with keeping a cycle time during a control cycle.
Definition: CycleUtil.h:40
armarx::Component::usingProxyFromProperty
bool usingProxyFromProperty(const std::string &propertyName, const std::string &endpoints="")
Use a proxy whose name is specified by the given property.
Definition: Component.cpp:172
armarx::RemoteGui::detail::SimpleGridLayoutBuilder::addChild
SimpleGridLayoutBuilder & addChild(WidgetPtr const &child, int colspan)
Definition: LayoutWidgets.h:139
Storage.h
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:46
visionx::FramedPointCloud::setFrameWithoutTransformation
void setFrameWithoutTransformation(const std::string &f)
Definition: FramedPointCloud.h:70
visionx::PointCloudFilter::processPointCloud
void processPointCloud()
Definition: PointCloudFilter.cpp:320
armarx::RemoteGui::makeTextLabel
detail::LabelBuilder makeTextLabel(std::string const &text)
Definition: StaticWidgets.h:24
visionx::PointCloudFilter::getReferenceFrame
virtual std::string getReferenceFrame(const Ice::Current &=Ice::emptyCurrent) override
Definition: PointCloudFilter.cpp:132
armarx::skills::gui::Parameters
aron::data::DictPtr Parameters
Definition: SkillManagerWrapper.h:21
PointCloudFilter.h
armarx::RemoteGui::detail::Vector3fMinMaxMixin::min
Derived & min(float v)
Definition: Vector3fWidgets.h:24
armarx::RemoteGui::ValueProxy::get
T get() const
Definition: WidgetProxy.h:313
armarx::aron::type::PointCloudPtr
std::shared_ptr< class PointCloud > PointCloudPtr
Definition: forward_declarations.h:23
visionx::PointCloudProcessor::getPointCloudFrame
std::string getPointCloudFrame(const std::string &providerName, const std::string &defaultFrame="")
Get the reference frame of the point cloud by given provider.
Definition: PointCloudProcessor.cpp:588
armarx::RemoteGui::makeSimpleGridLayout
detail::SimpleGridLayoutBuilder makeSimpleGridLayout(std::string const &name="")
Definition: LayoutWidgets.h:274
visionx::FramedPointCloud::getFrame
std::string getFrame() const
Get the current frame.
Definition: FramedPointCloud.h:64
armarx::WidgetDescription::makeFloatSpinBox
FloatSpinBoxPtr makeFloatSpinBox(std::string name, float min, float max, float defaultValue, int steps, int decimals)
Definition: DefaultWidgetDescriptions.cpp:193
armarx::DebugDrawerTopic::getLayer
const std::string & getLayer() const
Get the default layer (used if no layer is passed to a method).
Definition: DebugDrawerTopic.cpp:94
armarx::RemoteGui::TabProxy
Definition: WidgetProxy.h:17
armarx::Component::getProxyFromProperty
ProxyType getProxyFromProperty(const std::string &propertyName, bool addToDependencies=false, const std::string &endpoints="", bool throwOnProxyError=true)
Get a proxy whose name is specified by the given property.
Definition: Component.h:242
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:855
armarx::RemoteGui::TabProxy::receiveUpdates
void receiveUpdates()
Definition: WidgetProxy.h:135
visionx::PointCloudProcessor::provideResultPointClouds
void provideResultPointClouds(const PointCloudPtrT &pointClouds, std::string providerName="")
sends result PointClouds for visualization
Definition: PointCloudProcessor.h:288
M_PI
#define M_PI
Definition: MathTools.h:17
FramedPose.h
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:184
visionx::PointCloudProcessor::waitForPointClouds
bool waitForPointClouds(int milliseconds=1000)
Wait for new PointClouds.
Definition: PointCloudProcessor.cpp:458
visionx::FramedPointCloud::cloud
PointCloudPtrT cloud
The point cloud.
Definition: FramedPointCloud.h:111
armarx::Pose::toEigen
virtual Eigen::Matrix4f toEigen() const
Definition: Pose.cpp:334
visionx::PointCloudFilter::process
virtual void process() override
Definition: PointCloudFilter.cpp:274
armarx::RemoteGui::detail::ValueMixin::value
Derived & value(ValueT const &value)
Definition: Basic.h:84
max
T max(T t1, T t2)
Definition: gdiam.h:51
visionx::PointCloudFilter::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: PointCloudFilter.cpp:567
ARMARX_ERROR
#define ARMARX_ERROR
Definition: Logging.h:196
visionx::PointCloudProcessorPropertyDefinitions
Properties of PointCloudProcessor.
Definition: PointCloudProcessor.h:166
visionx::PointCloudProcessor::getPointClouds
int getPointClouds(const PointCloudPtrT &pointCloudPtr)
Poll PointClouds from provider.
Definition: PointCloudProcessor.h:380
armarx::WidgetDescription::makeIntSpinBox
IntSpinBoxPtr makeIntSpinBox(std::string name, int min, int max, int defaultValue)
Definition: DefaultWidgetDescriptions.cpp:182
armarx::RemoteGui::detail::ComboBoxBuilder::options
ComboBoxBuilder & options(std::vector< std::string > const &options)
Definition: StringWidgets.h:21
visionx::PointCloudFilter::onExitPointCloudProcessor
virtual void onExitPointCloudProcessor() override
Definition: PointCloudFilter.cpp:269
visionx::FramedPointCloud
A point cloud which keeps track of its reference coordinate frame and allows changing frames using ar...
Definition: PointCloudFilter.h:56
armarx::WidgetDescription::WidgetPtr
::IceInternal::Handle<::armarx::WidgetDescription::Widget > WidgetPtr
Definition: NJointControllerBase.h:67
armarx::transform
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT >>
Convenience function (with less typing) to transform a container of type InputT into the same contain...
Definition: algorithm.h:351
armarx::RemoteGui::TabProxy::getValue
ValueProxy< T > getValue(std::string const &name)
Definition: WidgetProxy.h:167
CycleUtil.h
armarx::RemoteGui::ValueProxy::set
void set(std::atomic< T1 > const &value)
Definition: WidgetProxy.h:352
visionx::PointCloudFilter::onConnectPointCloudProcessor
virtual void onConnectPointCloudProcessor() override
Definition: PointCloudFilter.cpp:208
armarx::Component::getConfigIdentifier
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition: Component.cpp:79
armarx::DebugDrawerTopic::drawPose
void drawPose(const VisuID &id, const Eigen::Matrix4f &pose, bool ignoreLengthScale=false)
Draw a pose (with the preset scale).
Definition: DebugDrawerTopic.cpp:705
visionx::PointCloudFilter::onDisconnectPointCloudProcessor
virtual void onDisconnectPointCloudProcessor() override
Definition: PointCloudFilter.cpp:297
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:181
armarx::PropertyUser::getProperty
Property< PropertyType > getProperty(const std::string &name)
Property creation and retrieval.
Definition: PropertyUser.h:180
armarx::DebugDrawerTopic::setLayer
void setLayer(const std::string &layer)
Set the default layer (used if no layer is passed to a method).
Definition: DebugDrawerTopic.cpp:100
armarx::DebugDrawerTopic::drawBoxEdges
void drawBoxEdges(const VisuID &id, const Eigen::Vector3f &position, const Eigen::Quaternionf &orientation, const Eigen::Vector3f &extents, float width=DEFAULTS.boxEdgesWidth, const DrawColor &color=DEFAULTS.boxEdgesColor, bool ignoreLengthScale=false)
Draw box edges (as a line set).
Definition: DebugDrawerTopic.cpp:275
IceUtil::Handle< class PropertyDefinitionContainer >
visionx::FramedPointCloud::transformBy
void transformBy(const Eigen::Matrix4f &transform)
Definition: FramedPointCloud.h:104
armarx::WidgetDescription::makeCheckBox
CheckBoxPtr makeCheckBox(std::string name, bool defaultValue, std::string label)
Definition: DefaultWidgetDescriptions.cpp:162
visionx::PointCloudFilter::getDefaultName
virtual std::string getDefaultName() const override
Definition: PointCloudFilter.cpp:126
armarx::RemoteGui::TabProxy::sendUpdates
void sendUpdates()
Definition: WidgetProxy.h:151
armarx::RemoteGui::makeComboBox
detail::ComboBoxBuilder makeComboBox(std::string const &name)
Definition: StringWidgets.h:61
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
Eigen::Matrix
Definition: EigenForwardDeclarations.h:27
armarx::ManagedIceObject::getName
std::string getName() const
Retrieve name of object.
Definition: ManagedIceObject.cpp:108
armarx::RemoteGui::detail::Vector3fMinMaxMixin::max
Derived & max(float v)
Definition: Vector3fWidgets.h:36
armarx::FramedPose::getFrame
std::string getFrame() const
Definition: FramedPose.cpp:453
GfxTL::Matrix3f
MatrixXX< 3, 3, float > Matrix3f
Definition: MatrixXX.h:649
min
T min(T t1, T t2)
Definition: gdiam.h:44
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::DebugDrawerTopic::getTopic
DebugDrawerInterfacePrx getTopic() const
Get the topic.
Definition: DebugDrawerTopic.cpp:62
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
armarx::RemoteGui::ValueProxy
Definition: WidgetProxy.h:13
armarx::DebugDrawerTopic::setEnabled
void setEnabled(bool enabled)
Set whether drawing is enabled.
Definition: DebugDrawerTopic.cpp:68
visionx::PointCloudFilterPropertyDefinitions
Definition: PointCloudFilter.h:59
armarx::WidgetDescription::makeVBoxLayout
VBoxLayoutPtr makeVBoxLayout(std::vector< WidgetPtr > elements)
Definition: DefaultWidgetDescriptions.cpp:39
armarx::ManagedIceObject::getProxy
Ice::ObjectPrx getProxy(long timeoutMs=0, bool waitForScheduler=true) const
Returns the proxy of this object (optionally it waits for the proxy)
Definition: ManagedIceObject.cpp:407
visionx::PointCloudProcessor::getPointCloudProviderNames
std::vector< std::string > getPointCloudProviderNames() const
Get the names of providers for which usingPointCloudProvider() has been called.
Definition: PointCloudProcessor.cpp:404
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:27