RTABMapRegistration.h
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 #pragma once
26 
27 
28 #include <Eigen/Geometry>
29 
30 #include <opencv2/opencv.hpp>
31 
34 
35 #include <RobotAPI/interface/core/RobotState.h>
38 
41 #include <VisionX/interface/components/RTABMapInterface.h>
44 
45 #include <Image/IplImageAdaptor.h>
47 #include <MemoryX/interface/components/WorkingMemoryInterface.h>
49 
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>
56 
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>
66 
67 #pragma GCC diagnostic pop
68 
69 namespace armarx
70 {
71  /**
72  * @class RTABMapRegistrationPropertyDefinitions
73  * @brief
74  */
77  {
78  public:
81  {
82  // defineRequiredProperty<std::string>("agentName", "name of the agent for which the sensor values are provided");
83 
84  defineOptionalProperty<std::string>("agentName", "RTABMap", "");
85  defineOptionalProperty<std::string>("providerName", "OpenNIPointCloudProvider", "");
86  //defineOptionalProperty<std::string>("sourceFrameName", "DepthCamera", "the robot node to use as source coordinate system for the captured point clouds");
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",
95  false,
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");
99  }
100  };
101 
102  /**
103  * @class RTABMapRegistration
104  *
105  * @ingroup VisionX-Components
106  * @brief A brief description
107  *
108  *
109  * Detailed Description
110  */
112  virtual public visionx::RTABMapInterface,
114  virtual public visionx::ImageProcessor,
115  virtual public UEventsHandler
116  {
117  public:
118  /**
119  * @see armarx::ManagedIceObject::getDefaultName()
120  */
121  std::string
122  getDefaultName() const override
123  {
124  return "RTABMapRegistration";
125  }
126 
127  protected:
128  /**
129  * @see PropertyUser::createPropertyDefinitions()
130  */
132 
133  void onInitCapturingPointCloudProvider() override;
134  void onExitCapturingPointCloudProvider() override;
135  void onStartCapture(float framesPerSecond) override;
136  void onStopCapture() override;
137  bool doCapture() override;
138 
139  void onInitImageProcessor() override;
140  void onConnectImageProcessor() override;
141  void onExitImageProcessor() override;
142  void process() override;
143 
144  void
145  onInitComponent() override
146  {
147  CapturingPointCloudProvider::onInitComponent();
148  ImageProcessor::onInitComponent();
149  }
150 
151  void
153  {
154  ImageProcessor::onConnectComponent();
155  CapturingPointCloudProvider::onConnectComponent();
156  }
157 
158  void
160  {
161  CapturingPointCloudProvider::onDisconnectComponent();
162  ImageProcessor::onDisconnectComponent();
163  }
164 
165  void
166  onExitComponent() override
167  {
168  CapturingPointCloudProvider::onExitComponent();
169  ImageProcessor::onExitComponent();
170  }
171 
172  bool handleEvent(UEvent* event) override;
173 
174  visionx::MetaPointCloudFormatPtr getDefaultPointCloudFormat() override;
175 
176 
177  private:
178  bool extractPointCloud(rtabmap::SensorData sensorData,
180  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr& tempCloudPtr);
181  void updatePosition(Eigen::Matrix4f pose);
182  void processData();
183 
184  std::string agentName;
185  std::string providerName;
186  std::string sourceFrameName;
187  bool provideGlobalPointCloud;
188 
189  rtabmap::Rtabmap* rtabmap;
190  rtabmap::RtabmapThread* rtabmapThread;
191  rtabmap::OdometryThread* odomThread;
192  rtabmap::CameraModel cameraModel;
193 
194 
195  CByteImage** images;
196  armarx::MetaInfoSizeBasePtr imageMetaInfo;
197  int imageId;
198 
199  Eigen::Matrix4f initialCameraPose;
200 
201  boost::mutex RTABDataMutex;
202  bool hasNewData;
203  boost::condition dataCondition;
204 
205  void requestGlobalPointCloud();
206  std::map<int, rtabmap::Signature> signatures;
207  std::map<int, rtabmap::Transform> poses;
208 
209  boost::mutex resultPointCloudMutex;
210  boost::condition resultCondition;
211  bool hasNewResultPointCloud;
212  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr resultPointCloudPtr;
213 
214  pcl::PassThrough<pcl::PointXYZRGBA> passThroughFilter;
215 
216  armarx::RobotStateComponentInterfacePrx robotStateComponent;
217  memoryx::WorkingMemoryInterfacePrx workingMemory;
218  memoryx::AgentInstancesSegmentBasePrx agentInstancesSegment;
219 
220  memoryx::AgentInstancePtr agentInstance;
221  std::string agentInstanceId;
222 
224  };
225 } // namespace armarx
CapturingPointCloudProvider.h
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
armarx::RTABMapRegistration::getDefaultPointCloudFormat
visionx::MetaPointCloudFormatPtr getDefaultPointCloudFormat() override
default point cloud format used to initialize shared memory
Definition: RTABMapRegistration.cpp:511
visionx::ImageProcessor
The ImageProcessor class provides an interface for access to ImageProviders via Ice and shared memory...
Definition: ImageProcessor.h:98
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:650
Pose.h
armarx::RTABMapRegistration::doCapture
bool doCapture() override
Main capturing function.
Definition: RTABMapRegistration.cpp:166
armarx::RTABMapRegistrationPropertyDefinitions
Definition: RTABMapRegistration.h:75
armarx::PropertyDefinitionContainer::prefix
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
Definition: PropertyDefinitionContainer.h:345
PeriodicTask.h
armarx::RTABMapRegistration::onExitImageProcessor
void onExitImageProcessor() override
Exit the ImapeProcessor component.
Definition: RTABMapRegistration.cpp:437
armarx::RTABMapRegistration::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: RTABMapRegistration.cpp:37
armarx::RTABMapRegistration
A brief description.
Definition: RTABMapRegistration.h:111
IceInternal::Handle< AgentInstance >
visionx::CapturingPointCloudProviderPropertyDefinitions::CapturingPointCloudProviderPropertyDefinitions
CapturingPointCloudProviderPropertyDefinitions(std::string prefix)
Definition: CapturingPointCloudProvider.h:43
armarx::RTABMapRegistration::onConnectImageProcessor
void onConnectImageProcessor() override
Implement this method in the ImageProcessor in order execute parts when the component is fully initia...
Definition: RTABMapRegistration.cpp:391
ImageProcessor.h
FramedPose.h
visionx::CapturingPointCloudProviderPropertyDefinitions
Definition: CapturingPointCloudProvider.h:39
armarx::RTABMapRegistrationPropertyDefinitions::RTABMapRegistrationPropertyDefinitions
RTABMapRegistrationPropertyDefinitions(std::string prefix)
Definition: RTABMapRegistration.h:79
armarx::RTABMapRegistration::onExitComponent
void onExitComponent() override
Definition: RTABMapRegistration.h:166
armarx::RTABMapRegistration::handleEvent
bool handleEvent(UEvent *event) override
Definition: RTABMapRegistration.cpp:195
armarx::RTABMapRegistration::onInitCapturingPointCloudProvider
void onInitCapturingPointCloudProvider() override
This is called when the Component::onInitComponent() is called.
Definition: RTABMapRegistration.cpp:44
armarx::RTABMapRegistration::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: RTABMapRegistration.h:159
Component.h
visionx::CapturingPointCloudProvider
The CapturingPointCloudProvider provides a callback function to trigger the capturing of point clouds...
Definition: CapturingPointCloudProvider.h:58
armarx::transform
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
armarx::RTABMapRegistration::onStopCapture
void onStopCapture() override
This is called when the point cloud provider capturing has been stopped.
Definition: RTABMapRegistration.cpp:151
armarx::RTABMapRegistration::process
void process() override
Process the vision component.
Definition: RTABMapRegistration.cpp:447
Entity.h
IceUtil::Handle< class PropertyDefinitionContainer >
armarx::RTABMapRegistration::onInitComponent
void onInitComponent() override
Definition: RTABMapRegistration.h:145
IceInternal::ProxyHandle<::IceProxy::armarx::RobotStateComponentInterface >
armarx::RTABMapRegistration::getDefaultName
std::string getDefaultName() const override
Definition: RTABMapRegistration.h:122
ImageUtil.h
AgentInstance.h
armarx::RTABMapRegistration::onStartCapture
void onStartCapture(float framesPerSecond) override
This is called when the point cloud provider capturing has been started.
Definition: RTABMapRegistration.cpp:103
TypeMapping.h
armarx::RTABMapRegistration::onConnectComponent
void onConnectComponent() override
Definition: RTABMapRegistration.h:152
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:27
armarx::RTABMapRegistration::onExitCapturingPointCloudProvider
void onExitCapturingPointCloudProvider() override
This is called when the Component::onExitComponent() setup is called.
Definition: RTABMapRegistration.cpp:82
armarx::RTABMapRegistration::onInitImageProcessor
void onInitImageProcessor() override
Setup the vision component.
Definition: RTABMapRegistration.cpp:384