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 
27 
29 
32 #include <VisionX/interface/components/RGBDImageProvider.h>
34 
35 #include <Image/ImageProcessor.h>
36 #include <Calibration/Undistortion.h>
37 
38 #include <rc_genicam_api/device.h>
39 #include <rc_genicam_api/stream.h>
40 #include <rc_genicam_api/imagelist.h>
41 #include <memory>
42 
43 
44 namespace rcg
45 {
46 
47  using DevicePtr = std::shared_ptr<rcg::Device>;
48  using StreamPtr = std::shared_ptr<rcg::Stream> ;
49 }
50 
51 namespace visionx
52 {
53 
54 
55  /**
56  * @class RCPointCloudProviderPropertyDefinitions
57  * @brief
58  */
61  {
62  public:
64  };
65 
66  /**
67  * @defgroup Component-RCPointCloudProvider RCPointCloudProvider
68  * @ingroup VisionX-Components
69  * A description of the component RCPointCloudProvider.
70  *
71  * @class RCPointCloudProvider
72  * @ingroup Component-RCPointCloudProvider
73  * @brief Brief description of class RCPointCloudProvider.
74  *
75  * Detailed description of class RCPointCloudProvider.
76  */
78  virtual public RGBDPointCloudProviderInterface,
79  virtual public CapturingPointCloudProvider,
80  virtual public ImageProvider,
81  public RoboceptionUser,
83  {
84  public:
86 
87  /**
88  * @see armarx::ManagedIceObject::getDefaultName()
89  */
90  std::string getDefaultName() const override
91  {
92  return "RCPointCloudProvider";
93  }
94 
95  void onInitComponent() override;
96  void onConnectComponent() override;
97  void onDisconnectComponent() override;
98  void onExitComponent() override;
99 
100  protected:
101  void onInitCapturingPointCloudProvider() override;
102 
103  void onExitCapturingPointCloudProvider() override;
104 
105  void onStartCapture(float frameRate) override;
106 
107  void onStopCapture() override;
108 
109  bool doCapture() override;
110 
111  bool hasSharedMemorySupport(const Ice::Current& c = Ice::emptyCurrent) override
112  {
113  return true;
114  }
115 
116 
117  visionx::StereoCalibration getStereoCalibration(const Ice::Current& c = Ice::emptyCurrent) override
118  {
119  return stereoCalibration;
120  }
121 
122  bool getImagesAreUndistorted(const Ice::Current& c = Ice::emptyCurrent) override
123  {
124  return true;
125  }
126 
127  std::string getReferenceFrame(const Ice::Current& c = Ice::emptyCurrent) override
128  {
129  return getProperty<std::string>("ReferenceFrameName").getValue();
130  }
131 
132  /// @see PropertyUser::createPropertyDefinitions()
134 
135 
136  void startCaptureForNumFrames(Ice::Int, const Ice::Current&) override;
137 
138  // ImageProvider interface
139  protected:
140  void onInitImageProvider() override;
141  void onExitImageProvider() override;
142 
143  private:
144  armarx::RemoteGui::WidgetPtr buildGui();
145  void processGui(armarx::RemoteGui::TabProxy& prx);
146 
147  void updateFinalCloudTransform(
148  float sx, float sy, float sz,
149  float rx, float ry, float rz,
150  float tx, float ty, float tz);
151 
152  Eigen::Matrix4f getFinalCloudTransform();
153 
154  private:
155  double scan3dCoordinateScale = 1.0;
156 
157  rcg::ImageList intensityBuffer;
158  rcg::ImageList disparityBuffer;
159 
161  };
162 }
163 
rcg::StreamPtr
std::shared_ptr< rcg::Stream > StreamPtr
Definition: RCImageProvider.h:46
visionx::RCPointCloudProvider::doCapture
bool doCapture() override
Main capturing function.
Definition: RCPointCloudProvider.cpp:343
CapturingPointCloudProvider.h
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
visionx::RoboceptionUser
This class contains common implementation for RCImageProvider and RCPointCloudProvider.
Definition: RoboceptionUser.h:57
armarx::PropertyDefinitionContainer::prefix
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
Definition: PropertyDefinitionContainer.h:333
visionx::RCPointCloudProvider::onExitCapturingPointCloudProvider
void onExitCapturingPointCloudProvider() override
This is called when the Component::onExitComponent() setup is called.
Definition: RCPointCloudProvider.cpp:328
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:43
rcg
Definition: RCImageProvider.h:42
visionx::RCPointCloudProvider
Brief description of class RCPointCloudProvider.
Definition: RCPointCloudProvider.h:77
visionx::RCPointCloudProvider::onStartCapture
void onStartCapture(float frameRate) override
This is called when the point cloud provider capturing has been started.
Definition: RCPointCloudProvider.cpp:333
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:479
visionx::RCPointCloudProvider::onInitComponent
void onInitComponent() override
Pure virtual hook for the subclass.
Definition: RCPointCloudProvider.cpp:231
visionx::CapturingPointCloudProvider::frameRate
float frameRate
Required frame rate.
Definition: CapturingPointCloudProvider.h:214
visionx::RCPointCloudProvider::getImagesAreUndistorted
bool getImagesAreUndistorted(const Ice::Current &c=Ice::emptyCurrent) override
Definition: RCPointCloudProvider.h:122
ImageProcessor.h
visionx::RCPointCloudProvider::startCaptureForNumFrames
void startCaptureForNumFrames(Ice::Int, const Ice::Current &) override
Definition: RCPointCloudProvider.cpp:469
visionx::RCPointCloudProvider::onExitComponent
void onExitComponent() override
Hook for subclass.
Definition: RCPointCloudProvider.cpp:264
visionx::RCPointCloudProvider::onInitImageProvider
void onInitImageProvider() override
This is called when the Component::onInitComponent() is called.
Definition: RCPointCloudProvider.cpp:475
visionx::RoboceptionUser::stereoCalibration
visionx::StereoCalibration stereoCalibration
Definition: RoboceptionUser.h:99
rcg::DevicePtr
std::shared_ptr< rcg::Device > DevicePtr
Definition: RCImageProvider.h:45
visionx::RCPointCloudProvider::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: RCPointCloudProvider.cpp:461
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:127
armarx::RemoteGuiComponentPluginUser
Definition: RemoteGuiComponentPlugin.h:240
visionx::RCPointCloudProvider::onConnectComponent
void onConnectComponent() override
Pure virtual hook for the subclass.
Definition: RCPointCloudProvider.cpp:248
Component.h
visionx::CapturingPointCloudProvider
The CapturingPointCloudProvider provides a callback function to trigger the capturing of point clouds...
Definition: CapturingPointCloudProvider.h:56
armarx::WidgetDescription::WidgetPtr
::IceInternal::Handle<::armarx::WidgetDescription::Widget > WidgetPtr
Definition: NJointControllerBase.h:66
visionx::ImageProvider
ImageProvider abstract class defines a component which provide images via ice or shared memory.
Definition: ImageProvider.h:66
TripleBuffer.h
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
armarx::ComponentPropertyDefinitions
Default component property definition container.
Definition: Component.h:70
visionx::RCPointCloudProvider::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: RCPointCloudProvider.cpp:258
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:916
armarx::WriteBufferedTripleBuffer
Same as the TripleBuffer, but partial writes of the data structure are ok. The write operation may be...
Definition: TripleBuffer.h:267
visionx::RCPointCloudProvider::RCPointCloudProvider
RCPointCloudProvider()
Definition: RCPointCloudProvider.cpp:224
RoboceptionUser.h
visionx::RCPointCloudProvider::getDefaultName
std::string getDefaultName() const override
Definition: RCPointCloudProvider.h:90
visionx::RCPointCloudProviderPropertyDefinitions
Definition: RCPointCloudProvider.h:59
visionx::RCPointCloudProvider::onStopCapture
void onStopCapture() override
This is called when the point cloud provider capturing has been stopped.
Definition: RCPointCloudProvider.cpp:338
RemoteGuiComponentPlugin.h
visionx::RCPointCloudProviderPropertyDefinitions::RCPointCloudProviderPropertyDefinitions
RCPointCloudProviderPropertyDefinitions(std::string prefix)
Definition: RCPointCloudProvider.cpp:483
visionx::RCPointCloudProvider::onInitCapturingPointCloudProvider
void onInitCapturingPointCloudProvider() override
This is called when the Component::onInitComponent() is called.
Definition: RCPointCloudProvider.cpp:270