28#include <opencv2/opencv.hpp>
30#include <SimoxUtility/algorithm/string/string_tools.h>
45#include <Calibration/Calibration.h>
46#include <Image/ByteImage.h>
47#include <Image/ImageProcessor.h>
61 "VisionX/examples/point_clouds/",
62 "The point cloud to read. If directory, all *.pcd files of this and all subdirectories "
64 "All point clouds are read in before the pointcloud providing starts.");
68 "scaleFactor", -1.0f,
"scale point cloud. only applied if value is larger than zero");
70 .map(
"320x240", Eigen::Vector2i(320, 240))
71 .map(
"640x480", Eigen::Vector2i(640, 480))
72 .map(
"320x240", Eigen::Vector2i(320, 240))
73 .map(
"640x480", Eigen::Vector2i(640, 480))
74 .map(
"800x600", Eigen::Vector2i(800, 600))
75 .map(
"768x576", Eigen::Vector2i(768, 576))
76 .map(
"1024x768", Eigen::Vector2i(1024, 768))
77 .map(
"1024x1024", Eigen::Vector2i(1024, 1024))
78 .map(
"1280x960", Eigen::Vector2i(1280, 960))
79 .map(
"1600x1200", Eigen::Vector2i(1600, 1200));
82 "depthCameraCalibrationFile",
"",
"Camera depth calibration file (YAML)");
84 "RGBCameraCalibrationFile",
"",
"Camera RGB calibration file (YAML)");
87 "sourceFrameName",
"",
"Assume point cloud was stored in this frame.");
91 "Coordinate frame in which point cloud will be transformed and provided.\n"
92 "If left empty, no transformation will be applied and source frame name\n"
93 "will be returned as reference frame.");
96 "RobotStateComponent",
97 "Name of the robot state component to use.");
100 "ProvidedPointCloudFormat",
102 "Format of the provided point cloud (XYZRGBA, XYZL, XYZRGBL)");
108 return "FakePointCloudProvider";
150 getProperty(pointCloudFileName,
"pointCloudFileName");
156 getProperty(providedPointCloudFormat,
"ProvidedPointCloudFormat");
157 ARMARX_INFO <<
"Providing point clouds in format " << providedPointCloudFormat <<
".";
159 getProperty(robotStateComponentName,
"RobotStateComponentName");
160 if (!robotStateComponentName.empty())
166 if (!(sourceFrameName.empty() && targetFrameName.empty()))
168 if (!sourceFrameName.empty() && !targetFrameName.empty() &&
169 robotStateComponentName.empty())
171 ARMARX_ERROR <<
"Source and target frames specified, but no RobotStateComponent is "
173 "No transformation will be applied.";
175 else if (sourceFrameName.empty() && !targetFrameName.empty())
177 ARMARX_WARNING <<
"Target frame was specified (" << targetFrameName
178 <<
"), but no source frame is specified.\n"
179 <<
"Did you set the property `sourceFrameName`? (No transformation "
182 else if (!sourceFrameName.empty() && targetFrameName.empty())
184 ARMARX_INFO <<
"Source frame was specified (" << sourceFrameName
185 <<
"), but no target frame is specified.\n"
186 <<
"No transformation will be applied and source frame is returned as "
194 ARMARX_ERROR <<
"Could not find point cloud file in ArmarXDataPath: "
195 << pointCloudFileName;
199 if (std::filesystem::is_directory(pointCloudFileName))
201 loadPointCloudDirectory(pointCloudFileName);
205 loadPointCloud(pointCloudFileName);
208 if (pointClouds.empty())
210 ARMARX_FATAL <<
"Unable to load point cloud: " << pointCloudFileName;
211 throw LocalException(
"Unable to load point cloud");
214 ARMARX_INFO <<
"Loaded " << pointClouds.size() <<
" point clouds.";
217 visionx::CameraParameters RGBCameraIntrinsics;
218 RGBCameraIntrinsics.focalLength.resize(2);
219 RGBCameraIntrinsics.principalPoint.resize(2);
223 RGBCameraIntrinsics))
227 <<
" - using camera uncalibrated";
230 visionx::CameraParameters depthCameraIntrinsics;
231 depthCameraIntrinsics.focalLength.resize(2);
232 depthCameraIntrinsics.principalPoint.resize(2);
236 depthCameraIntrinsics))
240 <<
" - using camera uncalibrated";
245 calibration.calibrationLeft.cameraParam = RGBCameraIntrinsics;
246 calibration.calibrationRight.cameraParam = depthCameraIntrinsics;
250 FakePointCloudProvider::loadPointCloud(
const std::string& fileName)
252 if (simox::alg::ends_with(fileName,
".pcd") && std::filesystem::is_regular_file(fileName))
254 pcl::PCLPointCloud2Ptr cloudptr(
new pcl::PCLPointCloud2());
257 if (io::loadPCDFile(fileName.c_str(), *cloudptr) == -1)
259 ARMARX_WARNING <<
"Unable to load point cloud from file " << fileName;
264 pointClouds.push_back(cloudptr);
273 FakePointCloudProvider::loadPointCloudDirectory(
const std::string& directoryName)
276 std::vector<std::string> fileNames;
278 for (std::filesystem::recursive_directory_iterator dir(directoryName), end;
279 dir != end &&
getState() < eManagedIceObjectExiting;
283 if (dir->path().extension() ==
".pcd")
285 fileNames.push_back(dir->path().string());
289 ARMARX_INFO <<
"In total " << fileNames.size() <<
" point clouds found.";
292 std::sort(fileNames.begin(), fileNames.end());
294 for (std::size_t f = 0; f < fileNames.size(); f++)
296 ARMARX_INFO <<
" File " << f <<
" / " << fileNames.size() <<
" is being loaded... "
300 loadPointCloud(fileNames[f]);
318 MetaPointCloudFormatPtr
321 MetaPointCloudFormatPtr format =
new MetaPointCloudFormat();
323 if (providedPointCloudFormat ==
"XYZL")
325 format->type = PointContentType::eLabeledPoints;
327 else if (providedPointCloudFormat ==
"XYZRGBL")
329 format->type = PointContentType::eColoredLabeledPoints;
333 format->type = PointContentType::eColoredPoints;
338 format->size = format->capacity;
346 setImageFormat(visionx::ImageDimension(dimensions(0), dimensions(1)), visionx::eRgb);
348 rgbImages =
new CByteImage*[1];
349 rgbImages[0] =
new CByteImage(dimensions(0), dimensions(1), CByteImage::eRGB24);
350 ::ImageProcessor::Zero(rgbImages[0]);
359 if (!robotStateComponentName.empty())
361 getProxy(robotStateComponent, robotStateComponentName);
362 if (!robotStateComponent)
364 ARMARX_ERROR <<
"Failed to obtain robot state component.";
380 pcl::PCLPointCloud2Ptr cloudptr;
383 std::scoped_lock lock(pointCloudMutex);
385 if (rewind &&
static_cast<size_t>(counter.load()) >= pointClouds.size())
390 cloudptr = pointClouds.at(counter);
394 if (providedPointCloudFormat ==
"XYZRGBA")
396 return processAndProvide<pcl::PointXYZRGBA>(cloudptr);
398 else if (providedPointCloudFormat ==
"XYZL")
400 return processAndProvide<pcl::PointXYZL>(cloudptr);
402 else if (providedPointCloudFormat ==
"XYZRGBL")
404 return processAndProvide<pcl::PointXYZRGBL>(cloudptr);
408 ARMARX_ERROR <<
"Could not provide point cloud, because format '"
409 << providedPointCloudFormat <<
"' is unknown";
415 FakePointCloudProvider::loadCalibrationFile(std::string fileName,
416 visionx::CameraParameters& calibration)
419 cv::FileStorage fs(fileName, cv::FileStorage::READ);
426 std::string cameraName = fs[
"camera_name"];
427 ARMARX_LOG <<
"loading calibration file for " << cameraName;
431 int imageWidth = fs[
"image_width"];
432 int imageHeight = fs[
"image_height"];
434 if (imageWidth != dimensions(0) || imageHeight != dimensions(1))
440 cv::Mat cameraMatrix, distCoeffs;
442 fs[
"camera_matrix"] >> cameraMatrix;
443 fs[
"distortion_coefficients:"] >> distCoeffs;
445 for (
int i = 0; i < 5; i++)
447 calibration.distortion[
static_cast<std::size_t
>(i)] = distCoeffs.at<
float>(0, i);
450 calibration.focalLength[0] = cameraMatrix.at<
float>(0, 0);
451 calibration.focalLength[1] = cameraMatrix.at<
float>(1, 1);
453 calibration.principalPoint[0] = cameraMatrix.at<
float>(2, 1);
454 calibration.principalPoint[1] = cameraMatrix.at<
float>(2, 2);
469 std::scoped_lock lock(pointCloudMutex);
471 ARMARX_INFO <<
"Changing point cloud filename to: " << filename;
474 loadPointCloud(filename);
483 template <
typename Po
intT>
485 FakePointCloudProvider::processAndProvide(
const PCLPointCloud2Ptr& pointCloud)
487 using PointCloudPtrT =
typename pcl::PointCloud<PointT>::Ptr;
489 PointCloudPtrT cloudptr(
new pcl::PointCloud<PointT>());
490 pcl::fromPCLPointCloud2(*pointCloud, *cloudptr);
492 if (cloudptr->isOrganized())
494 processRGBImage(pointCloud);
497 PointCloudPtrT resultCloudPtr(
new pcl::PointCloud<PointT>());
501 Eigen::Affine3f
transform(Eigen::Scaling(scaleFactor));
502 pcl::transformPointCloud(*cloudptr, *resultCloudPtr,
transform);
507 pcl::copyPointCloud(*cloudptr, *resultCloudPtr);
511 resultCloudPtr->header.stamp =
static_cast<uint64_t
>(time.toMicroSeconds());
513 if (!sourceFrameName.empty() || !targetFrameName.empty())
515 if (!sourceFrameName.empty() && !targetFrameName.empty())
521 localRobot, robotStateComponent, time.toMicroSeconds());
523 framedPointCloud.
changeFrame(targetFrameName, localRobot);
532 else if (sourceFrameName.empty())
538 else if (targetFrameName.empty())
549 std::vector<int> indices;
550 pcl::removeNaNFromPointCloud(*resultCloudPtr, *resultCloudPtr, indices);
554 << resultCloudPtr->points.size();
560 counter = freezeImageIdx.load();
570 FakePointCloudProvider::processRGBImage(
const PCLPointCloud2Ptr& pointCloud)
572 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudptr(
new pcl::PointCloud<pcl::PointXYZRGB>());
573 pcl::fromPCLPointCloud2(*pointCloud, *cloudptr);
575 if (!cloudptr->isOrganized())
578 <<
"The point cloud is not organized, so no RGB image is generated";
582 if (
static_cast<int>(cloudptr->width) != rgbImages[0]->width ||
583 static_cast<int>(cloudptr->height) != rgbImages[0]->height)
586 <<
"Dimensions of point cloud and image do not match, so no RGB image is generated";
590 ::ImageProcessor::Zero(rgbImages[0]);
591 const int width =
static_cast<int>(cloudptr->width);
592 const int height =
static_cast<int>(cloudptr->height);
594 for (
int i = 0; i < height; i++)
596 for (
int j = 0; j < width; j++)
598 pcl::PointXYZRGB& point = cloudptr->at(
static_cast<std::size_t
>(i * width + j));
599 rgbImages[0]->pixels[3 * (i * width + j) + 0] = point.r;
600 rgbImages[0]->pixels[3 * (i * width + j) + 1] = point.g;
601 rgbImages[0]->pixels[3 * (i * width + j) + 2] = point.b;
611 for (std::size_t i = 0; i < 1; i++)
634 return !targetFrameName.empty() ? targetFrameName : sourceFrameName;
638 FakePointCloudProvider::buildGui()
657 .
addTextLabel(
" / " + std::to_string(pointClouds.size() - 1));
666 prx.
getValue(removeNAN,
"removeNAN");
667 prx.
getValue(scaleFactor,
"scaleFactor");
668 prx.
getValue(freezeImage,
"freezeImage");
671 prx.
getValue(freezeImageIdx,
"freezeImageIdx");
675 prx.
setValue(counter,
"freezeImageIdx");
static bool getAbsolutePath(const std::string &relativeFilename, std::string &storeAbsoluteFilename, const std::vector< std::string > &additionalSearchPaths={}, bool verbose=true)
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Property< PropertyType > getProperty(const std::string &name)
SpamFilterDataPtr deactivateSpam(float deactivationDurationSec=10.0f, const std::string &identifier="", bool deactivate=true) const
disables the logging for the current line for the given amount of seconds.
virtual void onExitComponent()
Hook for subclass.
bool usingProxy(const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list.
virtual void onDisconnectComponent()
Hook for subclass.
virtual void onConnectComponent()=0
Pure virtual hook for the subclass.
Ice::ObjectPrx getProxy(long timeoutMs=0, bool waitForScheduler=true) const
Returns the proxy of this object (optionally it waits for the proxy)
virtual void onInitComponent()=0
Pure virtual hook for the subclass.
int getState() const
Retrieve current state of the ManagedIceObject.
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
PropertyDefinition< PropertyType > & defineOptionalProperty(const std::string &name, PropertyType defaultValue, const std::string &description="", PropertyDefinitionBase::PropertyConstness constness=PropertyDefinitionBase::eConstant)
void createOrUpdateRemoteGuiTab(Ts &&... ts)
void setValue(const T &val, std::string const &name)
ValueProxy< T > getValue(std::string const &name)
VirtualRobot::RobotPtr createLocalClone()
Clones the structure of this remote robot to a local instance.
static bool synchronizeLocalCloneToTimestamp(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx, Ice::Long timestamp)
Synchronizes a local robot to a robot state at timestamp.
static IceUtil::Time GetTime(TimeMode timeMode=TimeMode::VirtualTime)
Get the current time.
CapturingPointCloudProviderPropertyDefinitions(std::string prefix)
FakePointCloudProviderPropertyDefinitions(std::string prefix)
void onInitComponent() override
Pure virtual hook for the subclass.
bool doCapture() override
void onExitCapturingPointCloudProvider() override
bool hasSharedMemorySupport(const Ice::Current &=Ice::emptyCurrent) override
void onDisconnectComponent() override
Hook for subclass.
bool getImagesAreUndistorted(const Ice::Current &=Ice::emptyCurrent) override
void onStartCapture(float frameRate) override
std::string getReferenceFrame(const Ice::Current &=Ice::emptyCurrent) override
void onInitCapturingPointCloudProvider() override
MetaPointCloudFormatPtr getDefaultPointCloudFormat() override
default point cloud format used to initialize shared memory
void onConnectComponent() override
Pure virtual hook for the subclass.
void onStopCapture() override
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
void onInitImageProvider() override
void setPointCloudFilename(const std::string &filename, const ::Ice::Current &=Ice::emptyCurrent) override
void onExitComponent() override
Hook for subclass.
void onExitImageProvider() override
StereoCalibration getStereoCalibration(const Ice::Current &=Ice::emptyCurrent) override
std::string getDefaultName() const override
A point cloud which keeps track of its reference coordinate frame and allows changing frames using ar...
void changeFrame(const std::string &newFrame, const VirtualRobot::RobotConstPtr &robot)
Transform the point cloud from the current frame to the new frame using the given reference robot.
void onInitComponent() override
void onDisconnectComponent() override
Hook for subclass.
void setImageFormat(ImageDimension imageDimension, ImageType imageType, BayerPatternType bayerPatternType=visionx::eBayerPatternRg)
Sets the image basic format data.
void provideImages(void **inputBuffers, const IceUtil::Time &imageTimestamp=IceUtil::Time())
send images raw.
void onConnectComponent() override
void setNumberImages(int numberImages)
Sets the number of images on each capture.
void onExitComponent() override
void providePointCloud(PointCloudPtrT pointCloudPtr)
offer the new point cloud.
#define ARMARX_INFO
The normal logging level.
#define ARMARX_FATAL
The logging level for unexpected behaviour, that will lead to a seriously malfunctioning program and ...
#define ARMARX_ERROR
The logging level for unexpected behaviour, that must be fixed.
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
#define ARMARX_VERBOSE
The logging level for verbose information.
std::string const GlobalFrame
Variable of the global coordinate system.
detail::IntSpinBoxBuilder makeIntSpinBox(std::string const &name)
detail::CheckBoxBuilder makeCheckBox(std::string const &name)
detail::FloatSpinBoxBuilder makeFloatSpinBox(std::string const &name)
detail::SimpleGridLayoutBuilder makeSimpleGridLayout(std::string const &name="")
This file offers overloads of toIce() and fromIce() functions for STL container types.
std::string GetHandledExceptionString()
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT > >
Convenience function (with less typing) to transform a container of type InputT into the same contain...
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
SimpleGridLayoutBuilder & addTextLabel(std::string const &text, int colspan)
SimpleGridLayoutBuilder & cols(int n)
SimpleGridLayoutBuilder & addChild(WidgetPtr const &child, int colspan)