29 #include <condition_variable>
36 #include <opencv2/opencv.hpp>
43 #include <ArmarXCore/interface/observers/ObserverInterface.h>
48 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
55 #include <VisionX/interface/components/AzureKinectPointCloudProviderInterface.h>
56 #include <VisionX/libraries/armem_human/server/HumanMemoryServerInterface.h>
60 #include <k4a/k4a.hpp>
62 #ifdef INCLUDE_BODY_TRACKING
93 virtual public armarx::AzureKinectPointCloudProviderInterface,
97 #ifdef INCLUDE_BODY_TRACKING
132 std::vector<imrec::ChannelPreferences>
138 const Ice::Current& = Ice::emptyCurrent)
override;
141 const Ice::Current& = Ice::emptyCurrent)
override;
145 const Ice::Current& = Ice::emptyCurrent)
override;
169 MetaPointCloudFormatPtr
172 MetaPointCloudFormatPtr info =
new MetaPointCloudFormat();
174 info->type = PointContentType::eColoredPoints;
178 ARMARX_INFO <<
"default pointcloud format: " << resultColorImage->width <<
", "
179 << resultColorImage->height;
182 resultColorImage->width * resultColorImage->height *
sizeof(ColoredPoint3D);
183 info->size = info->capacity;
194 static inline std::pair<int, int>
199 case K4A_COLOR_RESOLUTION_720P:
201 case K4A_COLOR_RESOLUTION_2160P:
203 case K4A_COLOR_RESOLUTION_1440P:
205 case K4A_COLOR_RESOLUTION_1080P:
207 case K4A_COLOR_RESOLUTION_3072P:
209 case K4A_COLOR_RESOLUTION_1536P:
213 throw std::logic_error(
"Invalid color dimensions value!");
222 static inline std::pair<int, int>
227 case K4A_DEPTH_MODE_NFOV_2X2BINNED:
229 case K4A_DEPTH_MODE_NFOV_UNBINNED:
231 case K4A_DEPTH_MODE_WFOV_2X2BINNED:
233 case K4A_DEPTH_MODE_WFOV_UNBINNED:
235 case K4A_DEPTH_MODE_PASSIVE_IR:
239 throw std::logic_error(
"Invalid depth dimensions value!");
252 s << version.major <<
"." << version.minor <<
"." << version.iteration;
259 const std::chrono::nanoseconds& k4a_system_timestamp_ns);
271 std::mutex pointcloudProcMutex;
272 std::condition_variable pointcloudProcSignal;
274 bool depthImageReady;
275 bool depthImageProcessed;
284 pcl::PointCloud<CloudPointType>::Ptr pointcloud;
285 MetaPointCloudFormatPtr cloudFormat;
288 visionx::StereoCalibration calibration;
291 bool enableColorUndistortion =
false;
294 bool enableHeartbeat =
true;
297 std::string externalCalibrationFilePath;
300 cv::Mat cameraMatrix;
303 cv::Mat colorDistortionMap;
307 k4a_device_configuration_t config;
308 k4a::calibration k4aCalibration;
310 k4a::transformation transformation;
312 k4a::image alignedDepthImage, xyzImage;
314 #ifdef INCLUDE_BODY_TRACKING
315 k4abt::tracker bodyTracker;
322 void runPublishBodyTrackingResults();
325 int mDeviceId = K4A_DEVICE_DEFAULT;
329 unsigned int num_crashes = 0;
332 diagnostics mDiagnostics;
334 bool bodyTrackingEnabled =
false;
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;
346 std::string bodyCameraFrameName =
"AzureKinectDepthCamera";
347 std::string robotName =
"Armar6";
360 void update(
int higherFramerate);
365 Subordinate pointCloud {.name =
"Point Cloud"};
368 std::mutex deviceToRealtimeOffsetMtx;
369 std::chrono::nanoseconds device_to_realtime_offset_{0};
371 std::mutex debugObserverMtx;
372 std::mutex metaInfoMtx;