23 #ifndef _ARMARX_COMPONENT_ROBDEKON_DenseCRFSegmentationProcessor_H
24 #define _ARMARX_COMPONENT_ROBDEKON_DenseCRFSegmentationProcessor_H
29 #include <ArmarXCore/interface/observers/ObserverInterface.h>
33 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
36 #include <boost/graph/filtered_graph.hpp>
38 #include <pcl/point_types.h>
43 #include <ArmarXGui/interface/RemoteGuiInterface.h>
49 #include <VisionX/interface/components/DenseCRFSegmentationProcessorInterface.h>
59 armarx::densecrf::config,
63 AX_DESCRIPTION(
"Number of maximal object classes in an image"),
70 AX_DESCRIPTION(
"Number of maximal object classes in an image"),
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."),
83 use_approximate_voxels,
84 AX_DESCRIPTION(
"If true & UseVertexOnlyGraph is true, the downsampling"
85 " uses the ApproximateVoxelGrid for downsampling instead of the normal"
90 AX_DESCRIPTION(
"Resolution of the Voxels used as Vertices of the Graph"),
98 AX_DESCRIPTION(
"Number of iterations used for the map"),
104 armarx::densecrf::config,
107 provide_graph_pclouds,
108 AX_DESCRIPTION(
"If true a segmentation for each timestep"
109 "is provided as result cloud"),
113 provide_confidence_pclouds,
114 AX_DESCRIPTION(
"If true a confidence for each timestep"
115 "is provided as result cloud"),
119 colorize_confidence_pclouds,
120 AX_DESCRIPTION(
"If true the confidence pclouds are colorized"),
122 AX_NO_REMOTE_GUI()));
125 armarx::densecrf::config,
129 AX_DESCRIPTION(
"If true xyz values are used for edge computation"),
133 AX_DESCRIPTION(
"Weight for the influence of position in the edge computation"),
141 AX_DESCRIPTION(
"If true normal values are used for edge computation"),
145 AX_DESCRIPTION(
"Weight for the influence of normals in the edge computation"),
153 AX_DESCRIPTION(
"If true RGB values are used for edge computation"),
157 AX_DESCRIPTION(
"Weight for the influence of color in the edge computation"),
165 AX_DESCRIPTION(
"If true curvature values are used for edge computation"),
169 AX_DESCRIPTION(
"Weight for the influence of curvature in the edge computation"),
177 AX_DESCRIPTION(
"If true time values are used for edge computation"),
181 AX_DESCRIPTION(
"Weight for the influence of time in the edge computation"),
189 AX_DESCRIPTION(
"If true the influence values are combined before they are given to DenseCRF"),
193 AX_DESCRIPTION(
"Weight factor for the Potts Compatibility"),
202 (armarx::densecrf::config::general, general),
203 (armarx::densecrf::config::output, out),
204 (armarx::densecrf::config::edge_comp, edge));
236 virtual public DenseCRFSegmentationProcessorInterface,
249 return "DenseCRFSegmentationProcessor";
259 const Ice::Current& current)
override;
294 template <
typename TimestampMap>
295 struct vertex_timestamp_unequal_filter
297 vertex_timestamp_unequal_filter() =
default;
299 vertex_timestamp_unequal_filter(
TimestampMap tsm,
double ts) : m_tsm(tsm), m_ts(ts)
303 template <
typename Vertex>
305 operator()(
const Vertex&
v)
const
308 double current_ts = get(m_tsm,
v);
309 return abs(m_ts - current_ts) > 0.00001;
316 template <
typename TimestampMap>
317 struct vertex_timestamp_equal_filter
319 vertex_timestamp_equal_filter() =
default;
321 vertex_timestamp_equal_filter(
TimestampMap tsm,
double ts) : m_tsm(tsm), m_ts(ts)
325 template <
typename Vertex>
327 operator()(
const Vertex&
v)
const
330 double current_ts = get(m_tsm,
v);
331 return abs(m_ts - current_ts) < 0.00001;
338 double initial_time_;
342 std::deque<Graph> graph_queue_;
343 std::deque<double> timestamp_queue_;
345 void computeGraphUsingVoxelGrid(
const PointCloudT::Ptr inputCloudPtr);
347 void computeVertexOnlyGraph(pcl::PointCloud<PointT>::Ptr input_cloud_ptr);
349 void generateRandomClassLabels();
351 void relabelPointCloud(pcl::PointCloud<PointT>::Ptr input_cloud_ptr);
357 void updatePersistentGraph();
359 void addGraphToPersistentGraph(
Graph& graph);
361 void addCurrentGraphToPersistentGraph();
363 void removeGraphFromPersistentGraph(
Graph& graph);
365 void removeCurrentGraphFromPersistentGraph();
367 void removeTimestampFromPersistentGraph(
double ts);
369 static void copyRGBLToRGBLNormal(
PointCloudT& input_cloud,
379 template <
typename FilterT>
381 filterAndCopyPersistentGraph(
TimestampMap tsm, FilterT filter)
384 typedef boost::filtered_graph<GraphWithTimestamp, boost::keep_all, FilterT>
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;
396 int num_vertices = 0;
397 for (boost::tie(vi, v_end) = boost::vertices(filtered_graph); vi != v_end; ++vi)
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;
411 pcl::PointCloud<pcl::PointXYZL>::ConstPtr selectRandomSeeds();
413 Eigen::MatrixXf computeRandomUnaryEnergy(
int num_points);
415 void provideAllGraphs();
416 void provideAllConfidences();
418 WriteBufferedTripleBuffer<armarx::densecrf::config::data> config_;
419 std::mutex write_mutex_;