FakePointCloudProvider.cpp
Go to the documentation of this file.
1/*
2 * This file is part of ArmarX.
3 *
4 * Copyright (C) 2011-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5 *
6 * ArmarX is free software; you can redistribute it and/or modify
7 * it under the terms of the GNU General Public License version 2 as
8 * published by the Free Software Foundation.
9 *
10 * ArmarX is distributed in the hope that it will be useful, but
11 * WITHOUT ANY WARRANTY; without even the implied warranty of
12 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 * GNU General Public License for more details.
14 *
15 * You should have received a copy of the GNU General Public License
16 * along with this program. If not, see <http://www.gnu.org/licenses/>.
17 *
18 * @package VisionX::ArmarXObjects::FakePointCloudProvider
19 * @author Markus Grotz ( markus-grotz at web dot de )
20 * @date 2015
21 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22 * GNU General Public License
23 */
24
26
27// IVT
28#include <opencv2/opencv.hpp>
29
30#include <SimoxUtility/algorithm/string/string_tools.h>
31
35
37
40
44
45#include <Calibration/Calibration.h>
46#include <Image/ByteImage.h>
47#include <Image/ImageProcessor.h>
48
49
50using namespace armarx;
51using namespace pcl;
52
53namespace visionx
54{
56 std::string prefix) :
58 {
60 "pointCloudFileName",
61 "VisionX/examples/point_clouds/",
62 "The point cloud to read. If directory, all *.pcd files of this and all subdirectories "
63 "are read. \n"
64 "All point clouds are read in before the pointcloud providing starts.");
65
66 defineOptionalProperty<bool>("rewind", true, "loop through the point clouds");
68 "scaleFactor", -1.0f, "scale point cloud. only applied if value is larger than zero");
69 defineOptionalProperty<Eigen::Vector2i>("dimensions", Eigen::Vector2i(640, 480), "")
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));
80
82 "depthCameraCalibrationFile", "", "Camera depth calibration file (YAML)");
84 "RGBCameraCalibrationFile", "", "Camera RGB calibration file (YAML)");
85
87 "sourceFrameName", "", "Assume point cloud was stored in this frame.");
89 "TargetFrameName",
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.");
94
95 defineOptionalProperty<std::string>("RobotStateComponentName",
96 "RobotStateComponent",
97 "Name of the robot state component to use.");
98 defineOptionalProperty<bool>("RemoveNAN", true, "Remove NAN from point cloud");
100 "ProvidedPointCloudFormat",
101 "XYZRGBA",
102 "Format of the provided point cloud (XYZRGBA, XYZL, XYZRGBL)");
103 }
104
105 std::string
107 {
108 return "FakePointCloudProvider";
109 }
110
111 void
117
118 void
131
132 void
138
139 void
145
146 void
148 {
149 getProperty(rewind, "rewind");
150 getProperty(pointCloudFileName, "pointCloudFileName");
151 getProperty(scaleFactor, "scaleFactor");
152 getProperty(sourceFrameName, "sourceFrameName");
153 getProperty(targetFrameName, "TargetFrameName");
154 getProperty(removeNAN, "RemoveNAN");
155
156 getProperty(providedPointCloudFormat, "ProvidedPointCloudFormat");
157 ARMARX_INFO << "Providing point clouds in format " << providedPointCloudFormat << ".";
158
159 getProperty(robotStateComponentName, "RobotStateComponentName");
160 if (!robotStateComponentName.empty())
161 {
162 usingProxy(robotStateComponentName);
163 }
164
165 // Check invalid or dangerous configurations and warn early.
166 if (!(sourceFrameName.empty() && targetFrameName.empty()))
167 {
168 if (!sourceFrameName.empty() && !targetFrameName.empty() &&
169 robotStateComponentName.empty())
170 {
171 ARMARX_ERROR << "Source and target frames specified, but no RobotStateComponent is "
172 "specified.\n"
173 "No transformation will be applied.";
174 }
175 else if (sourceFrameName.empty() && !targetFrameName.empty())
176 {
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 "
180 "will be applied.)";
181 }
182 else if (!sourceFrameName.empty() && targetFrameName.empty())
183 {
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 "
187 "reference frame.";
188 }
189 }
190
191
192 if (!ArmarXDataPath::getAbsolutePath(pointCloudFileName, pointCloudFileName))
193 {
194 ARMARX_ERROR << "Could not find point cloud file in ArmarXDataPath: "
195 << pointCloudFileName;
196 }
197
198 // Loading each file
199 if (std::filesystem::is_directory(pointCloudFileName))
200 {
201 loadPointCloudDirectory(pointCloudFileName);
202 }
203 else
204 {
205 loadPointCloud(pointCloudFileName);
206 }
207
208 if (pointClouds.empty())
209 {
210 ARMARX_FATAL << "Unable to load point cloud: " << pointCloudFileName;
211 throw LocalException("Unable to load point cloud");
212 }
213
214 ARMARX_INFO << "Loaded " << pointClouds.size() << " point clouds.";
215
216
217 visionx::CameraParameters RGBCameraIntrinsics;
218 RGBCameraIntrinsics.focalLength.resize(2);
219 RGBCameraIntrinsics.principalPoint.resize(2);
220
221 if (!getProperty<std::string>("RGBCameraCalibrationFile").getValue().empty() &&
222 !loadCalibrationFile(getProperty<std::string>("RGBCameraCalibrationFile").getValue(),
223 RGBCameraIntrinsics))
224 {
225 ARMARX_WARNING << "Could not load rgb camera parameter file "
226 << getProperty<std::string>("RGBCameraCalibrationFile").getValue()
227 << " - using camera uncalibrated";
228 }
229
230 visionx::CameraParameters depthCameraIntrinsics;
231 depthCameraIntrinsics.focalLength.resize(2);
232 depthCameraIntrinsics.principalPoint.resize(2);
233
234 if (!getProperty<std::string>("depthCameraCalibrationFile").getValue().empty() &&
235 !loadCalibrationFile(getProperty<std::string>("depthCameraCalibrationFile").getValue(),
236 depthCameraIntrinsics))
237 {
238 ARMARX_WARNING << "Could not load depth camera parameter file "
239 << getProperty<std::string>("depthCameraCalibrationFile").getValue()
240 << " - using camera uncalibrated";
241 }
242
243 calibration.calibrationLeft = visionx::tools::createDefaultMonocularCalibration();
244 calibration.calibrationRight = visionx::tools::createDefaultMonocularCalibration();
245 calibration.calibrationLeft.cameraParam = RGBCameraIntrinsics;
246 calibration.calibrationRight.cameraParam = depthCameraIntrinsics;
247 }
248
249 bool
250 FakePointCloudProvider::loadPointCloud(const std::string& fileName)
251 {
252 if (simox::alg::ends_with(fileName, ".pcd") && std::filesystem::is_regular_file(fileName))
253 {
254 pcl::PCLPointCloud2Ptr cloudptr(new pcl::PCLPointCloud2());
255 ARMARX_INFO << "Loading: " << fileName;
256
257 if (io::loadPCDFile(fileName.c_str(), *cloudptr) == -1)
258 {
259 ARMARX_WARNING << "Unable to load point cloud from file " << fileName;
260 return false;
261 }
262 else
263 {
264 pointClouds.push_back(cloudptr);
265 return true;
266 }
267 }
268
269 return false;
270 }
271
272 bool
273 FakePointCloudProvider::loadPointCloudDirectory(const std::string& directoryName)
274 {
275 // reading file names
276 std::vector<std::string> fileNames;
277
278 for (std::filesystem::recursive_directory_iterator dir(directoryName), end;
279 dir != end && getState() < eManagedIceObjectExiting;
280 ++dir)
281 {
282 // Search for all *.pcd files
283 if (dir->path().extension() == ".pcd")
284 {
285 fileNames.push_back(dir->path().string());
286 }
287 }
288
289 ARMARX_INFO << "In total " << fileNames.size() << " point clouds found.";
290
291 // Sorting file names and loading them.
292 std::sort(fileNames.begin(), fileNames.end());
293
294 for (std::size_t f = 0; f < fileNames.size(); f++)
295 {
296 ARMARX_INFO << " File " << f << " / " << fileNames.size() << " is being loaded... "
297 << fileNames[f];
298 try
299 {
300 loadPointCloud(fileNames[f]);
301 }
302 catch (...)
303 {
304 ARMARX_WARNING << "Loading pointcloud '" << fileNames[f]
305 << "' failed: " << armarx::GetHandledExceptionString();
306 }
307 }
308
309 return true;
310 }
311
312 void
314 {
315 pointClouds.clear();
316 }
317
318 MetaPointCloudFormatPtr
320 {
321 MetaPointCloudFormatPtr format = new MetaPointCloudFormat();
322
323 if (providedPointCloudFormat == "XYZL")
324 {
325 format->type = PointContentType::eLabeledPoints;
326 }
327 else if (providedPointCloudFormat == "XYZRGBL")
328 {
329 format->type = PointContentType::eColoredLabeledPoints;
330 }
331 else
332 {
333 format->type = PointContentType::eColoredPoints;
334 }
335
336 format->capacity =
337 static_cast<Ice::Int>(640 * 480 * visionx::tools::getBytesPerPoint(format->type) * 50);
338 format->size = format->capacity;
339 return format;
340 }
341
342 void
344 {
345 Eigen::Vector2i dimensions = getProperty<Eigen::Vector2i>("dimensions");
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]);
351
352 counter = 0;
353 }
354
355 void
357 {
358 (void)_frameRate; // Unused.
359 if (!robotStateComponentName.empty())
360 {
361 getProxy(robotStateComponent, robotStateComponentName);
362 if (!robotStateComponent)
363 {
364 ARMARX_ERROR << "Failed to obtain robot state component.";
365 return;
366 }
367
368 localRobot = armarx::RemoteRobot::createLocalClone(robotStateComponent);
369 }
370 }
371
372 void
376
377 bool
379 {
380 pcl::PCLPointCloud2Ptr cloudptr;
381
382 {
383 std::scoped_lock lock(pointCloudMutex);
384
385 if (rewind && static_cast<size_t>(counter.load()) >= pointClouds.size())
386 {
387 counter = 0;
388 }
389
390 cloudptr = pointClouds.at(counter);
391 }
392
393 // Provide point cloud in configured format
394 if (providedPointCloudFormat == "XYZRGBA")
395 {
396 return processAndProvide<pcl::PointXYZRGBA>(cloudptr);
397 }
398 else if (providedPointCloudFormat == "XYZL")
399 {
400 return processAndProvide<pcl::PointXYZL>(cloudptr);
401 }
402 else if (providedPointCloudFormat == "XYZRGBL")
403 {
404 return processAndProvide<pcl::PointXYZRGBL>(cloudptr);
405 }
406 else
407 {
408 ARMARX_ERROR << "Could not provide point cloud, because format '"
409 << providedPointCloudFormat << "' is unknown";
410 return false;
411 }
412 }
413
414 bool
415 FakePointCloudProvider::loadCalibrationFile(std::string fileName,
416 visionx::CameraParameters& calibration)
417 {
418 ArmarXDataPath::getAbsolutePath(fileName, fileName, {}, false);
419 cv::FileStorage fs(fileName, cv::FileStorage::READ);
420
421 if (!fs.isOpened())
422 {
423 return false;
424 }
425
426 std::string cameraName = fs["camera_name"];
427 ARMARX_LOG << "loading calibration file for " << cameraName;
428
429
430 Eigen::Vector2i dimensions = getProperty<Eigen::Vector2i>("dimensions").getValue();
431 int imageWidth = fs["image_width"];
432 int imageHeight = fs["image_height"];
433
434 if (imageWidth != dimensions(0) || imageHeight != dimensions(1))
435 {
436 ARMARX_ERROR << "invalid camera size";
437 return false;
438 }
439
440 cv::Mat cameraMatrix, distCoeffs;
441
442 fs["camera_matrix"] >> cameraMatrix;
443 fs["distortion_coefficients:"] >> distCoeffs;
444
445 for (int i = 0; i < 5; i++)
446 {
447 calibration.distortion[static_cast<std::size_t>(i)] = distCoeffs.at<float>(0, i);
448 }
449
450 calibration.focalLength[0] = cameraMatrix.at<float>(0, 0);
451 calibration.focalLength[1] = cameraMatrix.at<float>(1, 1);
452
453 calibration.principalPoint[0] = cameraMatrix.at<float>(2, 1);
454 calibration.principalPoint[1] = cameraMatrix.at<float>(2, 2);
455
456 return true;
457 }
458
465
466 void
467 FakePointCloudProvider::setPointCloudFilename(const std::string& filename, const Ice::Current&)
468 {
469 std::scoped_lock lock(pointCloudMutex);
470
471 ARMARX_INFO << "Changing point cloud filename to: " << filename;
472
473 pointClouds.clear();
474 loadPointCloud(filename);
475 }
476
477 bool
479 {
480 return true;
481 }
482
483 template <typename PointT>
484 bool
485 FakePointCloudProvider::processAndProvide(const PCLPointCloud2Ptr& pointCloud)
486 {
487 using PointCloudPtrT = typename pcl::PointCloud<PointT>::Ptr;
488
489 PointCloudPtrT cloudptr(new pcl::PointCloud<PointT>());
490 pcl::fromPCLPointCloud2(*pointCloud, *cloudptr);
491
492 if (cloudptr->isOrganized())
493 {
494 processRGBImage(pointCloud);
495 }
496
497 PointCloudPtrT resultCloudPtr(new pcl::PointCloud<PointT>());
498
499 if (scaleFactor > 0)
500 {
501 Eigen::Affine3f transform(Eigen::Scaling(scaleFactor));
502 pcl::transformPointCloud(*cloudptr, *resultCloudPtr, transform);
503 }
504 else
505 {
506 // Copy initial point cloud for possibly applying a second transformation
507 pcl::copyPointCloud(*cloudptr, *resultCloudPtr);
508 }
509
510 const IceUtil::Time time = TimeUtil::GetTime();
511 resultCloudPtr->header.stamp = static_cast<uint64_t>(time.toMicroSeconds());
512
513 if (!sourceFrameName.empty() || !targetFrameName.empty())
514 {
515 if (!sourceFrameName.empty() && !targetFrameName.empty())
516 {
517 // Assume point cloud was stored in source frame and transform to target frame.
518 if (localRobot)
519 {
521 localRobot, robotStateComponent, time.toMicroSeconds());
522 FramedPointCloud framedPointCloud(resultCloudPtr, sourceFrameName);
523 framedPointCloud.changeFrame(targetFrameName, localRobot);
524 }
525 else
526 {
527 // This was already logged in the onInit().
528 // ARMARX_ERROR << "Source and target frames specified, but no RobotStateComponent available.\n"
529 // "No transformation is applied.";
530 }
531 }
532 else if (sourceFrameName.empty())
533 {
534 // This was already logged in the onInit().
535 // ARMARX_WARNING << "Target frame was specified (" << targetFrameName << "), but no source frame is specified.\n"
536 // << "Did you set the property `sourceFrameName`? (No transformation is applied.)";
537 }
538 else if (targetFrameName.empty())
539 {
540 // This was already logged in the onInit().
541 // ARMARX_INFO << "Source frame was specified (" << sourceFrameName << "), but no target frame is specified.\n"
542 // << "No transformation is applied and source frame is returned as reference frame.";
543 }
544 }
545
546
547 if (removeNAN)
548 {
549 std::vector<int> indices;
550 pcl::removeNaNFromPointCloud(*resultCloudPtr, *resultCloudPtr, indices);
551 }
552
553 ARMARX_VERBOSE << deactivateSpam() << "Providing point cloud of size "
554 << resultCloudPtr->points.size();
555 providePointCloud(resultCloudPtr);
556 provideImages(rgbImages);
557
558 if (freezeImage)
559 {
560 counter = freezeImageIdx.load();
561 }
562 else
563 {
564 ++counter;
565 }
566 return true;
567 }
568
569 bool
570 FakePointCloudProvider::processRGBImage(const PCLPointCloud2Ptr& pointCloud)
571 {
572 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudptr(new pcl::PointCloud<pcl::PointXYZRGB>());
573 pcl::fromPCLPointCloud2(*pointCloud, *cloudptr);
574
575 if (!cloudptr->isOrganized())
576 {
578 << "The point cloud is not organized, so no RGB image is generated";
579 return false;
580 }
581
582 if (static_cast<int>(cloudptr->width) != rgbImages[0]->width ||
583 static_cast<int>(cloudptr->height) != rgbImages[0]->height)
584 {
586 << "Dimensions of point cloud and image do not match, so no RGB image is generated";
587 return false;
588 }
589
590 ::ImageProcessor::Zero(rgbImages[0]);
591 const int width = static_cast<int>(cloudptr->width);
592 const int height = static_cast<int>(cloudptr->height);
593
594 for (int i = 0; i < height; i++)
595 {
596 for (int j = 0; j < width; j++)
597 {
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;
602 }
603 }
604
605 return true;
606 }
607
608 void
610 {
611 for (std::size_t i = 0; i < 1; i++)
612 {
613 delete rgbImages[i];
614 }
615
616 delete[] rgbImages;
617 }
618
619 StereoCalibration
621 {
622 return calibration;
623 }
624
625 bool
627 {
628 return true;
629 }
630
631 std::string
633 {
634 return !targetFrameName.empty() ? targetFrameName : sourceFrameName;
635 }
636
637 RemoteGui::WidgetPtr
638 FakePointCloudProvider::buildGui()
639 {
642 .cols(3)
643 .addChild(RemoteGui::makeCheckBox("rewind").value(rewind).label("rewind"), 3)
644
645 .addChild(RemoteGui::makeCheckBox("removeNAN").value(removeNAN).label("removeNAN"), 3)
646
647 .addTextLabel("scaleFactor")
649 .minmax(0, 10000)
650 .steps(10000)
651 .decimals(3),
652 2)
653
654 .addChild(
655 RemoteGui::makeCheckBox("freezeImage").value(freezeImage).label("freezeImage"))
656 .addChild(RemoteGui::makeIntSpinBox("freezeImageIdx").minmax(0, pointClouds.size() - 1))
657 .addTextLabel(" / " + std::to_string(pointClouds.size() - 1));
658 }
659
660 void
661 FakePointCloudProvider::processGui(armarx::RemoteGui::TabProxy& prx)
662 {
664 prx.receiveUpdates();
665 prx.getValue(rewind, "rewind");
666 prx.getValue(removeNAN, "removeNAN");
667 prx.getValue(scaleFactor, "scaleFactor");
668 prx.getValue(freezeImage, "freezeImage");
669 if (freezeImage)
670 {
671 prx.getValue(freezeImageIdx, "freezeImageIdx");
672 }
673 else
674 {
675 prx.setValue(counter, "freezeImageIdx");
676 }
677 prx.sendUpdates();
678 }
679} // namespace visionx
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.
Definition Component.cpp:90
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.
Definition Logging.cpp:99
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 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.
Definition TimeUtil.cpp:42
void onInitComponent() override
Pure virtual hook for the subclass.
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
MetaPointCloudFormatPtr getDefaultPointCloudFormat() override
default point cloud format used to initialize shared memory
void onConnectComponent() override
Pure virtual hook for the subclass.
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
void setPointCloudFilename(const std::string &filename, const ::Ice::Current &=Ice::emptyCurrent) override
void onExitComponent() override
Hook for subclass.
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.
Definition Logging.h:181
#define ARMARX_FATAL
The logging level for unexpected behaviour, that will lead to a seriously malfunctioning program and ...
Definition Logging.h:199
#define ARMARX_ERROR
The logging level for unexpected behaviour, that must be fixed.
Definition Logging.h:196
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
Definition Logging.h:193
#define ARMARX_LOG
Definition Logging.h:165
#define ARMARX_VERBOSE
The logging level for verbose information.
Definition Logging.h:187
std::string const GlobalFrame
Variable of the global coordinate system.
Definition FramedPose.h:65
detail::IntSpinBoxBuilder makeIntSpinBox(std::string const &name)
detail::CheckBoxBuilder makeCheckBox(std::string const &name)
Definition BoolWidgets.h:27
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...
Definition algorithm.h:351
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
size_t getBytesPerPoint(visionx::PointContentType pointContent)
MonocularCalibration createDefaultMonocularCalibration()
Creates a MonocularCalibration with all parameters set to a neutral value.
ArmarX headers.
SimpleGridLayoutBuilder & addTextLabel(std::string const &text, int colspan)
SimpleGridLayoutBuilder & addChild(WidgetPtr const &child, int colspan)
#define ARMARX_TRACE
Definition trace.h:77