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
69namespace 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");
88 "RobotStateComponentName",
89 "RobotStateComponent",
90 "Name of the robot state component that should be used");
92 "WorkingMemoryName", "WorkingMemory", "Name of the working memory");
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
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
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,
179 Eigen::Matrix4f transform,
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
IceUtil::Handle< PeriodicTask< T > > pointer_type
Shared pointer type for convenience.
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
PropertyDefinition< PropertyType > & defineOptionalProperty(const std::string &name, PropertyType defaultValue, const std::string &description="", PropertyDefinitionBase::PropertyConstness constness=PropertyDefinitionBase::eConstant)
void onInitComponent() override
Pure virtual hook for the subclass.
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 onDisconnectComponent() override
Hook for subclass.
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 onConnectComponent() override
Pure virtual hook for the subclass.
void onStopCapture() override
This is called when the point cloud provider capturing has been stopped.
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
void onExitComponent() override
Hook for subclass.
std::string getDefaultName() const override
The CapturingPointCloudProvider provides a callback function to trigger the capturing of point clouds...
The ImageProcessor class provides an interface for access to ImageProviders via Ice and shared memory...
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::ProxyHandle<::IceProxy::armarx::RobotStateComponentInterface > RobotStateComponentInterfacePrx
IceInternal::Handle< AgentInstance > AgentInstancePtr
Typedef of AgentEntityPtr as IceInternal::Handle<AgentEntity> for convenience.
ArmarX headers.