23 #include <pcl/filters/approximate_voxel_grid.h>
24 #include <pcl/common/transforms.h>
30 #include <VisionX/interface/components/Calibration.h>
31 #include <VisionX/interface/core/PointCloudProcessorInterface.h>
35 #define call_template_function(F) \
36 switch(_pointCloudProviderInfo.pointCloudFormat->type) \
38 case visionx::PointContentType::ePoints : F<pcl::PointXYZ>(); break; \
39 case visionx::PointContentType::eColoredPoints : F<pcl::PointXYZRGBA>(); break; \
40 case visionx::PointContentType::eColoredOrientedPoints : F<pcl::PointXYZRGBNormal>(); break; \
41 case visionx::PointContentType::eLabeledPoints : F<pcl::PointXYZL>(); break; \
42 case visionx::PointContentType::eColoredLabeledPoints : F<pcl::PointXYZRGBL>(); break; \
43 case visionx::PointContentType::eIntensity : F<pcl::PointXYZI>(); break; \
44 case visionx::PointContentType::eOrientedPoints : \
45 ARMARX_ERROR << "eOrientedPoints NOT HANDLED IN VISIONX"; \
46 [[fallthrough]]; default: \
47 ARMARX_ERROR << "Could not call " #F ", because format '" \
48 << _pointCloudProviderInfo.pointCloudFormat->type << "' is unknown"; \
56 return "MultiViewPointCloudProcessor";
61 prop->defineOptionalProperty<std::string>(
"ProviderReferenceFrame",
"",
"Name of the point cloud refence frame (empty = autodetect)");
62 std::lock_guard guard{_cfgBufWriteMutex};
72 std::lock_guard guard{_cfgBufWriteMutex};
86 std::lock_guard guard{_cfgBufWriteMutex};
110 _pointCloudProviderName = getProperty<std::string>(
"ProviderName");
119 _pointCloudProvider = _pointCloudProviderInfo.
proxy;
120 _pointCloudProviderRefFrame = getProperty<std::string>(
"ProviderReferenceFrame");
121 if (_pointCloudProviderRefFrame.empty())
123 _pointCloudProviderRefFrame =
"root";
124 auto frameprov = visionx::ReferenceFrameInterfacePrx::checkedCast(_pointCloudProvider);
127 _pointCloudProviderRefFrame = frameprov->getReferenceFrame();
132 if (!_providerThread.joinable())
136 _providerThread = std::thread
146 _robot =
addRobot(
"_robot", VirtualRobot::RobotIO::eStructure);
157 _stopProviding =
true;
158 _providerThread.join();
179 std::lock_guard guard{_cfgBufWriteMutex};
185 std::lock_guard guard{_cfgBufWriteMutex};
191 std::lock_guard guard{_cfgBufWriteMutex};
204 template<
class Po
intType>
211 const auto doRecord = _doRecord.load();
214 std::lock_guard guard{_viewPointsMutex};
216 _currentViewpoint = doRecord ? 0 : -1;
223 const auto currentViewpoint = _currentViewpoint.load();
225 using cloud_t = pcl::PointCloud<PointType>;
226 using cloud_ptr_t =
typename cloud_t::Ptr;
228 std::unique_lock lock{_cfgBufReadMutex};
236 cloud_ptr_t transformedCloud;
241 <<
"Timeout or error while waiting for point cloud data of provider "
242 << _pointCloudProviderName;
245 cloud_ptr_t inputCloud(
new cloud_t);
252 fp.changeFrame(_robot,
"Global");
256 transformedCloud = cloud_ptr_t(
new cloud_t);
257 pcl::transformPointCloud(*inputCloud, *transformedCloud, providerInRootFrame);
260 std::lock_guard guard{_viewPointsMutex};
261 const auto p =
static_cast<std::size_t
>(currentViewpoint);
262 if (p + 1 > _viewPoints.size())
264 _viewPoints.resize(p + 1);
266 _viewPoints.at(p).clouds.emplace_back(transformedCloud);
267 if (buf.maxNumberOfFramesPerViewPoint > 0)
269 while (_viewPoints.at(p).clouds.size() >
static_cast<std::size_t
>(buf.maxNumberOfFramesPerViewPoint))
271 _viewPoints.at(p).clouds.pop_front();
277 template<
class Po
intType>
280 using cloud_t = pcl::PointCloud<PointType>;
281 using cloud_ptr_t =
typename cloud_t::Ptr;
282 std::deque<std::uint64_t> idxVec;
283 while (!_stopProviding)
285 const auto timeBeg = std::chrono::high_resolution_clock::now();
287 std::unique_lock lock{_cfgBufReadMutex};
291 cloud_ptr_t cloud(
new cloud_t);
293 std::lock_guard guard{_viewPointsMutex};
294 if (idxVec.size() < _viewPoints.size())
296 idxVec.resize(_viewPoints.size());
298 for (std::size_t i = 0; i < idxVec.size(); ++i)
300 const auto& inVec = _viewPoints.at(i).clouds;
301 const auto idx = (idxVec.at(i)++) % inVec.size();
302 const auto& in = *std::any_cast<cloud_ptr_t>(inVec.at(idx));
303 auto& out = cloud->points;
304 out.insert(out.end(), in.begin(), in.end());
308 if (buf.gridSize > 0)
310 pcl::ApproximateVoxelGrid<PointType> grid;
311 grid.setLeafSize(Eigen::Vector3f::Constant(buf.gridSize));
312 grid.setInputCloud(cloud);
313 cloud_ptr_t tempCloud(
new cloud_t);
314 grid.filter(*tempCloud);
315 tempCloud.swap(cloud);
324 std::this_thread::sleep_until(timeBeg + std::chrono::milliseconds{dtms});