OpenNIPointCloudProvider.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::OpenNIPointCloudProvider
19 * @author David Schiebener (schiebener 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
30
33#include <VisionX/interface/components/RGBDImageProvider.h>
34//#include <VisionX/interface/components/Calibration.h>
35
36#include <condition_variable>
37#include <mutex>
38
39#include <Eigen/Geometry>
40
41#include <pcl/common/transforms.h>
42#include <pcl/io/openni2_grabber.h>
43#include <pcl/point_cloud.h>
44#include <pcl/point_types.h>
45
46#include <opencv2/opencv.hpp>
47
49
50#include <RobotAPI/interface/components/RobotHealthInterface.h>
52
53#include <Image/IplImageAdaptor.h>
54
55namespace visionx
56{
57
58 /**
59 * @class OpenNIPointCloudProviderPropertyDefinitions
60 * @brief
61 */
64 {
65 public:
68 {
69 defineOptionalProperty<Eigen::Vector2i>("dimensions", Eigen::Vector2i(640, 480), "")
70 .map("320x240", Eigen::Vector2i(320, 240))
71 .map("640x480", Eigen::Vector2i(640, 480))
72 .map("800x600", Eigen::Vector2i(800, 600))
73 .map("1280x1024", Eigen::Vector2i(1280, 1024))
74 .map("1600x1200", Eigen::Vector2i(1600, 1200));
75
76 defineOptionalProperty<std::string>("depthCameraCalibrationFile",
77 "VisionX/camera_calibration/asus_xtion_depth.yaml",
78 "");
80 "RGBCameraCalibrationFile", "VisionX/camera_calibration/asus_xtion_rgb.yaml", "");
81
82 defineOptionalProperty<bool>("EnableAutoExposure", true, "enable auto exposure.");
84 "EnableAutoWhiteBalance", true, "enable auto white balance.");
85
87 "ReferenceFrameName", "DepthCamera", "Optional reference frame name.");
89 "",
90 "Device id of the openni device, e.g. empty for "
91 "first device, or index in the format #n, e.g. 0");
93 "CaptureTimeOffset",
94 16.0f,
95 "In Milliseconds. Time offset between capturing the image on the hardware and "
96 "receiving the image in this process.",
99 "RobotHealthTopicName", "RobotHealthTopic", "Name of the RobotHealth topic");
100 defineOptionalProperty<std::string>("DebugObserverName",
101 "DebugObserver",
102 "Name of the topic the DebugObserver listens on");
103 }
104 };
105
106 /**
107 * @class OpenNIPointCloudProvider
108 * @ingroup VisionX-Components
109 * @brief A brief description
110 *
111 * Detailed Description
112 */
114 virtual public RGBDPointCloudProviderInterface,
115 virtual public CapturingPointCloudProvider,
116 virtual public ImageProvider
117 {
118 public:
120
121 /**
122 * @see armarx::ManagedIceObject::getDefaultName()
123 */
124 std::string
125 getDefaultName() const override
126 {
127 return "OpenNIPointCloudProvider";
128 }
129
130 std::vector<imrec::ChannelPreferences>
131 getImageRecordingChannelPreferences(const Ice::Current&) override;
132
133 protected:
134 /**
135 * @see visionx::PointCloudProviderBase::onInitPointCloudProvider()
136 */
137 void onInitCapturingPointCloudProvider() override;
138
139
140 void onConnectPointCloudProvider() override;
141
142 /**
143 * @see visionx::PointCloudProviderBase::onExitPointCloudProvider()
144 */
145 void onExitCapturingPointCloudProvider() override;
146
147 /**
148 * @see visionx::PointCloudProviderBase::onStartCapture()
149 */
150 void onStartCapture(float frameRate) override;
151
152 /**
153 * @see visionx::PointCloudProviderBase::onStopCapture()
154 */
155 void onStopCapture() override;
156
157 /**
158 * @see visionx::PointCloudProviderBase::doCapture()
159 */
160 bool doCapture() override;
161
162 /**
163 * @see visionx::CapturingImageProvider::onInitImageProvider()
164 */
165 void onInitImageProvider() override;
166
167 /**
168 * @see visionx::CapturingImageProvider::onExitImageProvider()
169 */
170 void
172 {
173 }
174
175 bool
176 hasSharedMemorySupport(const Ice::Current& c = Ice::emptyCurrent) override
177 {
178 return true;
179 }
180
181 /**
182 * @see PropertyUser::createPropertyDefinitions()
183 */
185
186 // mixed inherited stuff
187 void onInitComponent() override;
188 void onConnectComponent() override;
189 void onDisconnectComponent() override;
190 void onExitComponent() override;
191
192
193 StereoCalibration getStereoCalibration(const Ice::Current& c = Ice::emptyCurrent) override;
194
195 bool
196 getImagesAreUndistorted(const ::Ice::Current& c = Ice::emptyCurrent) override
197 {
198 return false;
199 }
200
201 std::string
202 getReferenceFrame(const Ice::Current& c = Ice::emptyCurrent) override
203 {
204 return getProperty<std::string>("ReferenceFrameName");
205 }
206
207 private:
208 void callbackFunctionForOpenNIGrabberPointCloudWithRGB(
209 const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr& newCloud);
210 void callbackFunctionForOpenNIGrabberPointCloud(
211 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr& newCloud);
212 void callbackFunctionForOpenNIGrabberImage(const pcl::io::Image::Ptr& newImage);
213 void grabImages(const pcl::io::Image::Ptr& RGBImage,
214 const pcl::io::DepthImage::Ptr& depthImage,
215 float reciprocalFocalLength);
216 void grabDepthImage(const pcl::io::IRImage::Ptr& RGBImage,
217 const pcl::io::DepthImage::Ptr& depthImage,
218 float x);
219
220
221 bool loadCalibrationFile(std::string fileName, visionx::CameraParameters& calibration);
222
223 ImageProviderInterfacePrx imageProviderPrx;
224 std::string providerName;
225 CByteImage** rgbImages;
226 int width, height;
227 mutable std::mutex syncMutex;
228
229 pcl::io::OpenNI2Grabber::Ptr grabberInterface;
230 std::condition_variable condition;
231 bool newPointCloudCapturingRequested, newImageCapturingRequested;
232 long timeOfLastImageCapture, timeOfLastPointCloudCapture;
233 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr pointcloudBuffer;
234 StereoCalibration calibration;
235 long captureTimeOffset;
236
237 armarx::RobotHealthInterfacePrx robotHealthTopic;
239 IceUtil::Time lastReportTimestamp;
240
241 armarx::plugins::HeartbeatComponentPlugin* heartbeatPlugin = nullptr;
242 };
243} // namespace visionx
constexpr T c
Property< PropertyType > getProperty(const std::string &name)
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)
The CapturingPointCloudProvider provides a callback function to trigger the capturing of point clouds...
ImageProvider abstract class defines a component which provide images via ice or shared memory.
std::string getReferenceFrame(const Ice::Current &c=Ice::emptyCurrent) override
bool hasSharedMemorySupport(const Ice::Current &c=Ice::emptyCurrent) override
void onInitComponent() override
Pure virtual hook for the subclass.
void onDisconnectComponent() override
Hook for subclass.
void onStartCapture(float frameRate) override
void onConnectComponent() override
Pure virtual hook for the subclass.
StereoCalibration getStereoCalibration(const Ice::Current &c=Ice::emptyCurrent) override
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
std::vector< imrec::ChannelPreferences > getImageRecordingChannelPreferences(const Ice::Current &) override
void onExitComponent() override
Hook for subclass.
std::string getDefaultName() const override
bool getImagesAreUndistorted(const ::Ice::Current &c=Ice::emptyCurrent) override
This file offers overloads of toIce() and fromIce() functions for STL container types.
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface > DebugObserverInterfacePrx
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
ArmarX headers.