27 #include <Eigen/Geometry>
29 #include <pcl/filters/approximate_voxel_grid.h>
31 #include <VisionX/interface/components/PointCloudAndImageAndCalibrationProviderInterface.h>
32 #include <VisionX/interface/components/RGBDImageProvider.h>
35 #include <Core/Model/Model.h>
37 #include <Image/IplImageAdaptor.h>
38 #include <pangolin/pangolin.h>
46 imageProviderName = getProperty<std::string>(
"ImageProviderName").getValue();
55 imageProvider = getProxy<visionx::ImageProviderInterfacePrx>(imageProviderName);
60 ARMARX_ERROR <<
"Number of images provided by " << imageProviderName <<
" ("
62 <<
") does not match the expected number of images (" << numImages <<
")";
66 std::lock_guard<std::mutex> lock(imagesMutex);
70 images[0] = imageRgb.get();
71 images[1] = imageDepth.get();
78 std::lock_guard<std::mutex> lock(imagesMutex);
82 imageRgb.reset(
nullptr);
83 imageDepth.reset(
nullptr);
85 imageProvider =
nullptr;
107 ImageProcessor::onInitComponent();
108 CapturingPointCloudProvider::onInitComponent();
110 framesBetweenUpdates = getProperty<int>(
"FramesBetweenUpdates").getValue();
111 downsamplingLeafSize = getProperty<float>(
"DownsamplingLeafSize").getValue();
113 framesSinceLastUpdate = framesBetweenUpdates;
115 resultPointCloud.reset(
new pcl::PointCloud<OutPointT>());
120 cofusionParams.
timeDelta = getProperty<int>(
"cofusion.TimeDelta").getValue();
121 cofusionParams.
countThresh = getProperty<int>(
"cofusion.CountThresh").getValue();
122 cofusionParams.
errThresh = getProperty<float>(
"cofusion.ErrThresh").getValue();
123 cofusionParams.
covThresh = getProperty<float>(
"cofusion.CovThresh").getValue();
124 cofusionParams.
closeLoops = getProperty<bool>(
"cofusion.CloseLoops").getValue();
125 cofusionParams.
iclnuim = getProperty<bool>(
"cofusion.Iclnuim").getValue();
126 cofusionParams.
reloc = getProperty<bool>(
"cofusion.Reloc").getValue();
127 cofusionParams.
photoThresh = getProperty<float>(
"cofusion.PhotoThresh").getValue();
129 getProperty<float>(
"cofusion.InitConfidenceGlobal").getValue();
131 getProperty<float>(
"cofusion.InitConfidenceObject").getValue();
132 cofusionParams.
depthCut = getProperty<float>(
"cofusion.DepthCut").getValue();
133 cofusionParams.
icpThresh = getProperty<float>(
"cofusion.IcpThresh").getValue();
134 cofusionParams.
fastOdom = getProperty<bool>(
"cofusion.FastOdom").getValue();
135 cofusionParams.
fernThresh = getProperty<float>(
"cofusion.FernThresh").getValue();
136 cofusionParams.
so3 = getProperty<bool>(
"cofusion.So3").getValue();
137 cofusionParams.
frameToFrameRGB = getProperty<bool>(
"cofusion.FrameToFrameRGB").getValue();
138 cofusionParams.
modelSpawnOffset = getProperty<unsigned>(
"cofusion.ModelSpawnOffset").getValue();
140 getProperty<Model::MatchingType>(
"cofusion.MatchingType").getValue();
142 getProperty<std::string>(
"cofusion.ExportDirectory").getValue();
144 getProperty<bool>(
"cofusion.ExportSegmentationResults").getValue();
146 #if USE_MASKFUSION == 1
147 cofusionParams.usePrecomputedMasksOnly =
148 getProperty<bool>(
"cofusion.UsePrecomputedMasksOnly").getValue();
149 cofusionParams.frameQueueSize = getProperty<int>(
"cofusion.FrameQueueSize").getValue();
158 ImageProcessor::onConnectComponent();
159 CapturingPointCloudProvider::onConnectComponent();
164 visionx::StereoCalibrationProviderInterfacePrx calibrationProvider =
165 visionx::StereoCalibrationProviderInterfacePrx::checkedCast(imageProvider);
167 if (calibrationProvider)
169 ARMARX_LOG <<
"reading intrinsics from calibration provider";
170 visionx::StereoCalibration calibration = calibrationProvider->getStereoCalibration();
172 cofusionParams.
fx = calibration.calibrationRight.cameraParam.focalLength[0];
173 cofusionParams.
fy = calibration.calibrationRight.cameraParam.focalLength[1];
174 cofusionParams.
cx = calibration.calibrationRight.cameraParam.principalPoint[0];
175 cofusionParams.
cy = calibration.calibrationRight.cameraParam.principalPoint[1];
177 referenceFrameName = calibrationProvider->getReferenceFrame();
181 cofusionParams.
fx = 525.0;
182 cofusionParams.
fy = 525.0;
183 cofusionParams.
cx = 320;
184 cofusionParams.
cy = 240;
185 referenceFrameName =
"unkown";
186 ARMARX_WARNING <<
"unable to get camera intrinsics. using dummy values";
190 visionx::ImageFormatInfo imageFormat = imageProvider->getImageFormat();
192 cofusionParams.
width = imageFormat.dimension.width;
193 cofusionParams.
height = imageFormat.dimension.height;
196 if (getProperty<bool>(
"ShowTimeStats").getValue())
198 if (stopwatchReportTask)
200 stopwatchReportTask->stop();
204 this, &CoFusionProcessor::reportStopwatchStats, 10000);
205 stopwatchReportTask->start();
208 providePointCloud<OutPointT>(resultPointCloud);
214 ImageProcessor::onDisconnectComponent();
215 CapturingPointCloudProvider::onDisconnectComponent();
221 ImageProcessor::onExitComponent();
222 CapturingPointCloudProvider::onExitComponent();
243 ARMARX_WARNING <<
"Timeout or error in waitForImages(" << imageProviderName <<
")";
249 std::lock_guard<std::mutex> lock(imagesMutex);
251 armarx::MetaInfoSizeBasePtr metaInfo;
253 int numImages =
getImages(imageProviderName, images, metaInfo);
256 ARMARX_WARNING <<
"Did not receive correct number of images! (Expected 2, but was "
257 << numImages <<
".) Aborting!";
263 initializeCoFusion();
276 stopwatch.start(
"CoFusion::ProcessFrame");
278 #if USE_MASKFUSION == 1
279 std::shared_ptr<FrameData> framePtr = std::make_shared<FrameData>(frame);
281 cofusion->processFrame(framePtr);
283 cofusion->processFrame(frame);
286 stopwatch.stop(
"CoFusion::ProcessFrame");
289 framesSinceLastUpdate++;
290 if (framesSinceLastUpdate >= framesBetweenUpdates)
293 framesSinceLastUpdate = 0;
300 CoFusionProcessor::initializeCoFusion()
302 ARMARX_INFO <<
"Initializing CoFusion (resolution: " << cofusionParams.
width <<
"x"
303 << cofusionParams.
height <<
")";
305 pangolin::Params windowParams;
306 windowParams.Set(
"SAMPLE_BUFFERS", 0);
307 windowParams.Set(
"SAMPLES", 0);
309 pangolin::CreateWindowAndBind(
310 "Main", cofusionParams.
width, cofusionParams.
height, windowParams);
313 GLenum glewInitError = glewInit();
316 ARMARX_ERROR <<
"glewInit() failed with error: " << glewInitError;
319 int prog = glCreateProgram();
320 ARMARX_INFO <<
"Created gl program (" << prog <<
")";
327 cofusion->addNewModelListener([
this](std::shared_ptr<Model> m) {
onNewModel(m); });
328 cofusion->addInactiveModelListener([
this](std::shared_ptr<Model> m) {
onInactiveModel(m); });
330 #if USE_MASKFUSION == 1
331 cofusion->preallocateModels(getProperty<int>(
"cofusion.PreallocatedModelsCount").getValue());
336 CoFusionProcessor::constructFrameData()
338 bool copyData =
false;
339 cv::Mat matRgb = cv::cvarrToMat(IplImageAdaptor::Adapt(imageRgb.get()), copyData);
340 cv::Mat matDepth = cv::cvarrToMat(IplImageAdaptor::Adapt(imageDepth.get()), copyData);
349 int rows = matDepth.rows;
350 int cols = matDepth.cols;
354 cv::Mat matDepthCofusion(rows, cols, CV_32FC1);
356 for (
int x = 0; x < rows; ++x)
358 for (
int y = 0; y < cols; ++y)
380 cv::Vec3b depthPixel = matDepth.at<cv::Vec3b>(x, y);
383 value += depthPixel[0];
384 value += depthPixel[1] << 8;
385 value += depthPixel[2] << 16;
400 matDepthCofusion.at<
float>(x, y) = depth;
404 frame.depth = matDepthCofusion;
410 CoFusionProcessor::updateSurfelMaps()
412 std::list<std::shared_ptr<Model>>& models = cofusion->getModels();
420 std::lock_guard<std::mutex> lock(surfelMapMutex);
422 ARMARX_INFO <<
"Downloading surfel maps of " << models.size() <<
" models ...";
424 for (std::shared_ptr<Model>
const& model : models)
426 unsigned int id = model->getID();
433 surfelMaps[id] = model->downloadMap();
436 Model::SurfelMap& surfelMap = surfelMaps[id];
437 ARMARX_VERBOSE <<
"SurfelMap contains " << surfelMap.numPoints <<
" points "
438 <<
"(container size: " << surfelMap.data->size() <<
")";
444 newFrameAvailable =
true;
456 <<
"CoFusionProcessor does currently not support startCaptureForNumFrames(numFrames)";
467 if (newFrameAvailable)
469 newFrameAvailable =
false;
470 resultPointCloud.reset();
471 reconstructResultPointCloud();
472 providePointCloud<OutPointT>(resultPointCloud);
482 CoFusionProcessor::reconstructResultPointCloud()
484 std::lock_guard<std::mutex> lock(surfelMapMutex);
486 resultPointCloud.reset(
new pcl::PointCloud<OutPointT>());
489 ARMARX_INFO <<
"Reconstructing point cloud from " << surfelMaps.size() <<
" SurfelMaps.";
490 stopwatch.start(
"PointCloud construction");
492 for (
auto& it : surfelMaps)
494 unsigned int id = it.first;
495 Model::SurfelMap& surfelMap = it.second;
498 ARMARX_INFO <<
"SurfelMap of model " <<
id <<
" contains " << surfelMap.numPoints
500 <<
"(container size: " << surfelMap.data->size() <<
")";
511 resultPointCloud->reserve(resultPointCloud->size() + surfelMap.numPoints);
513 for (
unsigned int i = 0; i < surfelMap.numPoints; ++i)
515 Eigen::Vector4f& position4f = (*surfelMap.data)[i * 3 + 0];
516 position4f.head<3>() *= 1000;
518 Eigen::Vector4f& color4f = (*surfelMap.data)[i * 3 + 1];
521 uint32_t color24b =
static_cast<uint32_t
>(color4f(0));
522 uchar r = (color24b >> 16) & 0xFF;
523 uchar g = (color24b >> 8) & 0xFF;
524 uchar b = (color24b >> 0) & 0xFF;
531 pcl::PointXYZRGBL point;
532 point.x = position4f(0);
533 point.y = position4f(1);
534 point.z = position4f(2);
539 resultPointCloud->push_back(point);
545 if (downsamplingLeafSize > 0.f)
547 pcl::PointCloud<OutPointT>::Ptr filtered(
new pcl::PointCloud<OutPointT>());
548 std::size_t sizeBefore = resultPointCloud->size();
550 pcl::ApproximateVoxelGrid<OutPointT> grid;
551 grid.setLeafSize(downsamplingLeafSize, downsamplingLeafSize, downsamplingLeafSize);
552 grid.setInputCloud(resultPointCloud);
553 grid.filter(*filtered);
554 resultPointCloud.swap(filtered);
556 std::size_t sizeAfter = resultPointCloud->size();
558 ARMARX_INFO <<
"Downsampled to " << sizeAfter <<
" points (before: " << sizeBefore <<
")";
561 stopwatch.stop(
"PointCloud construction");
564 visionx::MetaPointCloudFormatPtr
567 visionx::MetaPointCloudFormatPtr info =
new visionx::MetaPointCloudFormat();
568 info->capacity = 50 * 640 * 480 *
sizeof(visionx::ColoredLabeledPoint3D);
569 info->size = info->capacity;
570 info->type = visionx::eColoredLabeledPoints;
575 CoFusionProcessor::reportStopwatchStats()