RTABMapRegistration.cpp
Go to the documentation of this file.
1/*
2 * This file is part of ArmarX.
3 *
4 * Copyright (C) 2011-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5 *
6 * ArmarX is free software; you can redistribute it and/or modify
7 * it under the terms of the GNU General Public License version 2 as
8 * published by the Free Software Foundation.
9 *
10 * ArmarX is distributed in the hope that it will be useful, but
11 * WITHOUT ANY WARRANTY; without even the implied warranty of
12 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 * GNU General Public License for more details.
14 *
15 * You should have received a copy of the GNU General Public License
16 * along with this program. If not, see <http://www.gnu.org/licenses/>.
17 *
18 * @package VisionX::ArmarXObjects::RTABMapRegistration
19 * @author Markus Grotz ( markus dot grotz at kit dot edu )
20 * @date 2015
21 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22 * GNU General Public License
23 */
24
25#include "RTABMapRegistration.h"
26
27#include <VisionX/interface/components/PointCloudAndImageAndCalibrationProviderInterface.h>
28
29#include <rtabmap/core/Transform.h>
30#include <rtabmap/core/odometry/OdometryF2M.h>
31#include <rtabmap/core/util3d.h>
32
33using namespace armarx;
34using namespace rtabmap;
35
42
43void
45{
46 agentName = getProperty<std::string>("agentName").getValue();
47 provideGlobalPointCloud = getProperty<bool>("provideGlobalPointCloud").getValue();
48
49 usingProxy(getProperty<std::string>("RobotStateComponentName").getValue());
50 usingProxy(getProperty<std::string>("WorkingMemoryName").getValue());
51
52 passThroughFilter.setFilterFieldName("z");
53 passThroughFilter.setFilterLimits(getProperty<float>("MinDistance").getValue(),
54 getProperty<float>("MaxDistance").getValue());
55
56 updateTask =
57 new PeriodicTask<RTABMapRegistration>(this, &RTABMapRegistration::processData, 1000);
58
59 ParametersMap parameters;
60 // parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kRtabmapTimeThr(), "1000"));
61 parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kMemImageKept(), "true"));
62
63 ULogger::setType(ULogger::kTypeConsole);
64 //ULogger::setLevel(ULogger::kDebug);
65 ULogger::setLevel(ULogger::kWarning);
66
67 rtabmap = new Rtabmap();
68 rtabmap->init(parameters);
69 rtabmapThread = new RtabmapThread(rtabmap);
70
71 odomThread = new OdometryThread(new OdometryF2M());
72
73 odomThread->registerToEventsManager();
74 rtabmapThread->registerToEventsManager();
75
76 this->registerToEventsManager();
77
78 UEventsManager::createPipe(this, odomThread, "CameraEvent");
79}
80
81void
83{
84 this->unregisterFromEventsManager();
85
86 resultCondition.notify_one();
87 dataCondition.notify_one();
88
89 rtabmapThread->unregisterFromEventsManager();
90 odomThread->unregisterFromEventsManager();
91
92 odomThread->join(true);
93 rtabmapThread->join(true);
94
95 rtabmap->close();
96
97 delete odomThread;
98 delete rtabmapThread;
99 delete rtabmap;
100}
101
102void
104{
105 robotStateComponent = getProxy<RobotStateComponentInterfacePrx>(
106 getProperty<std::string>("RobotStateComponentName").getValue());
108 getProperty<std::string>("WorkingMemoryName").getValue());
109 agentInstancesSegment = workingMemory->getAgentInstancesSegment();
110
111 SharedRobotInterfacePrx synchronizedRobot = robotStateComponent->getSynchronizedRobot();
112
113 /*
114 Ice::CommunicatorPtr iceCommunicator = getIceManager()->getCommunicator();
115 agentInstance = new memoryx::AgentInstance(agentName);
116 agentInstance->setSharedRobot(synchronizedRobot);
117 agentInstance->setStringifiedSharedRobotInterfaceProxy(iceCommunicator->proxyToString(synchronizedRobot));
118 agentInstance->setAgentFilePath(robotStateComponent->getRobotFilename());
119 */
120
121 resultPointCloudPtr.reset(new pcl::PointCloud<pcl::PointXYZRGBA>);
122 hasNewResultPointCloud = false;
123 hasNewData = false;
124
125 FramedPoseBasePtr poseInGlobalFrame =
126 synchronizedRobot->getRobotNode(sourceFrameName)->getGlobalPose();
127 initialCameraPose = armarx::FramedPosePtr::dynamicCast(poseInGlobalFrame)->toEigen();
128
129 rtabmapThread->start();
130 odomThread->start();
131
132 updateTask->start();
133
134
135 while (captureEnabled && (!rtabmapThread->isRunning() || !odomThread->isRunning()))
136 {
137 ARMARX_WARNING << " waiting for RTABMap";
138 sleep(1);
139 }
140
141 // post(new OdometryResetEvent());
142
143
144 if (provideGlobalPointCloud)
145 {
146 requestGlobalPointCloud();
147 }
148}
149
150void
152{
153 updateTask->stop();
154
155 odomThread->kill();
156 rtabmapThread->kill();
157}
158
159void
160RTABMapRegistration::requestGlobalPointCloud()
161{
162 UEventsManager::post(new RtabmapEventCmd(RtabmapEventCmd::kCmdPublish3DMap, true, true, false));
163}
164
165bool
167{
168 boost::mutex::scoped_lock lock(resultPointCloudMutex);
169
170 while (captureEnabled && !hasNewResultPointCloud)
171 {
172 resultCondition.wait(lock);
173 }
174
175 if (!captureEnabled)
176 {
177 return false;
178 }
179
180 hasNewResultPointCloud = false;
181
182 if (resultPointCloudPtr->points.size())
183 {
184 providePointCloud(resultPointCloudPtr);
185
186 return true;
187 }
188 else
189 {
190 return false;
191 }
192}
193
194bool
196{
197 if (event->getClassName().compare("RtabmapEvent") == 0)
198 {
199 RtabmapEvent* rtabmapEvent = static_cast<RtabmapEvent*>(event);
200
201 boost::mutex::scoped_lock lock(RTABDataMutex);
202
203 /*
204 FramedPoseBasePtr poseInRootFrame = robotStateComponent->getSynchronizedRobot()->getRobotNode(sourceFrameName)->getPoseInRootFrame();
205 Eigen::Matrix4f cameraToRoot = armarx::FramedPosePtr::dynamicCast(poseInRootFrame)->toEigen();
206
207 Signature s = stats.getSignature();
208
209 Eigen::Matrix4f transform = s.getPose().toEigen4f() * s.getLocalTransform().toEigen4f();
210 transform.block<3, 1>(0, 3) = transform.block<3, 1>(0, 3) * Eigen::Scaling(1000.0f);
211 transform = initialCameraPose * transform;
212
213 Eigen::Matrix4f robotPose = transform * cameraToRoot.inverse();
214 updatePosition(robotPose);
215 */
216
217 if (!provideGlobalPointCloud)
218 {
219 signatures = rtabmapEvent->getStats().getSignatures();
220
221 hasNewData = true;
222 dataCondition.notify_one();
223 }
224 }
225 else if (event->getClassName().compare("OdometryEvent") == 0)
226 {
227 OdometryEvent* rtabmapEvent = static_cast<OdometryEvent*>(event);
228
229 if (rtabmapEvent->pose().isNull())
230 {
232 << "unable to register current view. odometry lost.";
233 }
234 }
235 else if (provideGlobalPointCloud && event->getClassName().compare("RtabmapEvent3DMap") == 0)
236 {
237 RtabmapEvent3DMap* rtabmapEvent = static_cast<RtabmapEvent3DMap*>(event);
238
239 boost::mutex::scoped_lock lock(RTABDataMutex);
240
241 signatures = rtabmapEvent->getSignatures();
242 poses = rtabmapEvent->getPoses();
243
244 hasNewData = true;
245 dataCondition.notify_one();
246 }
247
248 return false;
249}
250
251bool
252RTABMapRegistration::extractPointCloud(SensorData sensorData,
253 Eigen::Matrix4f transform,
254 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr& tempCloudPtr)
255{
256 std::vector<CameraModel> cameraModels = sensorData.cameraModels();
257
258 if (cameraModels.size() != 1)
259 {
260 return false;
261 }
262
263 CameraModel m = cameraModels[0];
264
265 transform.block<3, 1>(0, 3) = transform.block<3, 1>(0, 3) * Eigen::Scaling(1000.0f);
266 transform = initialCameraPose * transform;
267
268 int decimation = (provideGlobalPointCloud) ? 4 : 1;
269
270 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudPtr = util3d::cloudFromDepthRGB(
271 sensorData.imageRaw(), sensorData.depthOrRightRaw(), m, decimation);
272
273 pcl::copyPointCloud(*cloudPtr, *tempCloudPtr);
274 passThroughFilter.setInputCloud(tempCloudPtr);
275 passThroughFilter.filter(*tempCloudPtr);
276
277 Eigen::Affine3f convertUnitToMM = Eigen::Affine3f(Eigen::Scaling(1000.0f));
278 pcl::transformPointCloud(*tempCloudPtr, *tempCloudPtr, convertUnitToMM);
279
280 pcl::transformPointCloud(*tempCloudPtr, *tempCloudPtr, transform);
281
282 return true;
283}
284
285void
286RTABMapRegistration::processData()
287{
288 boost::mutex::scoped_lock lock(RTABDataMutex);
289
290 while (captureEnabled && !hasNewData)
291 {
292 dataCondition.wait(lock);
293 }
294
295 if (!captureEnabled)
296 {
297 return;
298 }
299
300 hasNewData = false;
301
302 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr nextCloudPtr(new pcl::PointCloud<pcl::PointXYZRGBA>());
303
304 for (auto& items : signatures)
305 {
306 const int id = items.first;
307 const Signature signature = items.second;
308
309 if (signature.isBadSignature())
310 {
311 continue;
312 }
313
314 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr tempCloudPtr(
315 new pcl::PointCloud<pcl::PointXYZRGBA>());
316
317 Eigen::Matrix4f transform;
318
319 if (signature.isEnabled())
320 {
321 transform = signature.getPose().toEigen4f();
322 }
323 else
324 {
325 if (poses.count(id))
326 {
327 transform = poses.at(id).toEigen4f();
328 }
329 else
330 {
331 continue;
332 }
333 }
334
335 extractPointCloud(signature.sensorData(), transform, tempCloudPtr);
336
337 *nextCloudPtr += *tempCloudPtr;
338
339 /*
340 IceUtil::Time currentTime = IceUtil::Time::now();
341 std::string fileName = "/tmp/cloud" + std::to_string(currentTime.toMilliSeconds()) + ".pcd";
342 pcl::io::savePCDFile(fileName, *temp);
343 */
344 }
345
346 if (provideGlobalPointCloud)
347 {
348 requestGlobalPointCloud();
349 }
350
351
352 boost::mutex::scoped_lock resultLock(resultPointCloudMutex);
353
354 // resultPointCloudPtr->header.seq = signatures.end()
355
356 pcl::copyPointCloud(*nextCloudPtr, *resultPointCloudPtr);
357
358 hasNewResultPointCloud = true;
359 resultCondition.notify_one();
360}
361
362void
363RTABMapRegistration::updatePosition(Eigen::Matrix4f pose)
364{
365 Eigen::Matrix3f orientation = pose.block<3, 3>(0, 0);
366 FramedOrientationPtr orientationPtr =
367 new FramedOrientation(orientation, GlobalFrame, agentName);
368 Eigen::Vector3f position = pose.block<3, 1>(0, 3);
369 FramedPositionPtr positionPtr = new FramedPosition(position, GlobalFrame, agentName);
370 agentInstance->setOrientation(orientationPtr);
371 agentInstance->setPosition(positionPtr);
372
373 if (agentInstanceId.empty() || !agentInstancesSegment->hasEntityById(agentInstanceId))
374 {
375 agentInstanceId = agentInstancesSegment->addEntity(agentInstance);
376 }
377 else
378 {
379 agentInstancesSegment->updateEntity(agentInstanceId, agentInstance);
380 }
381}
382
383void
385{
386 providerName = getProperty<std::string>("providerName").getValue();
387 usingImageProvider(providerName);
388}
389
390void
392{
393 visionx::ImageType imageDisplayType = visionx::tools::typeNameToImageType("rgb");
394
395 visionx::ImageProviderInfo imageProviderInfo = getImageProvider(providerName, imageDisplayType);
396
397 int numImages = imageProviderInfo.numberImages;
398
399 if (numImages != 2)
400 {
401 ARMARX_FATAL << "invalid number of images. aborting";
402 return;
403 }
404
405 images = new CByteImage*[numImages];
406
407 for (int i = 0; i < numImages; i++)
408 {
409 images[i] = visionx::tools::createByteImage(imageProviderInfo);
410 }
411
412 visionx::StereoCalibrationInterfacePrx calibrationProvider =
413 visionx::StereoCalibrationInterfacePrx::checkedCast(imageProviderInfo.proxy);
414 if (!calibrationProvider)
415 {
416 ARMARX_FATAL << "unable to retrieve calibration information. aborting.";
417 return;
418 }
419
420 sourceFrameName = calibrationProvider->getReferenceFrame();
421
422 visionx::StereoCalibration calibration = calibrationProvider->getStereoCalibration();
423
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];
428
429 // todo test if cameras are rectified
430 float tx = 0.075;
431 //float tx = calibration.calibrationRight.cameraParam.translation[0];
432
433 cameraModel = CameraModel(fx, fy, cx, cy, Transform::getIdentity(), tx);
434}
435
436void
438{
439 post(new CameraEvent());
440
441 delete images[0];
442 delete images[1];
443 delete[] images;
444}
445
446void
448{
449 if (!waitForImages(1000))
450 {
451 ARMARX_WARNING << "Timeout or error while waiting for image data";
452 return;
453 }
454 long lastStamp = imageMetaInfo ? imageMetaInfo->timeProvided : 0.0;
455 if (getImages(providerName, images, imageMetaInfo) != 2)
456 {
457 ARMARX_WARNING << "Unable to transfer or read images";
458 return;
459 }
460 if (lastStamp == imageMetaInfo->timeProvided)
461 {
462 ARMARX_INFO << "Last timestamp as before - skipping image";
463 return;
464 }
465
466 // rgb format is CV_8UC3
467 const cv::Mat tempRGBImage = cv::cvarrToMat(IplImageAdaptor::Adapt(images[0]));
468 cv::Mat RGBImage;
469 cv::cvtColor(tempRGBImage, RGBImage, CV_RGB2BGR);
470
471
472 // depth image format is CV_16U1 or CV_32FC1
473
474 cv::Mat depthImage = cv::Mat(RGBImage.rows, RGBImage.cols, CV_16UC1);
475
476 for (int j = 0; j < depthImage.rows; j++)
477 {
478 for (int i = 0; i < depthImage.cols; i++)
479 {
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);
482
483 depthImage.at<unsigned short>(j, i) = value;
484 }
485 }
486
487
488 /*
489 cv::Mat disparityImage = cv::Mat(RGBImage.rows, RGBImage.cols, CV_32FC1);
490 for (int j = 0; j < disparityImage.rows; j++)
491 {
492 for (int i = 0; i < disparityImage.cols; i++)
493 {
494 int value = images[1]->pixels[3 * (j * images[1]->width + i) + 0]
495 + (images[1]->pixels[3 * (j * images[1]->width + i) + 1] << 8);
496 + (images[1]->pixels[3 * (j * images[1]->width + i) + 2] << 16);
497
498 disparityImage.at<float>(j, i) = value;
499 }
500 }
501 const cv::Mat depthImage = util3d::depthFromDisparity(disparityImage, cameraModel.cx(), cameraModel.Tx(), CV_32FC1);
502 */
503
504 double time = imageMetaInfo->timeProvided / 1000.0;
505 SensorData sensorData(RGBImage, depthImage, cameraModel, ++imageId, time);
506
507 post(new CameraEvent(sensorData, providerName));
508}
509
510visionx::MetaPointCloudFormatPtr
512{
513 visionx::MetaPointCloudFormatPtr info = new visionx::MetaPointCloudFormat();
514 info->size = 640 * 480 * sizeof(visionx::ColoredPoint3D);
515
516 if (provideGlobalPointCloud)
517 {
518 info->capacity = info->size * 50;
519 }
520 else
521 {
522 info->capacity = info->size;
523 }
524
525 info->type = visionx::PointContentType::eColoredPoints;
526 return info;
527}
SpamFilterDataPtr deactivateSpam(SpamFilterDataPtr const &spamFilter, float deactivationDurationSec, const std::string &identifier, bool deactivate)
Definition Logging.cpp:75
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition Component.cpp:90
Property< PropertyType > getProperty(const std::string &name)
bool usingProxy(const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list.
Ice::ObjectPrx getProxy(long timeoutMs=0, bool waitForScheduler=true) const
Returns the proxy of this object (optionally it waits for the proxy)
The periodic task executes one thread method repeatedly using the time period specified in the constr...
void onConnectImageProcessor() override
Implement this method in the ImageProcessor in order execute parts when the component is fully initia...
bool doCapture() override
Main capturing function.
void onExitCapturingPointCloudProvider() override
This is called when the Component::onExitComponent() setup is called.
void onExitImageProcessor() override
Exit the ImapeProcessor component.
void onStartCapture(float framesPerSecond) override
This is called when the point cloud provider capturing has been started.
visionx::MetaPointCloudFormatPtr getDefaultPointCloudFormat() override
default point cloud format used to initialize shared memory
bool handleEvent(UEvent *event) override
void process() override
Process the vision component.
void onInitCapturingPointCloudProvider() override
This is called when the Component::onInitComponent() is called.
void onInitImageProcessor() override
Setup the vision component.
void onStopCapture() override
This is called when the point cloud provider capturing has been stopped.
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
std::atomic_bool captureEnabled
Indicates that capturing is enabled and running.
void usingImageProvider(std::string name)
Registers a delayed topic subscription and a delayed provider proxy retrieval which all will be avail...
bool waitForImages(int milliseconds=1000)
Wait for new images.
ImageProviderInfo getImageProvider(std::string name, ImageType destinationImageType=eRgb, bool waitForProxy=false)
Select an ImageProvider.
int getImages(CByteImage **ppImages)
Poll images from provider.
int numberImages
Number of images.
ImageProviderInterfacePrx proxy
proxy to image provider
void providePointCloud(PointCloudPtrT pointCloudPtr)
offer the new point cloud.
#define ARMARX_INFO
The normal logging level.
Definition Logging.h:181
#define ARMARX_FATAL
The logging level for unexpected behaviour, that will lead to a seriously malfunctioning program and ...
Definition Logging.h:199
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
Definition Logging.h:193
std::string const GlobalFrame
Variable of the global coordinate system.
Definition FramedPose.h:65
const VariantTypeId FramedPosition
Definition FramedPose.h:38
const VariantTypeId FramedOrientation
Definition FramedPose.h:39
This file offers overloads of toIce() and fromIce() functions for STL container types.
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT > >
Convenience function (with less typing) to transform a container of type InputT into the same contain...
Definition algorithm.h:351
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
IceInternal::Handle< FramedPosition > FramedPositionPtr
Definition FramedPose.h:149
::IceInternal::ProxyHandle<::IceProxy::armarx::SharedRobotInterface > SharedRobotInterfacePrx
Definition FramedPose.h:59
IceInternal::Handle< FramedOrientation > FramedOrientationPtr
Definition FramedPose.h:207
ImageType typeNameToImageType(const std::string &imageTypeName)
Converts an image type name as string into an ImageType integer.
CByteImage * createByteImage(const ImageFormatInfo &imageFormat, const ImageType imageType)
Creates a ByteImage for the destination type specified in the given imageProviderInfo.