CoFusionProcessor.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 VisionX::ArmarXObjects::CoFusionProcessor
17  * @author Rainer Kartmann ( rainer dot kartmann at student dot kit dot edu )
18  * @date 2018
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
23 #ifndef _ARMARX_COMPONENT_VisionX_CoFusionProcessor_H
24 #define _ARMARX_COMPONENT_VisionX_CoFusionProcessor_H
25 
26 
27 #include <pcl/point_cloud.h>
28 #include <pcl/point_types.h>
29 
31 
34 #include <VisionX/interface/components/CoFusionProcessor.h>
35 
36 // from CoFusion
37 #include <Core/PoseMatch.h>
38 #include <Core/Utils/Intrinsics.h>
39 
40 #include <Core/Callbacks.h>
41 
42 #include "CoFusionParams.h"
43 #include "Stopwatch.h"
44 
45 
46 #include <RobotAPI/interface/core/RobotState.h>
47 
48 class Model;
49 
50 namespace armarx
51 {
52  /**
53  * @class CoFusionProcessorPropertyDefinitions
54  * @brief
55  */
58  {
59  public:
62  {
63  //defineRequiredProperty<std::string>("PropertyName", "Description");
64  //defineOptionalProperty<std::string>("PropertyName", "DefaultValue", "Description");
65 
66  defineOptionalProperty<std::string>("RobotStateComponentName", "RobotStateComponent", "Name of the RobotState of the Robot");
67 
68  // Point Cloud Provider properties
69  defineOptionalProperty<float>("framerate", 30.0f, "framerate for the point clouds").setMin(0.0f).setMax(60.0f);
70  defineOptionalProperty<bool>("isEnabled", true, "enable the capturing process immediately");
71 
72  defineOptionalProperty<std::string>("ImageProviderName", "ImageProvider", "Name of the input image provider.");
73 
74 
75  defineOptionalProperty<int>("FramesBetweenUpdates", 1, "Number of frames between two point cloud updates.");
76 
77  defineOptionalProperty<visionx::ImageSyncMode>("PointCloudSyncMode", visionx::eCaptureSynchronization,
78  "The point cloud sync mode ('capture' (default) or 'fps').")
79  .map("capture", visionx::eCaptureSynchronization)
80  .map("fps", visionx::eFpsSynchronization);
81 
82  defineOptionalProperty<float>("DownsamplingLeafSize", 5.0f, "If > 0, the result point cloud will be downsampled with the given leaf size.");
83 
84  defineOptionalProperty<bool>("ShowTimeStats", false, "If true, an execution time report is logged periodically.");
85 
86  defineOptionalProperty<std::string>("ReferenceFrameName", "DepthCamera", "reference frame name.");
87 
88  // COFUSION PARAMS
89  defineOptionalProperty<int>("cofusion.TimeDelta", 200, "The CoFusion time delta.");
90  defineOptionalProperty<int>("cofusion.CountThresh", 35000, "The CoFusion count thresh.");
91  defineOptionalProperty<float>("cofusion.ErrThresh", 5e-05, "The CoFusion err thresh.");
92  defineOptionalProperty<float>("cofusion.CovThresh", 1e-05, "The CoFusion cov thresh.");
93  defineOptionalProperty<bool>("cofusion.CloseLoops", false, "The CoFusion close loops.");
94  defineOptionalProperty<bool>("cofusion.Iclnuim", false, "The CoFusion iclnuim.");
95  defineOptionalProperty<bool>("cofusion.Reloc", false, "The CoFusion reloc.");
96  defineOptionalProperty<float>("cofusion.PhotoThresh", 115, "The CoFusion photo thresh.");
97  defineOptionalProperty<float>("cofusion.InitConfidenceGlobal", 4, "The CoFusion init confidence global.");
98  defineOptionalProperty<float>("cofusion.InitConfidenceObject", 2, "The CoFusion init confidence object.");
99  defineOptionalProperty<float>("cofusion.DepthCut", 3, "The CoFusion depth cut.");
100  defineOptionalProperty<float>("cofusion.IcpThresh", 10, "The CoFusion icp thresh.");
101  defineOptionalProperty<bool>("cofusion.FastOdom", false, "The CoFusion fast odom.");
102  defineOptionalProperty<float>("cofusion.FernThresh", 0.3095, "The CoFusion fern thresh.");
103  defineOptionalProperty<bool>("cofusion.So3", true, "The CoFusion so3.");
104  defineOptionalProperty<bool>("cofusion.FrameToFrameRGB", false, "The CoFusion frame to frame r g b.");
105  defineOptionalProperty<unsigned>("cofusion.ModelSpawnOffset", 20, "The CoFusion model spawn offset.");
106  defineOptionalProperty<Model::MatchingType>("cofusion.MatchingType", Model::MatchingType::Drost, "The CoFusion matching type.");
107  defineOptionalProperty<std::string>("cofusion.ExportDirectory", "", "The CoFusion export directory.");
108  defineOptionalProperty<bool>("cofusion.ExportSegmentationResults", false, "The CoFusion export segmentation results.");
109 
110 #if USE_MASKFUSION == 1
111  defineOptionalProperty<bool>("cofusion.UsePrecomputedMasksOnly", false, "");
112  defineOptionalProperty<int>("cofusion.FrameQueueSize", 5, "Set size of frame-queue manually");
113  defineOptionalProperty<int>("cofusion.DeviceMaskRCNN", -1, "Select GPU (device ID) which is running MaskRCNN.");
114 
115  defineOptionalProperty<int>("cofusion.PreallocatedModelsCount", 1, " Preallocate memory for a number of models, which can increase performance (default: 0)");
116 #endif
117  }
118  };
119 
120  /**
121  * @defgroup Component-CoFusionProcessor CoFusionProcessor
122  * @ingroup VisionX-Components
123  * A description of the component CoFusionProcessor.
124  *
125  * @class CoFusionProcessor
126  * @ingroup Component-CoFusionProcessor
127  * @brief Brief description of class CoFusionProcessor.
128  *
129  * Detailed description of class CoFusionProcessor.
130  */
132  virtual public visionx::ImageProcessor,
134  virtual public visionx::CoFusionProcessorInterface
135  {
136  public:
137  /**
138  * @see armarx::ManagedIceObject::getDefaultName()
139  */
140  std::string getDefaultName() const override
141  {
142  return "CoFusionProcessor";
143  }
144 
145 
146 
147  // CapturingPointCloudProviderInterface interface
148  virtual void startCaptureForNumFrames(Ice::Int numFrames, const Ice::Current& c = Ice::emptyCurrent) override;
149 
150  protected:
151 
152  // ImageProcessor interface
153  virtual void onInitImageProcessor() override;
154  /// Allocates imageRgb and imageDepth and sets images[].
155  virtual void onConnectImageProcessor() override;
156  /// Frees imageRgb and imageDepth.
157  virtual void onDisconnectImageProcessor() override;
158  virtual void onExitImageProcessor() override;
159 
160  /**
161  * @brief Performs the image processing.
162  *
163  * Processes input images, constructs FrameData and calls CoFusion::processFrame().
164  *
165  * This is the (only) thread that directly accesses cofusion.
166  * If cofusion is not allocated, it is initialized via initializeCoFusion().
167  *
168  * Every <framesBetweenUpdates> frames, updateSurfelMaps() is called.
169  */
170  virtual void process() override;
171 
172 
173  // CapturingPointCloudProvider interface
174  virtual void onInitCapturingPointCloudProvider() override;
175  virtual void onExitCapturingPointCloudProvider() override;
176  virtual void onStartCapture(float framesPerSecond) override;
177  virtual void onStopCapture() override;
178 
179  virtual bool doCapture() override;
180 
181  virtual visionx::MetaPointCloudFormatPtr getDefaultPointCloudFormat() override;
182 
183 
184  // ManagedIceObject interface (multiple inheritance)
185  virtual void onInitComponent() override;
186  virtual void onConnectComponent() override;
187  virtual void onDisconnectComponent() override;
188  virtual void onExitComponent() override;
189 
190 
191  void onNewModel(std::shared_ptr<Model> model);
192  void onInactiveModel(std::shared_ptr<Model> model);
193 
194 
195 
196  /**
197  * @see PropertyUser::createPropertyDefinitions()
198  */
200 
201  private:
202 
203  using OutPointT = pcl::PointXYZRGBL;
204 
205  /**
206  * @brief Initializes CoFusion.
207  * Initializes Pangolin, glew and creates a gl program.
208  * Allocates and sets cofusion.
209  */
210  void initializeCoFusion();
211 
212  /**
213  * @brief Constructs frame data from current imageRgb and imageDepth.
214  * @return the frame data
215  */
216  FrameData constructFrameData();
217 
218  /** @brief Updates surfelMaps with current CoFusion models. */
219  void updateSurfelMaps();
220 
221  /**
222  * \brief Constructs result point cloud from current surfelMaps.
223  * Allocates surfelMapMutex internally.
224  */
225  void reconstructResultPointCloud();
226 
227  /// Called periodically by stopwatchReportTask.
228  void reportStopwatchStats();
229 
230 
231  std::string imageProviderName;
232  visionx::ImageProviderInterfacePrx imageProvider;
233 
234 
235  // == CoFusion ==
236  CoFusionParams cofusionParams;
237 
238 #if USE_MASKFUSION == 1
239  std::unique_ptr<MaskFusion> cofusion;
240 #else
241  std::unique_ptr<CoFusion> cofusion;
242 #endif
243 
244 
245  // == input image processing ==
246  /// to be acquired when accessing images
247  std::mutex imagesMutex;
248 
249  /// input RGB image
250  visionx::CByteImageUPtr imageRgb;
251  /// input depth image
252  visionx::CByteImageUPtr imageDepth;
253  /// [ imageRgb, imageDepth ]
254  CByteImage* images[2];
255 
256 
257  /// Number of frames from one point cloud update to the next.
258  std::size_t framesBetweenUpdates;
259  /// Current number of frames since the latest point cloud update.
260  std::size_t framesSinceLastUpdate = 0;
261 
262 
263  // == output surfel maps for point cloud construction ==
264  /// to be acquired when accessing surfelMaps
265  std::mutex surfelMapMutex;
266 
267  /// The SurfelMaps of CoFusion models (up to framesBetweenUpdates frames old)
268  std::map<unsigned int, Model::SurfelMap> surfelMaps;
269  /// If not empty, contains the output point cloud constructed from the surfel maps.
270  pcl::PointCloud<OutPointT>::Ptr resultPointCloud;
271 
272  /// If > 0, this will be used for downsampling.
273  float downsamplingLeafSize = 0.f;
274 
275  /// Used for time stats
277 
279 
280  RobotStateComponentInterfacePrx robotStateComponent;
281 
282  std::string referenceFrameName;
283 
284  std::atomic<bool> newFrameAvailable = false;
285 
286  };
287 }
288 
289 #endif
armarx::CoFusionProcessor::getDefaultName
std::string getDefaultName() const override
Definition: CoFusionProcessor.h:140
CapturingPointCloudProvider.h
FrameData
Definition: TactileSensor.h:61
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
Stopwatch.h
visionx::ImageProcessor
The ImageProcessor class provides an interface for access to ImageProviders via Ice and shared memory...
Definition: ImageProcessor.h:87
armarx::CoFusionProcessor::onConnectComponent
virtual void onConnectComponent() override
Definition: CoFusionProcessor.cpp:147
armarx::CoFusionProcessor::onDisconnectImageProcessor
virtual void onDisconnectImageProcessor() override
Frees imageRgb and imageDepth.
Definition: CoFusionProcessor.cpp:76
armarx::CoFusionProcessor::startCaptureForNumFrames
virtual void startCaptureForNumFrames(Ice::Int numFrames, const Ice::Current &c=Ice::emptyCurrent) override
Definition: CoFusionProcessor.cpp:450
armarx::PropertyDefinitionContainer::prefix
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
Definition: PropertyDefinitionContainer.h:333
PeriodicTask.h
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:43
armarx::CoFusionProcessor::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: CoFusionProcessor.cpp:573
visionx::ImageProcessorPropertyDefinitions::ImageProcessorPropertyDefinitions
ImageProcessorPropertyDefinitions(std::string prefix)
Definition: ImageProcessor.h:65
armarx::CoFusionProcessor::process
virtual void process() override
Performs the image processing.
Definition: CoFusionProcessor.cpp:228
armarx::CoFusionProcessor::onDisconnectComponent
virtual void onDisconnectComponent() override
Hook for subclass.
Definition: CoFusionProcessor.cpp:203
armarx::CoFusionProcessor::onStopCapture
virtual void onStopCapture() override
This is called when the point cloud provider capturing has been stopped.
Definition: CoFusionProcessor.cpp:455
armarx::CoFusionProcessor::doCapture
virtual bool doCapture() override
Main capturing function.
Definition: CoFusionProcessor.cpp:459
armarx::CoFusionProcessor::onInitCapturingPointCloudProvider
virtual void onInitCapturingPointCloudProvider() override
This is called when the Component::onInitComponent() is called.
Definition: CoFusionProcessor.cpp:94
armarx::CoFusionProcessor::onInitComponent
virtual void onInitComponent() override
Definition: CoFusionProcessor.cpp:105
visionx::CByteImageUPtr
std::unique_ptr< CByteImage > CByteImageUPtr
Definition: ImageProvider.h:57
armarx::CoFusionProcessor::onStartCapture
virtual void onStartCapture(float framesPerSecond) override
This is called when the point cloud provider capturing has been started.
Definition: CoFusionProcessor.cpp:445
armarx::CoFusionProcessor::getDefaultPointCloudFormat
virtual visionx::MetaPointCloudFormatPtr getDefaultPointCloudFormat() override
default point cloud format used to initialize shared memory
Definition: CoFusionProcessor.cpp:558
ImageProcessor.h
armarx::CoFusionProcessor::onNewModel
void onNewModel(std::shared_ptr< Model > model)
Definition: CoFusionProcessor.cpp:215
stopwatch
Definition: Stopwatch.cpp:4
armarx::CoFusionProcessor::onExitCapturingPointCloudProvider
virtual void onExitCapturingPointCloudProvider() override
This is called when the Component::onExitComponent() setup is called.
Definition: CoFusionProcessor.cpp:99
armarx::CoFusionProcessor::onExitImageProcessor
virtual void onExitImageProcessor() override
Exit the ImapeProcessor component.
Definition: CoFusionProcessor.cpp:88
stopwatch::Stopwatch
Definition: Stopwatch.h:30
armarx::CoFusionParams
Definition: CoFusionParams.h:16
visionx::CapturingPointCloudProvider
The CapturingPointCloudProvider provides a callback function to trigger the capturing of point clouds...
Definition: CapturingPointCloudProvider.h:56
CoFusionParams.h
armarx::CoFusionProcessor
Brief description of class CoFusionProcessor.
Definition: CoFusionProcessor.h:131
armarx::CoFusionProcessor::onInactiveModel
void onInactiveModel(std::shared_ptr< Model > model)
Definition: CoFusionProcessor.cpp:221
armarx::CoFusionProcessorPropertyDefinitions::CoFusionProcessorPropertyDefinitions
CoFusionProcessorPropertyDefinitions(std::string prefix)
Definition: CoFusionProcessor.h:60
armarx::CoFusionProcessor::onExitComponent
virtual void onExitComponent() override
Definition: CoFusionProcessor.cpp:209
IceUtil::Handle< class PropertyDefinitionContainer >
visionx::ImageProcessorPropertyDefinitions
Definition: ImageProcessor.h:61
IceInternal::ProxyHandle<::IceProxy::armarx::RobotStateComponentInterface >
armarx::VariantType::Int
const VariantTypeId Int
Definition: Variant.h:916
armarx::CoFusionProcessor::onInitImageProcessor
virtual void onInitImageProcessor() override
Setup the vision component.
Definition: CoFusionProcessor.cpp:45
armarx::CoFusionProcessor::onConnectImageProcessor
virtual void onConnectImageProcessor() override
Allocates imageRgb and imageDepth and sets images[].
Definition: CoFusionProcessor.cpp:54
armarx::CoFusionProcessorPropertyDefinitions
Definition: CoFusionProcessor.h:56
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28