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