28 #include <Eigen/Geometry>
30 #include <opencv2/opencv.hpp>
35 #include <RobotAPI/interface/core/RobotState.h>
41 #include <VisionX/interface/components/RTABMapInterface.h>
45 #include <Image/IplImageAdaptor.h>
47 #include <MemoryX/interface/components/WorkingMemoryInterface.h>
50 #pragma GCC diagnostic push
51 #pragma GCC diagnostic ignored "-Wpedantic"
52 #include <pcl/common/transforms.h>
53 #include <pcl/filters/filter.h>
54 #include <pcl/filters/passthrough.h>
55 #include <pcl/io/pcd_io.h>
57 #include <rtabmap/core/CameraEvent.h>
58 #include <rtabmap/core/Odometry.h>
59 #include <rtabmap/core/OdometryEvent.h>
60 #include <rtabmap/core/OdometryThread.h>
61 #include <rtabmap/core/Rtabmap.h>
62 #include <rtabmap/core/RtabmapThread.h>
63 #include <rtabmap/utilite/UEventsHandler.h>
64 #include <rtabmap/utilite/UEventsManager.h>
65 #include <rtabmap/utilite/ULogger.h>
67 #pragma GCC diagnostic pop
84 defineOptionalProperty<std::string>(
"agentName",
"RTABMap",
"");
85 defineOptionalProperty<std::string>(
"providerName",
"OpenNIPointCloudProvider",
"");
87 defineOptionalProperty<std::string>(
88 "RobotStateComponentName",
89 "RobotStateComponent",
90 "Name of the robot state component that should be used");
91 defineOptionalProperty<std::string>(
92 "WorkingMemoryName",
"WorkingMemory",
"Name of the working memory");
93 defineOptionalProperty<bool>(
94 "provideGlobalPointCloud",
96 "provide global point cloud if set. otherwise only the current view");
97 defineOptionalProperty<float>(
"MinDistance", 0.02,
"minimum z-axis distance in meters");
98 defineOptionalProperty<float>(
"MaxDistance", 5.00,
"maximum z-axis distance in meters");
112 virtual public visionx::RTABMapInterface,
115 virtual public UEventsHandler
124 return "RTABMapRegistration";
147 CapturingPointCloudProvider::onInitComponent();
148 ImageProcessor::onInitComponent();
154 ImageProcessor::onConnectComponent();
155 CapturingPointCloudProvider::onConnectComponent();
161 CapturingPointCloudProvider::onDisconnectComponent();
162 ImageProcessor::onDisconnectComponent();
168 CapturingPointCloudProvider::onExitComponent();
169 ImageProcessor::onExitComponent();
178 bool extractPointCloud(rtabmap::SensorData sensorData,
180 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr& tempCloudPtr);
184 std::string agentName;
185 std::string providerName;
186 std::string sourceFrameName;
187 bool provideGlobalPointCloud;
189 rtabmap::Rtabmap* rtabmap;
190 rtabmap::RtabmapThread* rtabmapThread;
191 rtabmap::OdometryThread* odomThread;
192 rtabmap::CameraModel cameraModel;
196 armarx::MetaInfoSizeBasePtr imageMetaInfo;
201 boost::mutex RTABDataMutex;
203 boost::condition dataCondition;
205 void requestGlobalPointCloud();
206 std::map<int, rtabmap::Signature> signatures;
207 std::map<int, rtabmap::Transform> poses;
209 boost::mutex resultPointCloudMutex;
210 boost::condition resultCondition;
211 bool hasNewResultPointCloud;
212 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr resultPointCloudPtr;
214 pcl::PassThrough<pcl::PointXYZRGBA> passThroughFilter;
217 memoryx::WorkingMemoryInterfacePrx workingMemory;
218 memoryx::AgentInstancesSegmentBasePrx agentInstancesSegment;
221 std::string agentInstanceId;