PointCloudSegmenter.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
19  * @author Eren Aksoy ( eren dot aksoy 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 #include "PointCloudSegmenter.h"
26 
27 #include <QSettings>
28 
29 #include <pcl/common/colors.h>
30 #include <pcl/filters/crop_box.h>
31 
34 
36 
38 
39 using namespace armarx;
40 
41 namespace visionx
42 {
43  PointCloudSegmenter::PointCloudSegmenter() :
44  inputCloudPtr(new pcl::PointCloud<PointO>),
45  labeledColoredCloudPtr(new pcl::PointCloud<PointRGBL>)
46  {
47  }
48 
49  void
51  {
52  lastProcessedTimestamp = 0;
53 
54  // Get point cloud provider name
55  providerName = getProperty<std::string>("ProviderName").getValue();
56  ARMARX_INFO << "Using point cloud provider " << providerName << flush;
57 
58 
59  // Get segmentation method
60  segmentationMethod = getProperty<std::string>("segmentationMethod").getValue();
61  ARMARX_INFO << "Using the segmentation method " << segmentationMethod << flush;
62 
63  offeringTopic(getProperty<std::string>("DebugDrawerTopicName").getValue());
64 
65  enabled = getProperty<bool>("StartEnabled").getValue();
66  ARMARX_INFO << "Starting " << (enabled ? "Enabled" : "Disabled");
67 
68  // get LCCP segmentation parameters
69  minSegSize = getProperty<int>("lccpMinimumSegmentSize").getValue();
70  voxelRes = getProperty<float>("lccpVoxelResolution").getValue();
71  seedRes = getProperty<float>("lccpSeedResolution").getValue();
72  colorImp = getProperty<float>("lccpColorImportance").getValue();
73  spatialImp = getProperty<float>("lccpSpatialImportance").getValue();
74  normalImp = getProperty<float>("lccpNormalImportance").getValue();
75  concavityThres = getProperty<float>("lccpConcavityThreshold").getValue();
76  smoothnessThes = getProperty<float>("lccpSmoothnessThreshold").getValue();
77 
78  // get RG segmentation parameters
79  rgSmoothnessThes = getProperty<float>("rgSmoothnessThreshold").getValue();
80  rgCurvatureThres = getProperty<float>("rgCurvatureThreshold").getValue();
81 
82  // init segmenters and update parameters
83  if (segmentationMethod == "LCCP")
84  {
85  pLCCP = new LCCPSegClass();
86  pLCCP->UpdateParameters(voxelRes,
87  seedRes,
88  colorImp,
89  spatialImp,
90  normalImp,
91  concavityThres,
92  smoothnessThes,
93  minSegSize);
94  }
95  else if (segmentationMethod == "RG")
96  {
97  pRGSegmenter = new RGSegClass();
98  pRGSegmenter->UpdateRegionGrowingSegmentationParameters(rgSmoothnessThes,
99  rgCurvatureThres);
100  }
101  else if (segmentationMethod == "EC")
102  {
103  pECSegmenter = new EuclideanBasedClustering();
104  }
105  else if (segmentationMethod == "DS")
106  {
107  usingProxy(getProperty<std::string>("DeepSegmenterTopicName").getValue());
108  pDeepSegmenter = new DeepSegClass();
109  }
110  }
111 
112  void
114  {
115  debugDrawerTopic = getTopic<armarx::DebugDrawerInterfacePrx>(
116  getProperty<std::string>("DebugDrawerTopicName").getValue());
117  if (!debugDrawerTopic)
118  {
119  ARMARX_WARNING << "Failed to obtain debug drawer proxy";
120  }
121 
122  if (segmentationMethod == "DS")
123  {
124  deepSegmenterTopic = getProxy<armarx::DeepSegmenterInterfacePrx>(
125  getProperty<std::string>("DeepSegmenterTopicName").getValue());
126  if (!deepSegmenterTopic)
127  {
128  ARMARX_WARNING << "Failed to obtain deep segmenter proxy";
129  }
130  }
131 
132  enableResultPointClouds<PointRGBL>();
133 
136  }
137 
138  void
140  {
141  }
142 
143  void
145  {
146  if (pLCCP)
147  {
148  delete pLCCP;
149  }
150 
151  if (pRGSegmenter)
152  {
153  delete pRGSegmenter;
154  }
155 
156  if (pECSegmenter)
157  {
158  delete pECSegmenter;
159  }
160 
161  if (pDeepSegmenter)
162  {
163  delete pDeepSegmenter;
164  }
165  }
166 
167  void
169  {
170  {
171  std::unique_lock lock(enableMutex);
172 
173  if (!enabled)
174  {
175  return;
176  }
177  }
178 
179  if (!waitForPointClouds(providerName, 10000))
180  {
181  ARMARX_WARNING << "Timeout or error while waiting for point cloud data"
182  << armarx::flush;
183  return;
184  }
185 
186 
187  //if (getPointCloudFormat(providerName)->type == eColoredLabeledPoints)
188  //{
189  // ARMARX_INFO << "Received RGBL point cloud: Passing on already segmented point cloud";
190  //
191  // labeledColoredCloudPtr.reset(new pcl::PointCloud<pcl::PointXYZRGBL>());
192  // getPointClouds(providerName, labeledColoredCloudPtr);
193  // provideResultPointClouds(labeledColoredCloudPtr);
194  //
195  // {
196  // std::unique_lock lock(timestampMutex);
197  // lastProcessedTimestamp = getPointCloudFormat(providerName)->timeProvided;
198  // }
199  //
200  // return;
201  //}
202  //else
203  //{
204  getPointClouds(providerName, inputCloudPtr);
205  ARMARX_INFO << "Point cloud received (size: " << inputCloudPtr->points.size()
206  << ", providerName: " << providerName << ")";
207  //}
208 
209  MetaPointCloudFormatPtr info = getPointCloudFormat(providerName);
210  IceUtil::Int64 originalTimestamp = info->timeProvided;
211 
212  IceUtil::Time ts = IceUtil::Time::microSeconds(originalTimestamp);
213  std::string timestampString = ts.toDateTime().substr(ts.toDateTime().find(' ') + 1);
214 
215  IceUtil::Time start_ts = IceUtil::Time::now();
216 
217  ARMARX_INFO << "Point cloud received (timestamp: " << timestampString
218  << ", size: " << inputCloudPtr->points.size()
219  << ", providerName: " << providerName << ")";
220  if (inputCloudPtr->points.size() == 0)
221  {
222  return;
223  }
224 
225  if (segmentationMethod == "LCCP")
226  {
227  pcl::PointCloud<pcl::PointXYZL>::Ptr labeledPCPtr =
228  pLCCP->GetLabeledPointCloud(inputCloudPtr);
229  labeledColoredCloudPtr.reset(
230  new pcl::PointCloud<PointRGBL>()); // returns labeled cloud in XYZL format
231 
232  if (inputCloudPtr->size() != labeledPCPtr->size())
233  {
234  ARMARX_WARNING << "Point cloud size mismatch (RGB: " << inputCloudPtr->size()
235  << ", XYZL: " << labeledPCPtr->size() << "), skipping current frame";
236  return;
237  }
238 
239 
240  pcl::concatenateFields(*inputCloudPtr, *labeledPCPtr, *labeledColoredCloudPtr);
241  ARMARX_INFO << " computed supervoxelcluster size: "
242  << pLCCP->GetSuperVoxelClusterSize();
243  ARMARX_INFO << " computed labeledCloudPtr size: "
244  << labeledColoredCloudPtr->points.size();
245  }
246  else if (segmentationMethod == "RG")
247  {
248  pRGSegmenter->UpdateRegionGrowingSegmentationParameters(rgSmoothnessThes,
249  rgCurvatureThres);
250  auto colorizedLabeledCloudPtr = pRGSegmenter->ApplyRegionGrowingSegmentation(
251  inputCloudPtr); // returns labeled cloud in XYZRGBA format
252  pcl::PointCloud<pcl::PointXYZL>::Ptr labeledPCPtr(
253  new pcl::PointCloud<pcl::PointXYZL>());
254  convertFromXYZRGBAtoXYZL(
255  colorizedLabeledCloudPtr,
256  labeledPCPtr); // convert form XYZRGBA to XYZL for the labeling process
257  labeledColoredCloudPtr.reset(new pcl::PointCloud<PointRGBL>());
258  pcl::concatenateFields(*inputCloudPtr, *labeledPCPtr, *labeledColoredCloudPtr);
259  }
260  else if (segmentationMethod == "EC")
261  {
262  labeledColoredCloudPtr = pECSegmenter->GetLabeledPointCloud(inputCloudPtr);
263  }
264  else if (segmentationMethod == "DS")
265  {
266  if (!deepSegmenterTopic) // check the proxy
267  {
268  ARMARX_WARNING << "Failed to obtain deep segmenter proxy";
269  return;
270  }
271 
272  if (!inputCloudPtr->isOrganized()) // the input cloud must be organized
273  {
274  ARMARX_WARNING << "Input point cloud is not organized!";
275  return;
276  }
277 
278  // first get rgb image from the point cloud data
279  rgbImage = pDeepSegmenter->GetImageFromPointCloud(inputCloudPtr);
280 
281  deepSegmenterTopic->setImageDimensions(inputCloudPtr->width, inputCloudPtr->height);
282  armarx::Blob deepSegmentImage = deepSegmenterTopic->segmentImage(rgbImage);
283 
284  labeledColoredCloudPtr =
285  pDeepSegmenter->GetLabeledPointCloud(inputCloudPtr, deepSegmentImage);
286  }
287 
288  // Provide point cloud referencing the time stamp of the original source point cloud
289  labeledColoredCloudPtr->header.stamp = originalTimestamp;
290 
291  {
292  std::unique_lock lock(enableMutex);
293 
294  // Do not provide result if segmenter has been switched off in the meantime
295  if (enabled)
296  {
297  provideResultPointClouds(labeledColoredCloudPtr);
298 
299  {
300  std::unique_lock lock(timestampMutex);
301  lastProcessedTimestamp = originalTimestamp;
302  }
303  }
304  }
305 
306  ARMARX_INFO << "Point cloud segmentation took "
307  << (IceUtil::Time::now() - start_ts).toSecondsDouble() << " secs";
308 
309  if (getProperty<bool>("SingleRun").getValue())
310  {
311  ARMARX_WARNING << "PointCloudSegmenter configured to run only once";
312  enabled = false;
313  }
314  }
315 
318  {
319  return PropertyDefinitionsPtr(
321  }
322 
323  void
325  {
326  std::unique_lock lock(enableMutex);
327  enabled = true;
328 
329  ARMARX_INFO << "Enabling segmentation";
330  }
331 
332  void
334  {
335  std::unique_lock lock(enableMutex);
336  enabled = false;
337 
338  ARMARX_INFO << "Disabling segmentation";
339  }
340 
341  void
342  PointCloudSegmenter::changePointCloudProvider(const std::string& providerName,
343  const Ice::Current& c)
344  {
345  std::unique_lock lock(providerMutex);
346 
347  ARMARX_INFO << "Changing point cloud provider to '" << providerName << "'";
348 
350 
351  releasePointCloudProvider(this->providerName);
352  this->providerName = providerName;
353  usingPointCloudProvider(this->providerName);
354 
356  }
357 
358  void
359  PointCloudSegmenter::convertFromXYZRGBAtoXYZL(
360  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr& sourceCloudPtr,
361  pcl::PointCloud<pcl::PointXYZL>::Ptr& targetCloudPtr)
362  {
363  targetCloudPtr->resize(sourceCloudPtr->points.size());
364  uint32_t newLabel = 1;
365 
366  struct rgbValues
367  {
368  int rVal;
369  int gVal;
370  int bVal;
371  };
372 
373  std::map<uint32_t, rgbValues> colorMap;
374 
375  // scan the source cloud
376  for (size_t i = 0; i < sourceCloudPtr->points.size(); i++)
377  {
378  rgbValues currRGB;
379  currRGB.rVal = (int)sourceCloudPtr->points[i].r;
380  currRGB.gVal = (int)sourceCloudPtr->points[i].g;
381  currRGB.bVal = (int)sourceCloudPtr->points[i].b;
382 
383  bool isFound = false;
384  uint32_t foundLabel = 0;
385 
386  // search in the map
387  std::map<uint32_t, rgbValues>::iterator iter_i;
388 
389  for (iter_i = colorMap.begin(); iter_i != colorMap.end(); iter_i++)
390  {
391  if (currRGB.rVal == iter_i->second.rVal && currRGB.gVal == iter_i->second.gVal &&
392  currRGB.bVal == iter_i->second.bVal)
393  {
394  foundLabel = iter_i->first;
395  isFound = true;
396  break;
397  }
398  }
399 
400  if (!isFound)
401  {
402  colorMap[newLabel] = currRGB;
403  foundLabel = newLabel;
404  newLabel++;
405  }
406 
407  targetCloudPtr->points[i].x = sourceCloudPtr->points[i].x;
408  targetCloudPtr->points[i].y = sourceCloudPtr->points[i].y;
409  targetCloudPtr->points[i].z = sourceCloudPtr->points[i].z;
410  targetCloudPtr->points[i].label = foundLabel;
411  }
412  }
413 
414  bool
416  {
417  std::unique_lock lock(enableMutex);
418  return enabled;
419  }
420 
421  armarx::TimestampBasePtr
423  {
424  std::unique_lock lock(timestampMutex);
425  return new TimestampVariant(lastProcessedTimestamp);
426  }
427 
428  void
429  PointCloudSegmenter::setLccpParameters(const LccpParameters& parameters, const Ice::Current& c)
430  {
431  ARMARX_INFO << "Updating LCCP parameter setup (current segmentation method is "
432  << segmentationMethod << ")";
433  pLCCP->UpdateParameters(parameters.voxelResolution,
434  parameters.seedResolution,
435  parameters.colorImportance,
436  parameters.spatialImportance,
437  parameters.normalImportance,
438  parameters.concavityThreshold,
439  parameters.smoothnessThreshold,
440  parameters.minSegmentSize);
441  }
442 
443  void
445  const Ice::Current& c)
446  {
447  std::string absolute_filename;
448  ArmarXDataPath::getAbsolutePath(filename, absolute_filename);
449 
450  ARMARX_INFO << "Loading LCCP parameter setup from " << absolute_filename;
451  QSettings config(QString::fromStdString(absolute_filename), QSettings::IniFormat);
452 
453  config.beginGroup("LCCP");
454  pLCCP->UpdateParameters(
455  config.value("VoxelResolution", getProperty<float>("lccpVoxelResolution").getValue())
456  .toFloat(),
457  config.value("SeedResolution", getProperty<float>("lccpSeedResolution").getValue())
458  .toFloat(),
459  config.value("ColorImportance", getProperty<float>("lccpColorImportance").getValue())
460  .toFloat(),
461  config
462  .value("SpatialImportance", getProperty<float>("lccpSpatialImportance").getValue())
463  .toFloat(),
464  config.value("NormalImportance", getProperty<float>("lccpNormalImportance").getValue())
465  .toFloat(),
466  config
467  .value("ConcavityThreshold",
468  getProperty<float>("lccpConcavityThreshold").getValue())
469  .toFloat(),
470  config
471  .value("SmoothnessThreshold",
472  getProperty<float>("lccpSmoothnessThreshold").getValue())
473  .toFloat(),
474  config.value("MinSegmentSize", getProperty<int>("lccpMinimumSegmentSize").getValue())
475  .toInt());
476  config.endGroup();
477  }
478 
479  LccpParameters
481  {
482  LccpParameters parameters;
483 
484  parameters.voxelResolution = pLCCP->voxel_resolution;
485  parameters.seedResolution = pLCCP->seed_resolution;
486  parameters.colorImportance = pLCCP->color_importance;
487  parameters.spatialImportance = pLCCP->spatial_importance;
488  parameters.normalImportance = pLCCP->normal_importance;
489  parameters.concavityThreshold = pLCCP->concavity_tolerance_threshold;
490  parameters.smoothnessThreshold = pLCCP->smoothness_threshold;
491  parameters.minSegmentSize = pLCCP->min_segment_size;
492 
493 
494  return parameters;
495  }
496 
497  void
498  PointCloudSegmenter::setRgParameters(float smoothnessThreshold,
499  float curvatureThreshold,
500  const Ice::Current& c)
501  {
502  ARMARX_INFO << "Updating RG parameter setup";
503  pRGSegmenter->UpdateRegionGrowingSegmentationParameters(smoothnessThreshold,
504  curvatureThreshold);
505  }
506 
507  void
509  const Ice::Current& c)
510  {
511  std::string absolute_filename;
512  ArmarXDataPath::getAbsolutePath(filename, absolute_filename);
513 
514  ARMARX_INFO << "Loading RG parameter setup from " << absolute_filename;
515  QSettings config(QString::fromStdString(absolute_filename), QSettings::IniFormat);
516 
517  config.beginGroup("RG");
519  config
520  .value("SmoothnessThreshold",
521  getProperty<double>("rgSmoothnessThreshold").getValue())
522  .toDouble(),
523  config
524  .value("CurvatureThreshold", getProperty<double>("rgCurvatureThreshold").getValue())
525  .toDouble());
526  config.endGroup();
527  }
528 
529  void
531  {
532  GridLayout grid;
533  int row = 0;
534  {
535  tab.rgSmoothnessThreshold.setRange(1.0, 20.0);
537  tab.rgSmoothnessThreshold.setValue(rgSmoothnessThes);
539  grid.add(Label("rgSmoothnessThreshold:"), Pos{row, 0});
540  grid.add(tab.rgSmoothnessThreshold, Pos{row, 1});
541  row += 1;
542  }
543  {
544  tab.rgCurvatureThreshold.setRange(1.0, 50.0);
546  tab.rgCurvatureThreshold.setValue(rgCurvatureThres);
548  grid.add(Label("rgCurvatureThreshold:"), Pos{row, 0});
549  grid.add(tab.rgCurvatureThreshold, Pos{row, 1});
550  row += 1;
551  }
552 
553  RemoteGui_createTab("PointCloudSegmenter", grid, &tab);
554  }
555 
556  void
558  {
559  rgSmoothnessThes = tab.rgSmoothnessThreshold.getValue();
560  rgCurvatureThres = tab.rgCurvatureThreshold.getValue();
561  }
562 
563 } // namespace visionx
pcl
Definition: pcl_point_operators.cpp:3
armarx::RemoteGui::Client::FloatSpinBox::getValue
float getValue() const
Definition: Widgets.cpp:352
visionx::PointCloudSegmenter::onConnectPointCloudProcessor
void onConnectPointCloudProcessor() override
Definition: PointCloudSegmenter.cpp:113
visionx::PointCloudSegmenter::getLccpParameters
LccpParameters getLccpParameters(const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudSegmenter.cpp:480
EuclideanBasedClustering
Definition: EuclideanBasedClustering.h:41
visionx::PointCloudProcessor::getPointCloudFormat
MetaPointCloudFormatPtr getPointCloudFormat(std::string providerName)
Definition: PointCloudProcessor.cpp:534
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
visionx::PointCloudSegmenterPropertyDefinitions
Definition: PointCloudSegmenter.h:81
visionx::PointCloudSegmenter::changePointCloudProvider
void changePointCloudProvider(const std::string &providerName, const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudSegmenter.cpp:342
visionx::PointCloudSegmenter::createRemoteGuiTab
void createRemoteGuiTab()
Definition: PointCloudSegmenter.cpp:530
Pose.h
armarx::RemoteGui::Client::GridLayout::add
GridLayout & add(Widget const &child, Pos pos, Span span=Span{1, 1})
Definition: Widgets.cpp:438
DeepSegClass::GetImageFromPointCloud
armarx::Blob GetImageFromPointCloud(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &CloudPtr)
Definition: Deep_Segmenter.cpp:64
armarx::RemoteGui::Client::FloatSpinBox::setValue
void setValue(float newValue)
Definition: Widgets.cpp:358
armarx::TimestampVariant
Definition: TimestampVariant.h:54
visionx::PointCloudProcessor::onDisconnectComponent
virtual void onDisconnectComponent() override
Definition: PointCloudProcessor.cpp:234
armarx::RemoteGui::Client::FloatSpinBox::setRange
void setRange(float min, float max)
Definition: Widgets.cpp:330
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:46
visionx::PointRGBL
pcl::PointXYZRGBL PointRGBL
Definition: PointCloudSegmenter.h:66
RGSegClass
Definition: RG_Segmenter.h:38
visionx::PointCloudSegmenterTab::rgSmoothnessThreshold
FloatSpinBox rgSmoothnessThreshold
Definition: PointCloudSegmenter.h:73
visionx::PointCloudSegmenter::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: PointCloudSegmenter.cpp:317
visionx::voxelgrid::Label
uint32_t Label
Type of an object label.
Definition: types.h:6
armarx::RemoteGui::Client::GridLayout
Definition: Widgets.h:186
EuclideanBasedClustering::GetLabeledPointCloud
pcl::PointCloud< pcl::PointXYZRGBL >::Ptr & GetLabeledPointCloud(pcl::PointCloud< PointO >::Ptr &CloudPtr)
Definition: EuclideanBasedClustering.cpp:33
armarx::RemoteGui::Client::Pos
Definition: Widgets.h:174
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:855
visionx::PointCloudSegmenter::onDisconnectPointCloudProcessor
void onDisconnectPointCloudProcessor() override
Definition: PointCloudSegmenter.cpp:139
visionx::PointCloudProcessor::provideResultPointClouds
void provideResultPointClouds(const PointCloudPtrT &pointClouds, std::string providerName="")
sends result PointClouds for visualization
Definition: PointCloudProcessor.h:288
RGSegClass::ApplyRegionGrowingSegmentation
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr & ApplyRegionGrowingSegmentation(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &CloudPtr)
Definition: RG_Segmenter.cpp:41
visionx::PointCloudSegmenter::isPipelineStepEnabled
bool isPipelineStepEnabled(const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudSegmenter.cpp:415
visionx::PointCloudSegmenter::setLccpParameters
void setLccpParameters(const LccpParameters &parameters, const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudSegmenter.cpp:429
armarx::flush
const LogSender::manipulator flush
Definition: LogSender.h:251
RGSegClass::UpdateRegionGrowingSegmentationParameters
void UpdateRegionGrowingSegmentationParameters(float SmoothnessThres, float CurvatureThres)
Definition: RG_Segmenter.cpp:96
visionx::PointCloudSegmenter::onInitPointCloudProcessor
void onInitPointCloudProcessor() override
Definition: PointCloudSegmenter.cpp:50
visionx::PointCloudProcessor::waitForPointClouds
bool waitForPointClouds(int milliseconds=1000)
Wait for new PointClouds.
Definition: PointCloudProcessor.cpp:458
TimestampVariant.h
PointCloudSegmenter.h
enabled
std::atomic< bool > * enabled
Definition: RemoteGuiWidgetController.cpp:75
filename
std::string filename
Definition: VisualizationRobot.cpp:86
DeepSegClass
Definition: Deep_Segmenter.h:40
LCCPSegClass::UpdateParameters
void UpdateParameters(float voxelRes, float seedRes, float colorImp, float spatialImp, float normalImp, float concavityThres, float smoothnessThes, uint32_t minSegSize)
Definition: LCCP_Segmenter.cpp:175
visionx::PointCloudSegmenter::loadRgParametersFromFile
void loadRgParametersFromFile(const std::string &filename, const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudSegmenter.cpp:508
visionx::PointCloudSegmenter::enablePipelineStep
void enablePipelineStep(const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudSegmenter.cpp:324
armarx::RemoteGui::Client::FloatSpinBox::setDecimals
void setDecimals(int decimals)
Definition: Widgets.cpp:345
armarx::RemoteGui::Client::FloatSpinBox::setSteps
void setSteps(int steps)
Definition: Widgets.cpp:338
visionx::PointCloudProcessor::getPointClouds
int getPointClouds(const PointCloudPtrT &pointCloudPtr)
Poll PointClouds from provider.
Definition: PointCloudProcessor.h:380
LCCPSegClass
Definition: LCCP_Segmenter.h:49
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
for
for(;yybottom<=yytop;yybottom++)
Definition: Grammar.cpp:705
visionx::PointCloudSegmenter::RemoteGui_update
void RemoteGui_update() override
Definition: PointCloudSegmenter.cpp:557
armarx::LightweightRemoteGuiComponentPluginUser::RemoteGui_startRunningTask
void RemoteGui_startRunningTask()
Definition: LightweightRemoteGuiComponentPlugin.cpp:119
visionx::PointCloudSegmenter::loadLccpParametersFromFile
void loadLccpParametersFromFile(const std::string &filename, const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudSegmenter.cpp:444
ExpressionException.h
PointCloud
Definition: PointCloud.h:85
visionx::PointCloudSegmenter::disablePipelineStep
void disablePipelineStep(const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudSegmenter.cpp:333
armarx::Component::getConfigIdentifier
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition: Component.cpp:79
PointCloudConversions.h
visionx::PointCloudProcessor::releasePointCloudProvider
void releasePointCloudProvider(std::string providerName)
Removes topic subscription and provider proxy dependency to release a point cloud provider.
Definition: PointCloudProcessor.cpp:295
visionx::PointCloudProcessor::onConnectComponent
virtual void onConnectComponent() override
Definition: PointCloudProcessor.cpp:216
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:181
visionx::PointCloudSegmenter::setRgParameters
void setRgParameters(float smoothnessThreshold, float curvatureThreshold, const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudSegmenter.cpp:498
armarx::LightweightRemoteGuiComponentPluginUser::RemoteGui_createTab
void RemoteGui_createTab(std::string const &name, RemoteGui::Client::Widget const &rootWidget, RemoteGui::Client::Tab *tab)
Definition: LightweightRemoteGuiComponentPlugin.cpp:103
armarx::ManagedIceObject::offeringTopic
void offeringTopic(const std::string &name)
Registers a topic for retrival after initialization.
Definition: ManagedIceObject.cpp:300
IceUtil::Handle< class PropertyDefinitionContainer >
LCCPSegClass::GetSuperVoxelClusterSize
size_t GetSuperVoxelClusterSize()
Definition: LCCP_Segmenter.h:99
DeepSegClass::GetLabeledPointCloud
pcl::PointCloud< pcl::PointXYZRGBL >::Ptr & GetLabeledPointCloud(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &CloudPtr, armarx::Blob segmentImage)
Definition: Deep_Segmenter.cpp:33
visionx::PointCloudProcessor::usingPointCloudProvider
void usingPointCloudProvider(std::string providerName)
Registers a delayed topic subscription and a delayed provider proxy retrieval which will be available...
Definition: PointCloudProcessor.cpp:279
visionx::PointCloudSegmenterTab::rgCurvatureThreshold
FloatSpinBox rgCurvatureThreshold
Definition: PointCloudSegmenter.h:74
visionx::PointCloudSegmenter::process
void process() override
Definition: PointCloudSegmenter.cpp:168
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::PointO
pcl::PointXYZRGBA PointO
Definition: PointCloudSegmenter.h:62
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:154
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:27
LCCPSegClass::GetLabeledPointCloud
pcl::PointCloud< pcl::PointXYZL >::Ptr & GetLabeledPointCloud(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &CloudPtr)
Definition: LCCP_Segmenter.cpp:77
visionx::PointCloudSegmenter::onExitPointCloudProcessor
void onExitPointCloudProcessor() override
Definition: PointCloudSegmenter.cpp:144
visionx::PointCloudSegmenter::getLastProcessedTimestamp
armarx::TimestampBasePtr getLastProcessedTimestamp(const Ice::Current &c=Ice::emptyCurrent) override
Definition: PointCloudSegmenter.cpp:422