27 #include <VisionX/interface/components/PointCloudAndImageAndCalibrationProviderInterface.h>
29 #include <rtabmap/core/Transform.h>
30 #include <rtabmap/core/odometry/OdometryF2M.h>
31 #include <rtabmap/core/util3d.h>
34 using namespace rtabmap;
46 agentName = getProperty<std::string>(
"agentName").getValue();
47 provideGlobalPointCloud = getProperty<bool>(
"provideGlobalPointCloud").getValue();
49 usingProxy(getProperty<std::string>(
"RobotStateComponentName").getValue());
50 usingProxy(getProperty<std::string>(
"WorkingMemoryName").getValue());
52 passThroughFilter.setFilterFieldName(
"z");
53 passThroughFilter.setFilterLimits(getProperty<float>(
"MinDistance").getValue(),
54 getProperty<float>(
"MaxDistance").getValue());
59 ParametersMap parameters;
61 parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kMemImageKept(),
"true"));
63 ULogger::setType(ULogger::kTypeConsole);
65 ULogger::setLevel(ULogger::kWarning);
67 rtabmap =
new Rtabmap();
68 rtabmap->init(parameters);
69 rtabmapThread =
new RtabmapThread(rtabmap);
71 odomThread =
new OdometryThread(
new OdometryF2M());
73 odomThread->registerToEventsManager();
74 rtabmapThread->registerToEventsManager();
76 this->registerToEventsManager();
78 UEventsManager::createPipe(
this, odomThread,
"CameraEvent");
84 this->unregisterFromEventsManager();
86 resultCondition.notify_one();
87 dataCondition.notify_one();
89 rtabmapThread->unregisterFromEventsManager();
90 odomThread->unregisterFromEventsManager();
92 odomThread->join(
true);
93 rtabmapThread->join(
true);
105 robotStateComponent = getProxy<RobotStateComponentInterfacePrx>(
106 getProperty<std::string>(
"RobotStateComponentName").getValue());
107 workingMemory = getProxy<memoryx::WorkingMemoryInterfacePrx>(
108 getProperty<std::string>(
"WorkingMemoryName").getValue());
109 agentInstancesSegment = workingMemory->getAgentInstancesSegment();
121 resultPointCloudPtr.reset(
new pcl::PointCloud<pcl::PointXYZRGBA>);
122 hasNewResultPointCloud =
false;
125 FramedPoseBasePtr poseInGlobalFrame =
126 synchronizedRobot->getRobotNode(sourceFrameName)->getGlobalPose();
127 initialCameraPose = armarx::FramedPosePtr::dynamicCast(poseInGlobalFrame)->toEigen();
129 rtabmapThread->start();
135 while (captureEnabled && (!rtabmapThread->isRunning() || !odomThread->isRunning()))
144 if (provideGlobalPointCloud)
146 requestGlobalPointCloud();
156 rtabmapThread->kill();
160 RTABMapRegistration::requestGlobalPointCloud()
162 UEventsManager::post(
new RtabmapEventCmd(RtabmapEventCmd::kCmdPublish3DMap,
true,
true,
false));
168 boost::mutex::scoped_lock lock(resultPointCloudMutex);
170 while (captureEnabled && !hasNewResultPointCloud)
172 resultCondition.wait(lock);
180 hasNewResultPointCloud =
false;
182 if (resultPointCloudPtr->points.size())
184 providePointCloud(resultPointCloudPtr);
197 if (event->getClassName().compare(
"RtabmapEvent") == 0)
199 RtabmapEvent* rtabmapEvent =
static_cast<RtabmapEvent*
>(event);
201 boost::mutex::scoped_lock lock(RTABDataMutex);
217 if (!provideGlobalPointCloud)
219 signatures = rtabmapEvent->getStats().getSignatures();
222 dataCondition.notify_one();
225 else if (event->getClassName().compare(
"OdometryEvent") == 0)
227 OdometryEvent* rtabmapEvent =
static_cast<OdometryEvent*
>(event);
229 if (rtabmapEvent->pose().isNull())
232 <<
"unable to register current view. odometry lost.";
235 else if (provideGlobalPointCloud && event->getClassName().compare(
"RtabmapEvent3DMap") == 0)
237 RtabmapEvent3DMap* rtabmapEvent =
static_cast<RtabmapEvent3DMap*
>(event);
239 boost::mutex::scoped_lock lock(RTABDataMutex);
241 signatures = rtabmapEvent->getSignatures();
242 poses = rtabmapEvent->getPoses();
245 dataCondition.notify_one();
252 RTABMapRegistration::extractPointCloud(SensorData sensorData,
254 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr& tempCloudPtr)
256 std::vector<CameraModel> cameraModels = sensorData.cameraModels();
258 if (cameraModels.size() != 1)
263 CameraModel m = cameraModels[0];
268 int decimation = (provideGlobalPointCloud) ? 4 : 1;
270 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudPtr = util3d::cloudFromDepthRGB(
271 sensorData.imageRaw(), sensorData.depthOrRightRaw(), m, decimation);
273 pcl::copyPointCloud(*cloudPtr, *tempCloudPtr);
274 passThroughFilter.setInputCloud(tempCloudPtr);
275 passThroughFilter.filter(*tempCloudPtr);
277 Eigen::Affine3f convertUnitToMM = Eigen::Affine3f(Eigen::Scaling(1000.0f));
278 pcl::transformPointCloud(*tempCloudPtr, *tempCloudPtr, convertUnitToMM);
280 pcl::transformPointCloud(*tempCloudPtr, *tempCloudPtr,
transform);
286 RTABMapRegistration::processData()
288 boost::mutex::scoped_lock lock(RTABDataMutex);
290 while (captureEnabled && !hasNewData)
292 dataCondition.wait(lock);
302 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr nextCloudPtr(
new pcl::PointCloud<pcl::PointXYZRGBA>());
304 for (
auto& items : signatures)
306 const int id = items.first;
307 const Signature signature = items.second;
309 if (signature.isBadSignature())
314 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr tempCloudPtr(
315 new pcl::PointCloud<pcl::PointXYZRGBA>());
319 if (signature.isEnabled())
321 transform = signature.getPose().toEigen4f();
335 extractPointCloud(signature.sensorData(),
transform, tempCloudPtr);
337 *nextCloudPtr += *tempCloudPtr;
346 if (provideGlobalPointCloud)
348 requestGlobalPointCloud();
352 boost::mutex::scoped_lock resultLock(resultPointCloudMutex);
356 pcl::copyPointCloud(*nextCloudPtr, *resultPointCloudPtr);
358 hasNewResultPointCloud =
true;
359 resultCondition.notify_one();
368 Eigen::Vector3f position = pose.block<3, 1>(0, 3);
370 agentInstance->setOrientation(orientationPtr);
371 agentInstance->setPosition(positionPtr);
373 if (agentInstanceId.empty() || !agentInstancesSegment->hasEntityById(agentInstanceId))
375 agentInstanceId = agentInstancesSegment->addEntity(agentInstance);
379 agentInstancesSegment->updateEntity(agentInstanceId, agentInstance);
386 providerName = getProperty<std::string>(
"providerName").getValue();
387 usingImageProvider(providerName);
405 images =
new CByteImage*[numImages];
407 for (
int i = 0; i < numImages; i++)
412 visionx::StereoCalibrationInterfacePrx calibrationProvider =
413 visionx::StereoCalibrationInterfacePrx::checkedCast(imageProviderInfo.
proxy);
414 if (!calibrationProvider)
416 ARMARX_FATAL <<
"unable to retrieve calibration information. aborting.";
420 sourceFrameName = calibrationProvider->getReferenceFrame();
422 visionx::StereoCalibration calibration = calibrationProvider->getStereoCalibration();
424 float fx = calibration.calibrationRight.cameraParam.focalLength[0];
425 float fy = calibration.calibrationRight.cameraParam.focalLength[1];
426 float cx = calibration.calibrationRight.cameraParam.principalPoint[0];
427 float cy = calibration.calibrationRight.cameraParam.principalPoint[1];
433 cameraModel = CameraModel(fx, fy, cx, cy, Transform::getIdentity(), tx);
439 post(
new CameraEvent());
449 if (!waitForImages(1000))
451 ARMARX_WARNING <<
"Timeout or error while waiting for image data";
454 long lastStamp = imageMetaInfo ? imageMetaInfo->timeProvided : 0.0;
455 if (getImages(providerName, images, imageMetaInfo) != 2)
460 if (lastStamp == imageMetaInfo->timeProvided)
462 ARMARX_INFO <<
"Last timestamp as before - skipping image";
467 const cv::Mat tempRGBImage = cv::cvarrToMat(IplImageAdaptor::Adapt(images[0]));
469 cv::cvtColor(tempRGBImage, RGBImage, CV_RGB2BGR);
474 cv::Mat depthImage = cv::Mat(RGBImage.rows, RGBImage.cols, CV_16UC1);
476 for (
int j = 0; j < depthImage.rows; j++)
478 for (
int i = 0; i < depthImage.cols; i++)
480 unsigned short value = images[1]->pixels[3 * (j * images[1]->width + i) + 0] +
481 (images[1]->pixels[3 * (j * images[1]->width + i) + 1] << 8);
483 depthImage.at<
unsigned short>(j, i) =
value;
504 double time = imageMetaInfo->timeProvided / 1000.0;
505 SensorData sensorData(RGBImage, depthImage, cameraModel, ++imageId, time);
507 post(
new CameraEvent(sensorData, providerName));
510 visionx::MetaPointCloudFormatPtr
513 visionx::MetaPointCloudFormatPtr info =
new visionx::MetaPointCloudFormat();
514 info->size = 640 * 480 *
sizeof(visionx::ColoredPoint3D);
516 if (provideGlobalPointCloud)
518 info->capacity = info->size * 50;
522 info->capacity = info->size;
525 info->type = visionx::PointContentType::eColoredPoints;