RCPointCloudProvider.h
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * @package VisionX::ArmarXObjects::RCPointCloudProvider
17  * @author Fabian Paus ( paus at kit dot edu )
18  * @date 2018
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
23 #pragma once
24 
25 #include <memory>
26 
29 
31 
34 #include <VisionX/interface/components/RGBDImageProvider.h>
36 
37 #include <Calibration/Undistortion.h>
38 #include <Image/ImageProcessor.h>
39 #include <rc_genicam_api/device.h>
40 #include <rc_genicam_api/imagelist.h>
41 #include <rc_genicam_api/stream.h>
42 
43 namespace rcg
44 {
45 
46  using DevicePtr = std::shared_ptr<rcg::Device>;
47  using StreamPtr = std::shared_ptr<rcg::Stream>;
48 } // namespace rcg
49 
50 namespace visionx
51 {
52 
53 
54  /**
55  * @class RCPointCloudProviderPropertyDefinitions
56  * @brief
57  */
59  {
60  public:
62  };
63 
64  /**
65  * @defgroup Component-RCPointCloudProvider RCPointCloudProvider
66  * @ingroup VisionX-Components
67  * A description of the component RCPointCloudProvider.
68  *
69  * @class RCPointCloudProvider
70  * @ingroup Component-RCPointCloudProvider
71  * @brief Brief description of class RCPointCloudProvider.
72  *
73  * Detailed description of class RCPointCloudProvider.
74  */
76  virtual public RGBDPointCloudProviderInterface,
77  virtual public CapturingPointCloudProvider,
78  virtual public ImageProvider,
79  public RoboceptionUser,
81  {
82  public:
84 
85  /**
86  * @see armarx::ManagedIceObject::getDefaultName()
87  */
88  std::string
89  getDefaultName() const override
90  {
91  return "RCPointCloudProvider";
92  }
93 
94  void onInitComponent() override;
95  void onConnectComponent() override;
96  void onDisconnectComponent() override;
97  void onExitComponent() override;
98 
99  protected:
100  void onInitCapturingPointCloudProvider() override;
101 
102  void onExitCapturingPointCloudProvider() override;
103 
104  void onStartCapture(float frameRate) override;
105 
106  void onStopCapture() override;
107 
108  bool doCapture() override;
109 
110  bool
111  hasSharedMemorySupport(const Ice::Current& c = Ice::emptyCurrent) override
112  {
113  return true;
114  }
115 
116  visionx::StereoCalibration
117  getStereoCalibration(const Ice::Current& c = Ice::emptyCurrent) override
118  {
119  return stereoCalibration;
120  }
121 
122  bool
123  getImagesAreUndistorted(const Ice::Current& c = Ice::emptyCurrent) override
124  {
125  return true;
126  }
127 
128  std::string
129  getReferenceFrame(const Ice::Current& c = Ice::emptyCurrent) override
130  {
131  return getProperty<std::string>("ReferenceFrameName").getValue();
132  }
133 
134  /// @see PropertyUser::createPropertyDefinitions()
136 
137 
138  void startCaptureForNumFrames(Ice::Int, const Ice::Current&) override;
139 
140  // ImageProvider interface
141  protected:
142  void onInitImageProvider() override;
143  void onExitImageProvider() override;
144 
145  private:
146  armarx::RemoteGui::WidgetPtr buildGui();
147  void processGui(armarx::RemoteGui::TabProxy& prx);
148 
149  void updateFinalCloudTransform(float sx,
150  float sy,
151  float sz,
152  float rx,
153  float ry,
154  float rz,
155  float tx,
156  float ty,
157  float tz);
158 
159  Eigen::Matrix4f getFinalCloudTransform();
160 
161  private:
162  double scan3dCoordinateScale = 1.0;
163 
164  rcg::ImageList intensityBuffer;
165  rcg::ImageList disparityBuffer;
166 
168  };
169 } // namespace visionx
rcg::StreamPtr
std::shared_ptr< rcg::Stream > StreamPtr
Definition: RCImageProvider.h:46
visionx::RCPointCloudProvider::doCapture
bool doCapture() override
Main capturing function.
Definition: RCPointCloudProvider.cpp:358
CapturingPointCloudProvider.h
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:650
visionx::RoboceptionUser
This class contains common implementation for RCImageProvider and RCPointCloudProvider.
Definition: RoboceptionUser.h:55
armarx::PropertyDefinitionContainer::prefix
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
Definition: PropertyDefinitionContainer.h:345
visionx::RCPointCloudProvider::onExitCapturingPointCloudProvider
void onExitCapturingPointCloudProvider() override
This is called when the Component::onExitComponent() setup is called.
Definition: RCPointCloudProvider.cpp:340
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:46
rcg
Definition: RCImageProvider.h:42
visionx::RCPointCloudProvider
Brief description of class RCPointCloudProvider.
Definition: RCPointCloudProvider.h:75
visionx::RCPointCloudProvider::onStartCapture
void onStartCapture(float frameRate) override
This is called when the point cloud provider capturing has been started.
Definition: RCPointCloudProvider.cpp:346
armarx::RemoteGui::TabProxy
Definition: WidgetProxy.h:17
visionx::RCPointCloudProvider::onExitImageProvider
void onExitImageProvider() override
This is called when the Component::onExitComponent() setup is called.
Definition: RCPointCloudProvider.cpp:499
visionx::RCPointCloudProvider::onInitComponent
void onInitComponent() override
Pure virtual hook for the subclass.
Definition: RCPointCloudProvider.cpp:240
visionx::CapturingPointCloudProvider::frameRate
float frameRate
Required frame rate.
Definition: CapturingPointCloudProvider.h:220
visionx::RCPointCloudProvider::getImagesAreUndistorted
bool getImagesAreUndistorted(const Ice::Current &c=Ice::emptyCurrent) override
Definition: RCPointCloudProvider.h:123
ImageProcessor.h
visionx::RCPointCloudProvider::startCaptureForNumFrames
void startCaptureForNumFrames(Ice::Int, const Ice::Current &) override
Definition: RCPointCloudProvider.cpp:488
visionx::RCPointCloudProvider::onExitComponent
void onExitComponent() override
Hook for subclass.
Definition: RCPointCloudProvider.cpp:273
visionx::RCPointCloudProvider::onInitImageProvider
void onInitImageProvider() override
This is called when the Component::onInitComponent() is called.
Definition: RCPointCloudProvider.cpp:494
visionx::RoboceptionUser::stereoCalibration
visionx::StereoCalibration stereoCalibration
Definition: RoboceptionUser.h:107
rcg::DevicePtr
std::shared_ptr< rcg::Device > DevicePtr
Definition: RCImageProvider.h:45
visionx::RCPointCloudProvider::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: RCPointCloudProvider.cpp:481
visionx::RCPointCloudProvider::hasSharedMemorySupport
bool hasSharedMemorySupport(const Ice::Current &c=Ice::emptyCurrent) override
Definition: RCPointCloudProvider.h:111
visionx::RCPointCloudProvider::getReferenceFrame
std::string getReferenceFrame(const Ice::Current &c=Ice::emptyCurrent) override
Definition: RCPointCloudProvider.h:129
armarx::RemoteGuiComponentPluginUser
Definition: RemoteGuiComponentPlugin.h:221
visionx::RCPointCloudProvider::onConnectComponent
void onConnectComponent() override
Pure virtual hook for the subclass.
Definition: RCPointCloudProvider.cpp:257
Component.h
visionx::CapturingPointCloudProvider
The CapturingPointCloudProvider provides a callback function to trigger the capturing of point clouds...
Definition: CapturingPointCloudProvider.h:58
armarx::WidgetDescription::WidgetPtr
::IceInternal::Handle<::armarx::WidgetDescription::Widget > WidgetPtr
Definition: NJointControllerBase.h:67
visionx::ImageProvider
ImageProvider abstract class defines a component which provide images via ice or shared memory.
Definition: ImageProvider.h:66
TripleBuffer.h
armarx::ComponentPropertyDefinitions
Default component property definition container.
Definition: Component.h:69
visionx::RCPointCloudProvider::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: RCPointCloudProvider.cpp:266
IceUtil::Handle< class PropertyDefinitionContainer >
visionx::RCPointCloudProvider::getStereoCalibration
visionx::StereoCalibration getStereoCalibration(const Ice::Current &c=Ice::emptyCurrent) override
Definition: RCPointCloudProvider.h:117
armarx::VariantType::Int
const VariantTypeId Int
Definition: Variant.h:917
armarx::WriteBufferedTripleBuffer
Same as the TripleBuffer, but partial writes of the data structure are ok. The write operation may be...
Definition: TripleBuffer.h:312
visionx::RCPointCloudProvider::RCPointCloudProvider
RCPointCloudProvider()
Definition: RCPointCloudProvider.cpp:235
RoboceptionUser.h
visionx::RCPointCloudProvider::getDefaultName
std::string getDefaultName() const override
Definition: RCPointCloudProvider.h:89
visionx::RCPointCloudProviderPropertyDefinitions
Definition: RCPointCloudProvider.h:58
visionx::RCPointCloudProvider::onStopCapture
void onStopCapture() override
This is called when the point cloud provider capturing has been stopped.
Definition: RCPointCloudProvider.cpp:352
RemoteGuiComponentPlugin.h
visionx::RCPointCloudProviderPropertyDefinitions::RCPointCloudProviderPropertyDefinitions
RCPointCloudProviderPropertyDefinitions(std::string prefix)
Definition: RCPointCloudProvider.cpp:503
visionx::RCPointCloudProvider::onInitCapturingPointCloudProvider
void onInitCapturingPointCloudProvider() override
This is called when the Component::onInitComponent() is called.
Definition: RCPointCloudProvider.cpp:280