AzureKinectPointCloudProvider.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::AzureKinectPointCloudProvider
17  * @author Mirko Wächter
18  * @author Christian R. G. Dreher <c.dreher@kit.edu>
19  * @date 2019
20  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
21  * GNU General Public License
22  */
23 
24 
25 #pragma once
26 
27 // STD
28 #include <chrono>
29 #include <condition_variable>
30 #include <mutex>
31 
32 // Eigen3
33 #include <Eigen/Core>
34 
35 // OpenCV
36 #include <opencv2/opencv.hpp>
37 
38 // ArmarXCore
43 #include <ArmarXCore/interface/observers/ObserverInterface.h>
45 
46 // RobotAPI
48 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
49 
50 // VisionX
54 //#include <VisionX/interface/components/RGBDImageProvider.h>
55 #include <VisionX/interface/components/AzureKinectPointCloudProviderInterface.h>
56 #include <VisionX/libraries/armem_human/server/HumanMemoryServerInterface.h>
57 
58 // K4A
59 #include <k4a/k4a.h>
60 #include <k4a/k4a.hpp>
61 
62 #ifdef INCLUDE_BODY_TRACKING
64 
66 
67 #include <k4abt.hpp>
68 #endif
69 
70 namespace visionx
71 {
72  /// @class AzureKinectPointCloudProviderPropertyDefinitions
75  {
76  public:
78  };
79 
80 
81  // TODO: Update the comments for this component.
82  /**
83  * @defgroup Component-AzureKinectPointCloudProvider AzureKinectPointCloudProvider
84  * @ingroup VisionX-Components
85  * Provides support for the Azure Kinect cameras for ArmarX.
86  *
87  * @class AzureKinectPointCloudProvider
88  * @ingroup Component-AzureKinectPointCloudProvider
89  * @brief Brief description of class AzureKinectPointCloudProvider.
90  */
92  // virtual public visionx::RGBDPointCloudProviderInterface,
93  virtual public armarx::AzureKinectPointCloudProviderInterface,
95  virtual public visionx::ImageProvider,
97 #ifdef INCLUDE_BODY_TRACKING
98  ,
99  virtual public armarx::armem::ClientPluginUser
100 #endif
101  {
102  public:
104 
105  using CloudPointType = pcl::PointXYZRGBA;
106  /**
107  * @see armarx::ManagedIceObject::getDefaultName()
108  */
109  std::string getDefaultName() const override;
110 
111  protected:
112  /**
113  * @see PropertyUser::createPropertyDefinitions()
114  */
116 
117  // ManagedIceObject interface
118  protected:
119  void onInitComponent() override;
120  void onConnectComponent() override;
121  void onDisconnectComponent() override;
122 
123  void onExitComponent() override;
124 
125  // StereoCalibrationInterface interface
126  public:
127  visionx::StereoCalibration getStereoCalibration(const Ice::Current& c) override;
128  bool getImagesAreUndistorted(const ::Ice::Current& c) override;
129 
130  std::string getReferenceFrame(const Ice::Current& c) override;
131 
132  std::vector<imrec::ChannelPreferences>
133  getImageRecordingChannelPreferences(const Ice::Current&) override;
134 
135  // AzureKinectBodyTrackingInterface interface
136  public:
137  void enableHumanPoseEstimation(const armarx::EnableHumanPoseEstimationInput& input,
138  const Ice::Current& = Ice::emptyCurrent) override;
139 
140  void setMaxDepthBodyTracking(int maxDepthInMM,
141  const Ice::Current& = Ice::emptyCurrent) override;
142 
143  void setWidthBodyTracking(int minXinPixel,
144  int maxXinPixel,
145  const Ice::Current& = Ice::emptyCurrent) override;
146 
147  protected:
148  void onStartCapture(float frames_per_second) override;
149  void onStopCapture() override;
150  void onInitImageProvider() override;
151  void onConnectImageProvider() override;
152  void onDisconnectImageProvider() override;
153 
154  void
156  {
157  }
158 
159  void onInitCapturingPointCloudProvider() override;
160  void onExitCapturingPointCloudProvider() override;
161  bool doCapture() override;
162 
163  bool
164  hasSharedMemorySupport(const Ice::Current& c) override
165  {
166  return true;
167  }
168 
169  MetaPointCloudFormatPtr
171  {
172  MetaPointCloudFormatPtr info = new MetaPointCloudFormat();
173  //info->frameId = getProperty<std::string>("frameId").getValue();
174  info->type = PointContentType::eColoredPoints;
175 
176  ARMARX_CHECK_EXPRESSION(resultColorImage);
177 
178  ARMARX_INFO << "default pointcloud format: " << resultColorImage->width << ", "
179  << resultColorImage->height;
180 
181  info->capacity =
182  resultColorImage->width * resultColorImage->height * sizeof(ColoredPoint3D);
183  info->size = info->capacity;
184  return info;
185  }
186 
188 
189  /*!
190  * @brief Returns the dimension of the color images that will be produced for a certain resolution.
191  * @param resolution The resolution that should be used for the color image.
192  * @return Pair of width and height that color images will have.
193  */
194  static inline std::pair<int, int>
195  GetColorDimensions(const k4a_color_resolution_t resolution)
196  {
197  switch (resolution)
198  {
199  case K4A_COLOR_RESOLUTION_720P:
200  return {1280, 720};
201  case K4A_COLOR_RESOLUTION_2160P:
202  return {3840, 2160};
203  case K4A_COLOR_RESOLUTION_1440P:
204  return {2560, 1440};
205  case K4A_COLOR_RESOLUTION_1080P:
206  return {1920, 1080};
207  case K4A_COLOR_RESOLUTION_3072P:
208  return {4096, 3072};
209  case K4A_COLOR_RESOLUTION_1536P:
210  return {2048, 1536};
211 
212  default:
213  throw std::logic_error("Invalid color dimensions value!");
214  }
215  }
216 
217  /*!
218  * @brief Returns the dimension of the depth images that will be produced for a certain resolution.
219  * @param resolution The resolution that should be used for the depth image.
220  * @return Pair of width and height that depth images will have.
221  */
222  static inline std::pair<int, int>
223  GetDepthDimensions(const k4a_depth_mode_t depth_mode)
224  {
225  switch (depth_mode)
226  {
227  case K4A_DEPTH_MODE_NFOV_2X2BINNED:
228  return {320, 288};
229  case K4A_DEPTH_MODE_NFOV_UNBINNED:
230  return {640, 576};
231  case K4A_DEPTH_MODE_WFOV_2X2BINNED:
232  return {512, 512};
233  case K4A_DEPTH_MODE_WFOV_UNBINNED:
234  return {1024, 1024};
235  case K4A_DEPTH_MODE_PASSIVE_IR:
236  return {1024, 1024};
237 
238  default:
239  throw std::logic_error("Invalid depth dimensions value!");
240  }
241  }
242 
243  /*!
244  * @brief Creates a string from a k4a_version_t.
245  * @param version The verstion that should be transformed into a string.
246  * @return The string representing the version.
247  */
248  static std::string
249  VersionToString(const k4a_version_t& version)
250  {
251  std::stringstream s;
252  s << version.major << "." << version.minor << "." << version.iteration;
253  return s.str();
254  }
255 
256  std::function<void(armarx::Duration)> createSwCallback(const std::string& description);
257 
258  void updateTimestampOffset(const std::chrono::microseconds& k4a_device_timestamp_us,
259  const std::chrono::nanoseconds& k4a_system_timestamp_ns);
260 
261  void initializeTimestampOffset(const std::chrono::microseconds& k4a_device_timestamp_us);
262 
263 
264  armarx::DateTime timestampToArmarX(const std::chrono::microseconds& k4a_timestamp_us);
265 
266  private:
267  // Time the last image was recorded.
268  IceUtil::Time imagesTime;
269 
270  // Mutex to protect the point cloud provider.
271  std::mutex pointcloudProcMutex;
272  std::condition_variable pointcloudProcSignal;
273 
274  bool depthImageReady;
275  bool depthImageProcessed;
276 
277  // Task for the point cloud provider.
279 
280  // IVT result images scaled to the size of the color image.
281  visionx::CByteImageUPtr resultDepthImage, resultColorImage;
282 
283  // Result point cloud.
284  pcl::PointCloud<CloudPointType>::Ptr pointcloud;
285  MetaPointCloudFormatPtr cloudFormat;
286 
287  // Stereo calibration used.
288  visionx::StereoCalibration calibration;
289 
290  // Undistort the color image with all coefficients.
291  bool enableColorUndistortion = false;
292 
293  //
294  bool enableHeartbeat = true;
295 
296  // Path to a external calibration file.
297  std::string externalCalibrationFilePath;
298 
299  // Camera parameters and distortion information.
300  cv::Mat cameraMatrix;
301  cv::Mat distCoeffs;
302 
303  cv::Mat colorDistortionMap;
304 
305  // K4A handles.
306  k4a::device device;
307  k4a_device_configuration_t config;
308  k4a::calibration k4aCalibration;
309 
310  k4a::transformation transformation;
311 
312  k4a::image alignedDepthImage, xyzImage;
313 
314 #ifdef INCLUDE_BODY_TRACKING
315  k4abt::tracker bodyTracker;
316  // armarx::armem::human::HumanMemoryServerInterfacePrx humanMemoryServer;
317 
318  armarx::armem::human::client::Writer humanPoseWriter;
319 
321 
322  void runPublishBodyTrackingResults();
323 #endif
324 
325  int mDeviceId = K4A_DEVICE_DEFAULT;
326 
327  struct diagnostics
328  {
329  unsigned int num_crashes = 0;
330  };
331 
332  diagnostics mDiagnostics;
333 
334  bool bodyTrackingEnabled = false; // Initialize Body Tracking
335  bool bodyTrackingRunAtStart = false;
336  std::atomic<bool> bodyTrackingIsRunning = false;
337  std::string bodyTrackingModelFilename = "${K4A_BODY_TRACKING_DNN_MODEL_FILEPATH}";
338  std::int32_t bodyTrackingGPUDeviceID = 0;
339  std::mutex bodyTrackingParameterMutex;
340  float bodyTrackingTemporalSmoothingFactor = 0.0f;
341  int bodyTrackingDepthMaskMinX = -1;
342  int bodyTrackingDepthMaskMaxX = -1;
343  int bodyTrackingDepthMaskMaxZ = -1;
344  bool startIMU = false;
345 
346  std::string bodyCameraFrameName = "AzureKinectDepthCamera";
347  std::string robotName = "Armar6";
348 
349  struct Framerate
350  {
351  int value = 30;
352 
353  struct Subordinate
354  {
355  std::string name;
356  float value = 30;
357  unsigned int skipFrames = 0;
358  unsigned int skipFramesCount = 0;
359 
360  void update(int higherFramerate);
361  bool skip();
362  };
363 
364  Subordinate bodyTracking {.name = "Body Tracking"};
365  Subordinate pointCloud {.name = "Point Cloud"};
366  } framerate;
367 
368  std::mutex deviceToRealtimeOffsetMtx;
369  std::chrono::nanoseconds device_to_realtime_offset_{0};
370 
371  std::mutex debugObserverMtx;
372  std::mutex metaInfoMtx;
373 
374  armarx::plugins::HeartbeatComponentPlugin* heartbeatPlugin = nullptr;
375  };
376 } // namespace visionx
visionx::AzureKinectPointCloudProviderPropertyDefinitions
Definition: AzureKinectPointCloudProvider.h:73
CapturingPointCloudProvider.h
visionx::AzureKinectPointCloudProvider::GetDepthDimensions
static std::pair< int, int > GetDepthDimensions(const k4a_depth_mode_t depth_mode)
Returns the dimension of the depth images that will be produced for a certain resolution.
Definition: AzureKinectPointCloudProvider.h:223
visionx::AzureKinectPointCloudProvider::hasSharedMemorySupport
bool hasSharedMemorySupport(const Ice::Current &c) override
Definition: AzureKinectPointCloudProvider.h:164
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
visionx::AzureKinectPointCloudProvider::Framerate::Subordinate::update
void update(int higherFramerate)
Definition: AzureKinectPointCloudProvider.cpp:1508
armarx::armem::human::client::Writer
Definition: HumanPoseWriter.h:21
visionx::AzureKinectPointCloudProvider::doCapture
bool doCapture() override
Main capturing function.
Definition: AzureKinectPointCloudProvider.cpp:595
visionx::AzureKinectPointCloudProvider::getStereoCalibration
visionx::StereoCalibration getStereoCalibration(const Ice::Current &c) override
Definition: AzureKinectPointCloudProvider.cpp:1238
visionx::AzureKinectPointCloudProvider::VersionToString
static std::string VersionToString(const k4a_version_t &version)
Creates a string from a k4a_version_t.
Definition: AzureKinectPointCloudProvider.h:249
armarx::PropertyDefinitionContainer::prefix
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
Definition: PropertyDefinitionContainer.h:333
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:43
visionx::AzureKinectPointCloudProvider::Framerate::Subordinate::name
std::string name
Definition: AzureKinectPointCloudProvider.h:355
visionx::AzureKinectPointCloudProvider::initializeTimestampOffset
void initializeTimestampOffset(const std::chrono::microseconds &k4a_device_timestamp_us)
Definition: AzureKinectPointCloudProvider.cpp:1487
visionx::AzureKinectPointCloudProvider::GetColorDimensions
static std::pair< int, int > GetColorDimensions(const k4a_color_resolution_t resolution)
Returns the dimension of the color images that will be produced for a certain resolution.
Definition: AzureKinectPointCloudProvider.h:195
RunningTask.h
visionx::AzureKinectPointCloudProvider::getImageRecordingChannelPreferences
std::vector< imrec::ChannelPreferences > getImageRecordingChannelPreferences(const Ice::Current &) override
Definition: AzureKinectPointCloudProvider.cpp:1335
visionx::AzureKinectPointCloudProvider::updateTimestampOffset
void updateTimestampOffset(const std::chrono::microseconds &k4a_device_timestamp_us, const std::chrono::nanoseconds &k4a_system_timestamp_ns)
Definition: AzureKinectPointCloudProvider.cpp:1405
visionx::AzureKinectPointCloudProvider::createSwCallback
std::function< void(armarx::Duration)> createSwCallback(const std::string &description)
Definition: AzureKinectPointCloudProvider.cpp:149
armarx::plugins::HeartbeatComponentPlugin
Definition: HeartbeatComponentPlugin.h:33
visionx::AzureKinectPointCloudProvider
Brief description of class AzureKinectPointCloudProvider.
Definition: AzureKinectPointCloudProvider.h:91
visionx::AzureKinectPointCloudProvider::Framerate::Subordinate::value
float value
Definition: AzureKinectPointCloudProvider.h:356
visionx::AzureKinectPointCloudProvider::setWidthBodyTracking
void setWidthBodyTracking(int minXinPixel, int maxXinPixel, const Ice::Current &=Ice::emptyCurrent) override
Definition: AzureKinectPointCloudProvider.cpp:1392
armarx::armem::client::plugins::PluginUser
Adds the Memory Name System client component plugin.
Definition: PluginUser.h:29
visionx::AzureKinectPointCloudProvider::getDefaultPointCloudFormat
MetaPointCloudFormatPtr getDefaultPointCloudFormat() override
default point cloud format used to initialize shared memory
Definition: AzureKinectPointCloudProvider.h:170
visionx::AzureKinectPointCloudProvider::onStopCapture
void onStopCapture() override
This is called when the point cloud provider capturing has been stopped.
Definition: AzureKinectPointCloudProvider.cpp:586
visionx::AzureKinectPointCloudProvider::onExitImageProvider
void onExitImageProvider() override
This is called when the Component::onExitComponent() setup is called.
Definition: AzureKinectPointCloudProvider.h:155
visionx::AzureKinectPointCloudProvider::CloudPointType
pcl::PointXYZRGBA CloudPointType
Definition: AzureKinectPointCloudProvider.h:105
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:926
visionx::CByteImageUPtr
std::unique_ptr< CByteImage > CByteImageUPtr
Definition: ImageProvider.h:57
visionx::AzureKinectPointCloudProvider::Framerate::Subordinate::skipFrames
unsigned int skipFrames
Definition: AzureKinectPointCloudProvider.h:357
visionx::AzureKinectPointCloudProvider::timestampToArmarX
armarx::DateTime timestampToArmarX(const std::chrono::microseconds &k4a_timestamp_us)
Definition: AzureKinectPointCloudProvider.cpp:1471
visionx::CapturingPointCloudProviderPropertyDefinitions
Definition: CapturingPointCloudProvider.h:38
visionx::AzureKinectPointCloudProvider::runPointcloudPublishing
void runPointcloudPublishing()
Definition: AzureKinectPointCloudProvider.cpp:1081
visionx::AzureKinectPointCloudProvider::onExitCapturingPointCloudProvider
void onExitCapturingPointCloudProvider() override
This is called when the Component::onExitComponent() setup is called.
Definition: AzureKinectPointCloudProvider.cpp:418
armarx::aron::input
ReaderT::InputType & input
Definition: rw.h:19
visionx::AzureKinectPointCloudProviderPropertyDefinitions::AzureKinectPointCloudProviderPropertyDefinitions
AzureKinectPointCloudProviderPropertyDefinitions(std::string prefix)
Definition: AzureKinectPointCloudProvider.cpp:167
visionx::AzureKinectPointCloudProvider::setMaxDepthBodyTracking
void setMaxDepthBodyTracking(int maxDepthInMM, const Ice::Current &=Ice::emptyCurrent) override
Definition: AzureKinectPointCloudProvider.cpp:1385
visionx::AzureKinectPointCloudProvider::getReferenceFrame
std::string getReferenceFrame(const Ice::Current &c) override
Definition: AzureKinectPointCloudProvider.cpp:1329
DebugObserverComponentPlugin.h
visionx::AzureKinectPointCloudProvider::Framerate::Subordinate
Definition: AzureKinectPointCloudProvider.h:353
visionx::AzureKinectPointCloudProvider::onDisconnectComponent
void onDisconnectComponent() override
Hook for subclass.
Definition: AzureKinectPointCloudProvider.cpp:1222
visionx::imrec::Framerate
Framerate
Definition: public_api.h:68
visionx::AzureKinectPointCloudProvider::AzureKinectPointCloudProvider
AzureKinectPointCloudProvider()
Definition: AzureKinectPointCloudProvider.cpp:1502
HeartbeatComponentPlugin.h
visionx::AzureKinectPointCloudProvider::getImagesAreUndistorted
bool getImagesAreUndistorted(const ::Ice::Current &c) override
Definition: AzureKinectPointCloudProvider.cpp:1323
visionx::AzureKinectPointCloudProvider::onDisconnectImageProvider
void onDisconnectImageProvider() override
Definition: AzureKinectPointCloudProvider.cpp:384
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
forward_declarations.h
visionx::AzureKinectPointCloudProvider::onInitCapturingPointCloudProvider
void onInitCapturingPointCloudProvider() override
This is called when the Component::onInitComponent() is called.
Definition: AzureKinectPointCloudProvider.cpp:411
Component.h
visionx::CapturingPointCloudProvider
The CapturingPointCloudProvider provides a callback function to trigger the capturing of point clouds...
Definition: CapturingPointCloudProvider.h:56
visionx::AzureKinectPointCloudProvider::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: AzureKinectPointCloudProvider.cpp:207
armarx::core::time::DateTime
Represents a point in time.
Definition: DateTime.h:24
visionx::ImageProvider
ImageProvider abstract class defines a component which provide images via ice or shared memory.
Definition: ImageProvider.h:66
visionx::AzureKinectPointCloudProvider::onInitComponent
void onInitComponent() override
Pure virtual hook for the subclass.
Definition: AzureKinectPointCloudProvider.cpp:1208
CapturingImageProvider.h
visionx::AzureKinectPointCloudProvider::enableHumanPoseEstimation
void enableHumanPoseEstimation(const armarx::EnableHumanPoseEstimationInput &input, const Ice::Current &=Ice::emptyCurrent) override
Definition: AzureKinectPointCloudProvider.cpp:1351
ARMARX_CHECK_EXPRESSION
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
Definition: ExpressionException.h:73
TimeUtil.h
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
HumanPoseWriter.h
visionx::AzureKinectPointCloudProvider::onConnectImageProvider
void onConnectImageProvider() override
This is called when the Component::onConnectComponent() setup is called.
Definition: AzureKinectPointCloudProvider.cpp:348
IceUtil::Handle< class PropertyDefinitionContainer >
visionx::AzureKinectPointCloudProvider::Framerate::Subordinate::skip
bool skip()
Definition: AzureKinectPointCloudProvider.cpp:1527
visionx::AzureKinectPointCloudProvider::getDefaultName
std::string getDefaultName() const override
Definition: AzureKinectPointCloudProvider.cpp:1202
armarx::core::time::Duration
Represents a duration.
Definition: Duration.h:17
armarx::DebugObserverComponentPluginUser
Definition: DebugObserverComponentPlugin.h:82
PluginUser.h
DepthImageUtils.h
visionx::AzureKinectPointCloudProvider::onExitComponent
void onExitComponent() override
Hook for subclass.
Definition: AzureKinectPointCloudProvider.cpp:1231
visionx::AzureKinectPointCloudProvider::onStartCapture
void onStartCapture(float frames_per_second) override
This is called when the point cloud provider capturing has been started.
Definition: AzureKinectPointCloudProvider.cpp:426
visionx::AzureKinectPointCloudProvider::Framerate::Subordinate::skipFramesCount
unsigned int skipFramesCount
Definition: AzureKinectPointCloudProvider.h:358
armarx::ctrlutil::s
double s(double t, double s0, double v0, double a0, double j)
Definition: CtrlUtil.h:33
visionx::AzureKinectPointCloudProvider::onInitImageProvider
void onInitImageProvider() override
This is called when the Component::onInitComponent() is called.
Definition: AzureKinectPointCloudProvider.cpp:278
visionx::AzureKinectPointCloudProvider::onConnectComponent
void onConnectComponent() override
Pure virtual hook for the subclass.
Definition: AzureKinectPointCloudProvider.cpp:1215