DenseCRFSegmentationProcessor.h
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * @package ROBDEKON::ArmarXObjects::DenseCRFSegmentationProcessor
17  * @author Christoph Pohl ( christoph dot pohl at kit dot edu )
18  * @date 2019
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
23 #ifndef _ARMARX_COMPONENT_ROBDEKON_DenseCRFSegmentationProcessor_H
24 #define _ARMARX_COMPONENT_ROBDEKON_DenseCRFSegmentationProcessor_H
25 
26 
29 #include <ArmarXCore/interface/observers/ObserverInterface.h>
32 
33 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
34 
35 // RemoteGUI
36 #include <boost/graph/filtered_graph.hpp>
37 
38 #include <pcl/point_types.h>
39 
42 
43 #include <ArmarXGui/interface/RemoteGuiInterface.h>
47 
49 #include <VisionX/interface/components/DenseCRFSegmentationProcessorInterface.h>
54 
55 #include "Common.h"
56 #include "DenseGraphCRF.hpp"
57 
59  armarx::densecrf::config,
60  general,
61  (int,
62  num_classes,
63  AX_DESCRIPTION("Number of maximal object classes in an image"),
64  AX_DEFAULT(20),
65  AX_MIN(1),
66  AX_MAX(255),
67  AX_NO_REMOTE_GUI()),
68  (float,
69  ground_truth_prob,
70  AX_DESCRIPTION("Number of maximal object classes in an image"),
71  AX_DEFAULT(0.5),
72  AX_MIN(0),
73  AX_MAX(1),
74  AX_DECIMALS(2),
75  AX_STEPS(100)),
76  (bool,
77  use_vertex_only_graph,
78  AX_DESCRIPTION("If true, the graph is not computed via a voxel grid and"
79  " therefore has no edges between the vertices. This also means the"
80  " curvature is not signed in this case."),
81  AX_DEFAULT(false)),
82  (bool,
83  use_approximate_voxels,
84  AX_DESCRIPTION("If true & UseVertexOnlyGraph is true, the downsampling"
85  " uses the ApproximateVoxelGrid for downsampling instead of the normal"
86  "VoxelGrid"),
87  AX_DEFAULT(false)),
88  (float,
89  voxel_resolution,
90  AX_DESCRIPTION("Resolution of the Voxels used as Vertices of the Graph"),
91  AX_DEFAULT(0.05),
92  AX_MIN(0.01),
93  AX_MAX(.02),
94  AX_DECIMALS(3),
95  AX_STEPS(100)),
96  (int,
97  map_iterations,
98  AX_DESCRIPTION("Number of iterations used for the map"),
99  AX_DEFAULT(5),
100  AX_MIN(1),
101  AX_MAX(100)));
102 
104  armarx::densecrf::config,
105  output,
106  (bool,
107  provide_graph_pclouds,
108  AX_DESCRIPTION("If true a segmentation for each timestep"
109  "is provided as result cloud"),
110  AX_DEFAULT(false),
111  AX_NO_REMOTE_GUI()),
112  (bool,
113  provide_confidence_pclouds,
114  AX_DESCRIPTION("If true a confidence for each timestep"
115  "is provided as result cloud"),
116  AX_DEFAULT(false),
117  AX_NO_REMOTE_GUI()),
118  (bool,
119  colorize_confidence_pclouds,
120  AX_DESCRIPTION("If true the confidence pclouds are colorized"),
121  AX_DEFAULT(false),
122  AX_NO_REMOTE_GUI()));
123 
125  armarx::densecrf::config,
126  edge_comp,
127  (bool,
128  use_xyz,
129  AX_DESCRIPTION("If true xyz values are used for edge computation"),
130  AX_DEFAULT(true)),
131  (float,
132  xyz_influence,
133  AX_DESCRIPTION("Weight for the influence of position in the edge computation"),
134  AX_DEFAULT(0),
135  AX_MIN(-2),
136  AX_MAX(2),
137  AX_DECIMALS(1),
138  AX_STEPS(100)),
139  (bool,
140  use_normals,
141  AX_DESCRIPTION("If true normal values are used for edge computation"),
142  AX_DEFAULT(true)),
143  (float,
144  normals_influence,
145  AX_DESCRIPTION("Weight for the influence of normals in the edge computation"),
146  AX_DEFAULT(0),
147  AX_MIN(-2),
148  AX_MAX(2),
149  AX_DECIMALS(1),
150  AX_STEPS(100)),
151  (bool,
152  use_rgb,
153  AX_DESCRIPTION("If true RGB values are used for edge computation"),
154  AX_DEFAULT(true)),
155  (float,
156  rgb_influence,
157  AX_DESCRIPTION("Weight for the influence of color in the edge computation"),
158  AX_DEFAULT(0),
159  AX_MIN(-2),
160  AX_MAX(2),
161  AX_DECIMALS(1),
162  AX_STEPS(100)),
163  (bool,
164  use_curvature,
165  AX_DESCRIPTION("If true curvature values are used for edge computation"),
166  AX_DEFAULT(true)),
167  (float,
168  curvature_influence,
169  AX_DESCRIPTION("Weight for the influence of curvature in the edge computation"),
170  AX_DEFAULT(0),
171  AX_MIN(-2),
172  AX_MAX(2),
173  AX_DECIMALS(1),
174  AX_STEPS(100)),
175  (bool,
176  use_time,
177  AX_DESCRIPTION("If true time values are used for edge computation"),
178  AX_DEFAULT(true)),
179  (float,
180  time_influence,
181  AX_DESCRIPTION("Weight for the influence of time in the edge computation"),
182  AX_DEFAULT(0),
183  AX_MIN(-2),
184  AX_MAX(2),
185  AX_DECIMALS(1),
186  AX_STEPS(100)),
187  (bool,
188  use_combined,
189  AX_DESCRIPTION("If true the influence values are combined before they are given to DenseCRF"),
190  AX_DEFAULT(true)),
191  (float,
192  potts_compatibilty,
193  AX_DESCRIPTION("Weight factor for the Potts Compatibility"),
194  AX_DEFAULT(10),
195  AX_MIN(0.5),
196  AX_MAX(50),
197  AX_DECIMALS(1),
198  AX_STEPS(200)));
199 
200 ARMARX_CONFIG_STRUCT_DEFINE_ADAPT_CONFIGURE(armarx::densecrf::config,
201  data,
202  (armarx::densecrf::config::general, general),
203  (armarx::densecrf::config::output, out),
204  (armarx::densecrf::config::edge_comp, edge));
205 
206 namespace armarx
207 {
208 
209  /**
210  * @class DenseCRFSegmentationProcessorPropertyDefinitions
211  * @brief
212  */
215  {
216  public:
219  {
220  }
221  };
222 
223  /**
224  * @defgroup Component-DenseCRFSegmentationProcessor DenseCRFSegmentationProcessor
225  * @ingroup VisionX-Components
226  * A description of the component DenseCRFSegmentationProcessor.
227  *
228  * @class DenseCRFSegmentationProcessor
229  * @ingroup Component-DenseCRFSegmentationProcessor
230  * @brief Brief description of class DenseCRFSegmentationProcessor.
231  *
232  * Detailed description of class DenseCRFSegmentationProcessor.
233  */
234 
236  virtual public DenseCRFSegmentationProcessorInterface,
237  virtual public visionx::PointCloudProcessor,
239  {
240  public:
241  typedef boost::graph_traits<Graph>::vertex_iterator VertexIterator;
242 
243  /**
244  * @see armarx::ManagedIceObject::getDefaultName()
245  */
246  std::string
247  getDefaultName() const override
248  {
249  return "DenseCRFSegmentationProcessor";
250  }
251 
252  Vector5f getCurrentEdgeWeights(const Ice::Current& current) override;
253 
254  void setEdgeWeights(float xyz,
255  float rgb,
256  float normals,
257  float curvature,
258  float time,
259  const Ice::Current& current) override;
260 
261  protected:
262  /**
263  * @see visionx::PointCloudProcessor::onInitPointCloudProcessor()
264  */
265  void onInitPointCloudProcessor() override;
266 
267  /**
268  * @see visionx::PointCloudProcessor::onConnectPointCloudProcessor()
269  */
270  void onConnectPointCloudProcessor() override;
271 
272  /**
273  * @see visionx::PointCloudProcessor::onDisconnectPointCloudProcessor()
274  */
275  void onDisconnectPointCloudProcessor() override;
276 
277  /**
278  * @see visionx::PointCloudProcessor::onExitPointCloudProcessor()
279  */
280  void onExitPointCloudProcessor() override;
281 
282  /**
283  * @see visionx::PointCloudProcessor::process()
284  */
285  void process() override;
286 
287  /**
288  * @see PropertyUser::createPropertyDefinitions()
289  */
291 
292 
293  private:
294  template <typename TimestampMap>
295  struct vertex_timestamp_unequal_filter
296  {
297  vertex_timestamp_unequal_filter() = default;
298 
299  vertex_timestamp_unequal_filter(TimestampMap tsm, double ts) : m_tsm(tsm), m_ts(ts)
300  {
301  }
302 
303  template <typename Vertex>
304  bool
305  operator()(const Vertex& v) const
306  {
307  // keep all verticers that are not the one supplied to the constructor
308  double current_ts = get(m_tsm, v);
309  return abs(m_ts - current_ts) > 0.00001;
310  }
311 
312  TimestampMap m_tsm;
313  double m_ts{};
314  };
315 
316  template <typename TimestampMap>
317  struct vertex_timestamp_equal_filter
318  {
319  vertex_timestamp_equal_filter() = default;
320 
321  vertex_timestamp_equal_filter(TimestampMap tsm, double ts) : m_tsm(tsm), m_ts(ts)
322  {
323  }
324 
325  template <typename Vertex>
326  bool
327  operator()(const Vertex& v) const
328  {
329  // keep all verticers that are not the one supplied to the constructor
330  double current_ts = get(m_tsm, v);
331  return abs(m_ts - current_ts) < 0.00001;
332  }
333 
334  TimestampMap m_tsm;
335  double m_ts;
336  };
337 
338  double initial_time_;
339  GraphPtr current_graph_ptr_;
340  GraphWithTimestampPtr persistent_graph_ptr_;
341 
342  std::deque<Graph> graph_queue_;
343  std::deque<double> timestamp_queue_;
344 
345  void computeGraphUsingVoxelGrid(const PointCloudT::Ptr inputCloudPtr);
346 
347  void computeVertexOnlyGraph(pcl::PointCloud<PointT>::Ptr input_cloud_ptr);
348 
349  void generateRandomClassLabels();
350 
351  void relabelPointCloud(pcl::PointCloud<PointT>::Ptr input_cloud_ptr);
352 
353  // void computeRandomWalkerSegmentation();
354 
355  // void computeEdgeWeights();
356 
357  void updatePersistentGraph();
358 
359  void addGraphToPersistentGraph(Graph& graph);
360 
361  void addCurrentGraphToPersistentGraph();
362 
363  void removeGraphFromPersistentGraph(Graph& graph);
364 
365  void removeCurrentGraphFromPersistentGraph();
366 
367  void removeTimestampFromPersistentGraph(double ts);
368 
369  static void copyRGBLToRGBLNormal(PointCloudT& input_cloud,
370  PointCloudWithNormalT& output_cloud);
371 
372  static void copyRGBLNormalToRGBL(PointCloudWithNormalT& input_cloud,
373  PointCloudT& output_cloud);
374 
375  GraphWithTimestamp retrieveGraphFromPersistentGraph(double ts);
376 
377  GraphWithTimestamp retrieveCurrentGraphFromPersistentGraph();
378 
379  template <typename FilterT>
381  filterAndCopyPersistentGraph(TimestampMap tsm, FilterT filter)
382  {
383  ARMARX_TRACE;
384  typedef boost::filtered_graph<GraphWithTimestamp, boost::keep_all, FilterT>
385  FilteredGraph;
386  typedef
387  typename boost::graph_traits<FilteredGraph>::vertex_iterator FilteredVertexIterator;
388  FilteredGraph filtered_graph =
389  boost::make_filtered_graph(*persistent_graph_ptr_, boost::keep_all(), filter);
390  FilteredVertexIterator vi, v_end;
391  GraphWithTimestamp temp_graph;
392  TimestampMap temp_tsm = boost::get(boost::vertex_timestamp_t(), temp_graph.m_graph);
393  ConfidenceMap cm =
394  boost::get(boost::vertex_confidence_t(), persistent_graph_ptr_->m_graph);
395  ConfidenceMap temp_cm = boost::get(boost::vertex_confidence_t(), temp_graph.m_graph);
396  int num_vertices = 0;
397  for (boost::tie(vi, v_end) = boost::vertices(filtered_graph); vi != v_end; ++vi)
398  {
399  num_vertices++;
400  VertexWTsId new_vertex = boost::add_vertex(temp_graph);
401  boost::put(temp_tsm, new_vertex, get(tsm, *vi));
402  boost::put(temp_cm, new_vertex, get(cm, *vi));
403  PointWithNormalT point = filtered_graph.m_g.m_graph.m_point_cloud->points[*vi];
404  temp_graph[new_vertex] = point;
405  }
406  // ARMARX_INFO << "Filtered Graph has " << num_vertices << " num_vertices and "
407  // << static_cast<int>(boost::num_vertices(temp_graph)) << " Vertices";
408  return temp_graph;
409  }
410 
411  pcl::PointCloud<pcl::PointXYZL>::ConstPtr selectRandomSeeds();
412 
413  Eigen::MatrixXf computeRandomUnaryEnergy(int num_points);
414 
415  void provideAllGraphs();
416  void provideAllConfidences();
417 
418  WriteBufferedTripleBuffer<armarx::densecrf::config::data> config_;
419  std::mutex write_mutex_;
420  };
421 } // namespace armarx
422 
423 #endif
armarx::PointCloudWithNormalT
pcl::PointCloud< PointWithNormalT > PointCloudWithNormalT
Definition: Common.h:33
armarx::VertexWTsId
boost::graph_traits< GraphWithTimestamp >::vertex_descriptor VertexWTsId
Definition: Common.h:69
armarx::DenseCRFSegmentationProcessor::getCurrentEdgeWeights
Vector5f getCurrentEdgeWeights(const Ice::Current &current) override
Definition: DenseCRFSegmentationProcessor.cpp:797
boost::vertex_timestamp_t
Definition: Common.h:16
armarx::DenseCRFSegmentationProcessor::onInitPointCloudProcessor
void onInitPointCloudProcessor() override
Definition: DenseCRFSegmentationProcessor.cpp:64
armarx::DenseCRFSegmentationProcessor
Brief description of class DenseCRFSegmentationProcessor.
Definition: DenseCRFSegmentationProcessor.h:235
armarx::DenseCRFSegmentationProcessorPropertyDefinitions::DenseCRFSegmentationProcessorPropertyDefinitions
DenseCRFSegmentationProcessorPropertyDefinitions(std::string prefix)
Definition: DenseCRFSegmentationProcessor.h:217
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
armarx::DenseCRFSegmentationProcessor::getDefaultName
std::string getDefaultName() const override
Definition: DenseCRFSegmentationProcessor.h:247
armarx::ConfidenceMap
boost::property_map< CloudGraphWithTimestamp, boost::vertex_confidence_t >::type ConfidenceMap
Definition: Common.h:77
armarx::DenseCRFSegmentationProcessor::onExitPointCloudProcessor
void onExitPointCloudProcessor() override
Definition: DenseCRFSegmentationProcessor.cpp:134
Common.h
WidgetBuilder.h
DenseGraphCRF.hpp
trace.h
armarx::PropertyDefinitionContainer::prefix
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
Definition: PropertyDefinitionContainer.h:345
armarx::DenseCRFSegmentationProcessor::onConnectPointCloudProcessor
void onConnectPointCloudProcessor() override
Definition: DenseCRFSegmentationProcessor.cpp:76
armarx::DenseCRFSegmentationProcessorPropertyDefinitions
Definition: DenseCRFSegmentationProcessor.h:213
visionx::PointCloudProcessorPropertyDefinitions::PointCloudProcessorPropertyDefinitions
PointCloudProcessorPropertyDefinitions(std::string prefix)
Definition: PointCloudProcessor.cpp:121
armarx::DenseCRFSegmentationProcessor::setEdgeWeights
void setEdgeWeights(float xyz, float rgb, float normals, float curvature, float time, const Ice::Current &current) override
Definition: DenseCRFSegmentationProcessor.cpp:809
armarx::GraphPtr
Agraph_t * GraphPtr
Definition: Layout.h:41
boost::vertex_confidence_t
Definition: Common.h:21
armarx::DenseCRFSegmentationProcessor::VertexIterator
boost::graph_traits< Graph >::vertex_iterator VertexIterator
Definition: DenseCRFSegmentationProcessor.h:241
ARMARX_TRACE
#define ARMARX_TRACE
Definition: trace.h:77
voxel_grid_graph_builder.h
armarx::abs
std::vector< T > abs(const std::vector< T > &v)
Definition: VectorHelpers.h:281
ARMARX_CONFIG_STRUCT_DEFINE_ADAPT_CONFIGURE
ARMARX_CONFIG_STRUCT_DEFINE_ADAPT_CONFIGURE(armarx::densecrf::config, general,(int, num_classes, AX_DESCRIPTION("Number of maximal object classes in an image"), AX_DEFAULT(20), AX_MIN(1), AX_MAX(255), AX_NO_REMOTE_GUI()),(float, ground_truth_prob, AX_DESCRIPTION("Number of maximal object classes in an image"), AX_DEFAULT(0.5), AX_MIN(0), AX_MAX(1), AX_DECIMALS(2), AX_STEPS(100)),(bool, use_vertex_only_graph, AX_DESCRIPTION("If true, the graph is not computed via a voxel grid and" " therefore has no edges between the vertices. This also means the" " curvature is not signed in this case."), AX_DEFAULT(false)),(bool, use_approximate_voxels, AX_DESCRIPTION("If true & UseVertexOnlyGraph is true, the downsampling" " uses the ApproximateVoxelGrid for downsampling instead of the normal" "VoxelGrid"), AX_DEFAULT(false)),(float, voxel_resolution, AX_DESCRIPTION("Resolution of the Voxels used as Vertices of the Graph"), AX_DEFAULT(0.05), AX_MIN(0.01), AX_MAX(.02), AX_DECIMALS(3), AX_STEPS(100)),(int, map_iterations, AX_DESCRIPTION("Number of iterations used for the map"), AX_DEFAULT(5), AX_MIN(1), AX_MAX(100)))
visionx::PointCloudProcessor
The PointCloudProcessor class provides an interface for access to PointCloudProviders via Ice and sha...
Definition: PointCloudProcessor.h:177
data
uint8_t data[1]
Definition: EtherCATFrame.h:68
common.h
armarx::Graph
boost::subgraph< CloudGraph > Graph
Definition: Common.h:58
WidgetProxy.h
armarx::TimestampMap
boost::property_map< CloudGraphWithTimestamp, boost::vertex_timestamp_t >::type TimestampMap
Definition: Common.h:75
armarx::PointCloudT
pcl::PointCloud< PointT > PointCloudT
Definition: Common.h:32
visionx::PointCloudProcessorPropertyDefinitions
Properties of PointCloudProcessor.
Definition: PointCloudProcessor.h:166
PointCloudProcessor.h
TaskUtil.h
PluginAll.h
armarx::RemoteGuiComponentPluginUser
Definition: RemoteGuiComponentPlugin.h:221
Component.h
armarx::DenseCRFSegmentationProcessor::onDisconnectPointCloudProcessor
void onDisconnectPointCloudProcessor() override
Definition: DenseCRFSegmentationProcessor.cpp:129
TripleBuffer.h
armarx::ctrlutil::v
double v(double t, double v0, double a0, double j)
Definition: CtrlUtil.h:39
IceUtil::Handle< class PropertyDefinitionContainer >
create_macro.h
armarx::DenseCRFSegmentationProcessor::process
void process() override
Definition: DenseCRFSegmentationProcessor.cpp:139
armarx::PointWithNormalT
pcl::PointXYZRGBLNormal PointWithNormalT
Definition: Common.h:31
PointXYZRGBLNormal.h
point_cloud_graph.h
RemoteGuiComponentPlugin.h
armarx::DenseCRFSegmentationProcessor::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: DenseCRFSegmentationProcessor.cpp:55
armarx::GraphWithTimestamp
boost::subgraph< CloudGraphWithTimestamp > GraphWithTimestamp
Definition: Common.h:59
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:27
armarx::GraphWithTimestampPtr
boost::shared_ptr< GraphWithTimestamp > GraphWithTimestampPtr
Definition: Common.h:64