34 #include <RobotAPI/interface/core/RobotState.h>
38 #include <MemoryX/interface/components/WorkingMemoryInterface.h>
41 #include <VisionX/interface/components/RTABMapInterface.h>
47 #include <Eigen/Geometry>
50 #include <opencv2/opencv.hpp>
51 #include <Image/IplImageAdaptor.h>
53 #pragma GCC diagnostic push
54 #pragma GCC diagnostic ignored "-Wpedantic"
55 #include <pcl/io/pcd_io.h>
56 #include <pcl/common/transforms.h>
57 #include <pcl/filters/filter.h>
58 #include <pcl/filters/passthrough.h>
60 #include <rtabmap/core/Rtabmap.h>
61 #include <rtabmap/core/RtabmapThread.h>
63 #include <rtabmap/core/CameraEvent.h>
64 #include <rtabmap/core/Odometry.h>
66 #include <rtabmap/core/OdometryThread.h>
67 #include <rtabmap/core/OdometryEvent.h>
70 #include <rtabmap/utilite/UEventsManager.h>
71 #include <rtabmap/utilite/UEventsHandler.h>
72 #include <rtabmap/utilite/ULogger.h>
74 #pragma GCC diagnostic pop
91 defineOptionalProperty<std::string>(
"agentName",
"RTABMap",
"");
92 defineOptionalProperty<std::string>(
"providerName",
"OpenNIPointCloudProvider",
"");
94 defineOptionalProperty<std::string>(
"RobotStateComponentName",
"RobotStateComponent",
"Name of the robot state component that should be used");
95 defineOptionalProperty<std::string>(
"WorkingMemoryName",
"WorkingMemory",
"Name of the working memory");
96 defineOptionalProperty<bool>(
"provideGlobalPointCloud",
false,
"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
123 return "RTABMapRegistration";
145 CapturingPointCloudProvider::onInitComponent();
146 ImageProcessor::onInitComponent();
151 ImageProcessor::onConnectComponent();
152 CapturingPointCloudProvider::onConnectComponent();
157 CapturingPointCloudProvider::onDisconnectComponent();
158 ImageProcessor::onDisconnectComponent();
163 CapturingPointCloudProvider::onExitComponent();
164 ImageProcessor::onExitComponent();
174 bool extractPointCloud(rtabmap::SensorData sensorData,
Eigen::Matrix4f transform, pcl::PointCloud<pcl::PointXYZRGBA>::Ptr& tempCloudPtr);
178 std::string agentName;
179 std::string providerName;
180 std::string sourceFrameName;
181 bool provideGlobalPointCloud;
183 rtabmap::Rtabmap* rtabmap;
184 rtabmap::RtabmapThread* rtabmapThread;
185 rtabmap::OdometryThread* odomThread;
186 rtabmap::CameraModel cameraModel;
190 armarx::MetaInfoSizeBasePtr imageMetaInfo;
195 boost::mutex RTABDataMutex;
197 boost::condition dataCondition;
199 void requestGlobalPointCloud();
200 std::map<int, rtabmap::Signature> signatures;
201 std::map<int, rtabmap::Transform> poses;
203 boost::mutex resultPointCloudMutex;
204 boost::condition resultCondition;
205 bool hasNewResultPointCloud;
206 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr resultPointCloudPtr;
208 pcl::PassThrough<pcl::PointXYZRGBA> passThroughFilter;
211 memoryx::WorkingMemoryInterfacePrx workingMemory;
212 memoryx::AgentInstancesSegmentBasePrx agentInstancesSegment;
215 std::string agentInstanceId;