23 #ifndef _ARMARX_COMPONENT_VisionX_CoFusionProcessor_H
24 #define _ARMARX_COMPONENT_VisionX_CoFusionProcessor_H
27 #include <pcl/point_cloud.h>
28 #include <pcl/point_types.h>
34 #include <VisionX/interface/components/CoFusionProcessor.h>
37 #include <Core/PoseMatch.h>
38 #include <Core/Utils/Intrinsics.h>
40 #include <Core/Callbacks.h>
46 #include <RobotAPI/interface/core/RobotState.h>
66 defineOptionalProperty<std::string>(
"RobotStateComponentName",
"RobotStateComponent",
"Name of the RobotState of the Robot");
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");
72 defineOptionalProperty<std::string>(
"ImageProviderName",
"ImageProvider",
"Name of the input image provider.");
75 defineOptionalProperty<int>(
"FramesBetweenUpdates", 1,
"Number of frames between two point cloud updates.");
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);
82 defineOptionalProperty<float>(
"DownsamplingLeafSize", 5.0f,
"If > 0, the result point cloud will be downsampled with the given leaf size.");
84 defineOptionalProperty<bool>(
"ShowTimeStats",
false,
"If true, an execution time report is logged periodically.");
86 defineOptionalProperty<std::string>(
"ReferenceFrameName",
"DepthCamera",
"reference frame name.");
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.");
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.");
115 defineOptionalProperty<int>(
"cofusion.PreallocatedModelsCount", 1,
" Preallocate memory for a number of models, which can increase performance (default: 0)");
134 virtual public visionx::CoFusionProcessorInterface
142 return "CoFusionProcessor";
170 virtual void process()
override;
191 void onNewModel(std::shared_ptr<Model> model);
203 using OutPointT = pcl::PointXYZRGBL;
210 void initializeCoFusion();
219 void updateSurfelMaps();
225 void reconstructResultPointCloud();
228 void reportStopwatchStats();
231 std::string imageProviderName;
232 visionx::ImageProviderInterfacePrx imageProvider;
238 #if USE_MASKFUSION == 1
239 std::unique_ptr<MaskFusion> cofusion;
241 std::unique_ptr<CoFusion> cofusion;
247 std::mutex imagesMutex;
254 CByteImage* images[2];
258 std::size_t framesBetweenUpdates;
260 std::size_t framesSinceLastUpdate = 0;
265 std::mutex surfelMapMutex;
268 std::map<unsigned int, Model::SurfelMap> surfelMaps;
270 pcl::PointCloud<OutPointT>::Ptr resultPointCloud;
273 float downsamplingLeafSize = 0.f;
282 std::string referenceFrameName;
284 std::atomic<bool> newFrameAvailable =
false;