MultiSensePointCloudProvider.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::MultiSensePointCloudProvider
19  * @author Markus Grotz ( markus dot grotz at kit dot edu )
20  * @date 2016
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 
25 #pragma once
26 
28 
31 
32 #include <VisionX/interface/components/PointCloudAndImageAndCalibrationProviderInterface.h>
33 
34 #include <pcl/point_types.h>
35 #include <pcl/io/pcd_io.h>
36 #include <pcl/common/transforms.h>
37 #include <pcl/filters/filter.h>
38 #include <pcl/filters/crop_box.h>
39 
40 #include <opencv2/opencv.hpp>
41 
42 #include <MultiSense/MultiSenseChannel.hh>
43 #include <MultiSense/MultiSenseTypes.hh>
44 
45 
46 #include <Image/IplImageAdaptor.h>
47 
48 #include <Eigen/Core>
49 
50 namespace armarx
51 {
52 
53  static Eigen::Vector4f stringToVector4f(std::string propertyValue)
54  {
55  Eigen::Vector4f vec;
56  sscanf(propertyValue.c_str(), "%f, %f, %f, %f", &vec.data()[0], &vec.data()[1], &vec.data()[2], &vec.data()[3]);
57  return vec;
58  }
59 
60 
61  /**
62  * @class MultiSensePointCloudProviderPropertyDefinitions
63  * @brief
64  */
67  {
68  public:
71  {
73 
74  defineOptionalProperty<Eigen::Vector4f>("minPoint", Eigen::Vector4f(-5000, -1e+06, -0, 1), "").setFactory(f);
75  defineOptionalProperty<Eigen::Vector4f>("maxPoint", Eigen::Vector4f(1000, 1e+08, 1e+08, 1), "").setFactory(f);
76  defineOptionalProperty<std::string>("ipAddress", "10.66.171.21", "Description");
77  defineOptionalProperty<bool>("enableLight", false, "Switch on the MultiSense LEDs on startup");
78  defineOptionalProperty<bool>("useLidar", false, "Use the laser for depth information");
79  defineOptionalProperty<std::string>("CalibrationFileName", "VisionX/examples/camera_multisense.txt", "Camera calibration file");
80  }
81  };
82 
83  /**
84  * @defgroup Component-MultiSensePointCloudProvider MultiSensePointCloudProvider
85  * @ingroup VisionX-Components
86  * A description of the component MultiSensePointCloudProvider.
87  *
88  * @class MultiSensePointCloudProvider
89  * @ingroup Component-MultiSensePointCloudProvider
90  * @brief Brief description of class MultiSensePointCloudProvider.
91  *
92  * Detailed description of class MultiSensePointCloudProvider.
93  */
95  virtual public visionx::CapturingPointCloudAndImageAndStereoCalibrationProviderInterface,
97  virtual public visionx::ImageProvider
98  {
99  public:
100  /**
101  * @see armarx::ManagedIceObject::getDefaultName()
102  */
103  std::string getDefaultName() const override
104  {
105  return "MultiSensePointCloudProvider";
106  }
107 
108 
109  void disparityImageCallback(const crl::multisense::image::Header& header);
110 
111  void lumaImageCallback(const crl::multisense::image::Header& header);
112 
113  void chromaImageCallback(const crl::multisense::image::Header& header);
114 
115  void lidarScanCallback(const crl::multisense::lidar::Header& header);
116 
117  protected:
118  /**
119  * @see visionx::PointCloudProviderBase::onInitPointCloudProvider()
120  */
121  void onInitCapturingPointCloudProvider() override;
122 
123  /**
124  * @see visionx::PointCloudProviderBase::onExitPointCloudProvider()
125  */
126  void onExitCapturingPointCloudProvider() override;
127 
128  /**
129  * @see visionx::PointCloudProviderBase::onStartCapture()
130  */
131  void onStartCapture(float frameRate) override;
132 
133  /**
134  * @see visionx::PointCloudProviderBase::onStopCapture()
135  */
136  void onStopCapture() override;
137 
138  /**
139  * @see visionx::PointCloudProviderBase::doCapture()
140  */
141  bool doCapture() override;
142 
143  visionx::MetaPointCloudFormatPtr getDefaultPointCloudFormat() override;
144 
145 
146  /**
147  * @see visionx::CapturingImageProvider::onInitImageProvider()
148  */
149  void onInitImageProvider() override;
150 
151  /**
152  * @see visionx::CapturingImageProvider::onExitImageProvider()
153  */
154  void onExitImageProvider() override { }
155 
156 
157  /**
158  * @see PropertyUser::createPropertyDefinitions()
159  */
161 
162  void onInitComponent() override
163  {
166  }
167 
168  void onConnectComponent() override
169  {
172  }
173 
174  void onDisconnectComponent() override
175  {
178  }
179 
180  void onExitComponent() override
181  {
184  }
185 
186  visionx::MonocularCalibration getMonocularCalibration(const ::Ice::Current& c = Ice::emptyCurrent) override;
187 
188  visionx::StereoCalibration getStereoCalibration(const Ice::Current& c = Ice::emptyCurrent) override;
189 
190  bool getImagesAreUndistorted(const ::Ice::Current& c = Ice::emptyCurrent) override
191  {
192  return false;
193  }
194 
195  bool hasSharedMemorySupport(const Ice::Current& c = Ice::emptyCurrent) override
196  {
197  return true;
198  }
199 
200 
201 
202 
203  private:
204 
205  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr pointCloudData;
206 
207  crl::multisense::Channel* driver;
208 
209  boost::mutex dataMutex;
210 
211  crl::multisense::DataSource mask;
212 
213  bool hasNewDisparityData;
214  bool hasNewColorData;
215 
216  std::vector<uint8_t> lumaData;
217  bool hasNewLumaData;
218 
219  cv::Mat_<double> q_matrix;
220 
221  cv::Mat rgbImage;
222  cv::Mat disparityImage;
223 
224  Eigen::Matrix4f cameraToSpindle;
225  Eigen::Matrix4f laserToSpindle;
226 
227  pcl::CropBox<pcl::PointXYZRGBA> cropBoxFilter;
228 
229 
230  visionx::StereoCalibration calibration;
231  CByteImage** rgbImages;
232 
233  };
234 }
235 
armarx::MultiSensePointCloudProvider::chromaImageCallback
void chromaImageCallback(const crl::multisense::image::Header &header)
Definition: MultiSensePointCloudProvider.cpp:404
CapturingPointCloudProvider.h
visionx::PointCloudProvider::onConnectComponent
void onConnectComponent() override
Definition: PointCloudProvider.cpp:77
armarx::MultiSensePointCloudProvider::lumaImageCallback
void lumaImageCallback(const crl::multisense::image::Header &header)
Definition: MultiSensePointCloudProvider.cpp:369
armarx::MultiSensePointCloudProvider::onExitComponent
void onExitComponent() override
Definition: MultiSensePointCloudProvider.h:180
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
armarx::MultiSensePointCloudProvider::onStopCapture
void onStopCapture() override
Definition: MultiSensePointCloudProvider.cpp:320
armarx::PropertyDefinitionContainer::prefix
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
Definition: PropertyDefinitionContainer.h:333
visionx::ImageProvider::onExitComponent
void onExitComponent() override
Definition: ImageProvider.cpp:152
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:43
armarx::MultiSensePointCloudProvider::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: MultiSensePointCloudProvider.cpp:619
armarx::MultiSensePointCloudProvider::getStereoCalibration
visionx::StereoCalibration getStereoCalibration(const Ice::Current &c=Ice::emptyCurrent) override
Definition: MultiSensePointCloudProvider.cpp:594
armarx::MultiSensePointCloudProvider::onExitImageProvider
void onExitImageProvider() override
Definition: MultiSensePointCloudProvider.h:154
visionx::PointCloudProvider::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: PointCloudProvider.cpp:95
visionx::PointCloudProvider::onExitComponent
void onExitComponent() override
Definition: PointCloudProvider.cpp:106
visionx::ImageProvider::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: ImageProvider.cpp:141
visionx::CapturingPointCloudProviderPropertyDefinitions::CapturingPointCloudProviderPropertyDefinitions
CapturingPointCloudProviderPropertyDefinitions(std::string prefix)
Definition: CapturingPointCloudProvider.h:42
armarx::MultiSensePointCloudProvider::hasSharedMemorySupport
bool hasSharedMemorySupport(const Ice::Current &c=Ice::emptyCurrent) override
Definition: MultiSensePointCloudProvider.h:195
armarx::MultiSensePointCloudProvider::lidarScanCallback
void lidarScanCallback(const crl::multisense::lidar::Header &header)
Definition: MultiSensePointCloudProvider.cpp:461
visionx::CapturingPointCloudProvider::frameRate
float frameRate
Required frame rate.
Definition: CapturingPointCloudProvider.h:214
ImageProcessor.h
armarx::MultiSensePointCloudProvider::onInitComponent
void onInitComponent() override
Definition: MultiSensePointCloudProvider.h:162
visionx::CapturingPointCloudProviderPropertyDefinitions
Definition: CapturingPointCloudProvider.h:38
armarx::MultiSensePointCloudProvider::onConnectComponent
void onConnectComponent() override
Definition: MultiSensePointCloudProvider.h:168
armarx::MultiSensePointCloudProvider::getDefaultName
std::string getDefaultName() const override
Definition: MultiSensePointCloudProvider.h:103
visionx::PointCloudProvider::onInitComponent
void onInitComponent() override
Definition: PointCloudProvider.cpp:59
armarx::MultiSensePointCloudProvider::getImagesAreUndistorted
bool getImagesAreUndistorted(const ::Ice::Current &c=Ice::emptyCurrent) override
Definition: MultiSensePointCloudProvider.h:190
armarx::MultiSensePointCloudProvider::onInitImageProvider
void onInitImageProvider() override
Definition: MultiSensePointCloudProvider.cpp:587
Component.h
visionx::CapturingPointCloudProvider
The CapturingPointCloudProvider provides a callback function to trigger the capturing of point clouds...
Definition: CapturingPointCloudProvider.h:56
armarx::MultiSensePointCloudProviderPropertyDefinitions
Definition: MultiSensePointCloudProvider.h:65
armarx::MultiSensePointCloudProviderPropertyDefinitions::MultiSensePointCloudProviderPropertyDefinitions
MultiSensePointCloudProviderPropertyDefinitions(std::string prefix)
Definition: MultiSensePointCloudProvider.h:69
visionx::ImageProvider
ImageProvider abstract class defines a component which provide images via ice or shared memory.
Definition: ImageProvider.h:66
armarx::MultiSensePointCloudProvider::onInitCapturingPointCloudProvider
void onInitCapturingPointCloudProvider() override
Definition: MultiSensePointCloudProvider.cpp:57
armarx::MultiSensePointCloudProvider::onExitCapturingPointCloudProvider
void onExitCapturingPointCloudProvider() override
Definition: MultiSensePointCloudProvider.cpp:233
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
visionx::ImageProvider::onConnectComponent
void onConnectComponent() override
Definition: ImageProvider.cpp:104
IceUtil::Handle< class PropertyDefinitionContainer >
visionx::ImageProvider::onInitComponent
void onInitComponent() override
Definition: ImageProvider.cpp:88
armarx::MultiSensePointCloudProvider::disparityImageCallback
void disparityImageCallback(const crl::multisense::image::Header &header)
Definition: MultiSensePointCloudProvider.cpp:529
armarx::MultiSensePointCloudProvider::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: MultiSensePointCloudProvider.h:174
armarx::MultiSensePointCloudProvider::onStartCapture
void onStartCapture(float frameRate) override
Definition: MultiSensePointCloudProvider.cpp:274
armarx::MultiSensePointCloudProvider
Brief description of class MultiSensePointCloudProvider.
Definition: MultiSensePointCloudProvider.h:94
armarx::MultiSensePointCloudProvider::doCapture
bool doCapture() override
Definition: MultiSensePointCloudProvider.cpp:331
armarx::PropertyDefinition::PropertyFactoryFunction
std::function< PropertyType(std::string)> PropertyFactoryFunction
Definition: PropertyDefinition.h:114
armarx::MultiSensePointCloudProvider::getMonocularCalibration
visionx::MonocularCalibration getMonocularCalibration(const ::Ice::Current &c=Ice::emptyCurrent) override
Definition: MultiSensePointCloudProvider.cpp:601
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
armarx::MultiSensePointCloudProvider::getDefaultPointCloudFormat
visionx::MetaPointCloudFormatPtr getDefaultPointCloudFormat() override
default point cloud format used to initialize shared memory
Definition: MultiSensePointCloudProvider.cpp:610