MaskFilterPointCloudProcessor.cpp
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::MaskFilterPointCloudProcessor
17 * @author Raphael Grimm ( raphael dot grimm at kit dot edu )
18 * @date 2018
19 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20 * GNU General Public License
21 */
22
23
25
26#include <pcl/common/transforms.h>
27#include <pcl/point_types.h>
28
30
33
34#include <VisionX/interface/components/Calibration.h>
36
37static constexpr auto InMaskSuff = "_in_mask";
38static constexpr auto OutOfMaskSuff = "_out_of_mask";
39static constexpr auto OutOfMaskImgSuff = "_out_of_image";
40static constexpr auto MaskVisuSuff = "_mask_visu";
41static constexpr auto MaskAsCloudSuff = "_mask_as_cloud";
42
43#define call_template_function(F) \
44 switch (_pointCloudProviderInfo.pointCloudFormat->type) \
45 { \
46 /*case visionx::PointContentType::ePoints : F<pcl::PointXYZ>(); break; */ \
47 case visionx::PointContentType::eColoredPoints: \
48 F<pcl::PointXYZRGBA>(); \
49 break; \
50 case visionx::PointContentType::eColoredOrientedPoints: \
51 F<pcl::PointXYZRGBNormal>(); \
52 break; \
53 /*case visionx::PointContentType::eLabeledPoints : F<pcl::PointXYZL>(); break; */ \
54 case visionx::PointContentType::eColoredLabeledPoints: \
55 F<pcl::PointXYZRGBL>(); \
56 break; \
57 /*case visionx::PointContentType::eIntensity : F<pcl::PointXYZI>(); break; */ \
58 case visionx::PointContentType::eOrientedPoints: \
59 ARMARX_ERROR << "eOrientedPoints NOT HANDLED IN VISIONX"; /*no break*/ \
60 [[fallthrough]]; \
61 default: \
62 ARMARX_ERROR << "Could not process point cloud, because format '" \
63 << _pointCloudProviderInfo.pointCloudFormat->type << "' is unknown"; \
64 } \
65 do \
66 { \
67 } while (false)
68
69using namespace armarx;
70
71void
76
77void
79{
81 _debugDrawerTopicName = getProperty<std::string>("DebugDrawerTopicName");
83 _robotStateComponentName = getProperty<std::string>("RobotStateComponentName");
85
88
92
93 _redHi = static_cast<std::uint8_t>(getProperty<int>("MaskRedHi"));
94 _redLo = static_cast<std::uint8_t>(getProperty<int>("MaskRedLo"));
95 _greenHi = static_cast<std::uint8_t>(getProperty<int>("MaskGreenHi"));
96 _greenLo = static_cast<std::uint8_t>(getProperty<int>("MaskGreenLo"));
97 _blueHi = static_cast<std::uint8_t>(getProperty<int>("MaskBlueHi"));
98 _blueLo = static_cast<std::uint8_t>(getProperty<int>("MaskBlueLo"));
99
100 _pointCloudReportFrame = getProperty<std::string>("PointCloudReportFrame");
101}
102
103void
105{
106 //sync
107 {
110 VirtualRobot::RobotIO::eStructure);
111 }
112 //debug visu
113 {
115 }
116 //point cloud provider
117 {
123
127 getProperty<std::string>("PointCloudProviderReferenceFrameOverride");
128 if (_pointCloudProviderRefFrame.empty())
129 {
131 auto frameprov = visionx::ReferenceFrameInterfacePrx::checkedCast(_pointCloudProvider);
132 if (frameprov)
133 {
134 _pointCloudProviderRefFrame = frameprov->getReferenceFrame();
135 }
136 }
138 }
139 //guess some config params
140 {
141 _maskZRotation = -180;
142 if (_pointCloudProviderRefFrame.size() >= 3 &&
143 (_pointCloudProviderRefFrame.substr(_pointCloudProviderRefFrame.size() - 3) == "Sim" ||
144 _pointCloudProviderRefFrame.substr(_pointCloudProviderRefFrame.size() - 3) == "sim"))
145 {
146 _maskZRotation = -90;
147 }
148 }
149 //image provider
150 {
153 ARMARX_CHECK_EQUAL(_maskImageProviderInfo.imageFormat.type, visionx::ImageType::eRgb);
159 for (int i = 0; i < _maskImageProviderInfo.numberImages; ++i)
160 {
161 _maskImageProviderImageOwner.emplace_back(
163 _maskImageProviderImages.emplace_back(
164 static_cast<void*>(_maskImageProviderImageOwner.back()->pixels));
165 }
166
167
168 {
170 getProperty<std::string>("MaskImageProviderReferenceFrameOverride");
171 if (_maskImageProviderRefFrame.empty())
172 {
174 auto frameprov =
175 visionx::ReferenceFrameInterfacePrx::checkedCast(_maskImageProvider);
176 if (frameprov)
177 {
178 _maskImageProviderRefFrame = frameprov->getReferenceFrame();
179 }
180 }
182 }
183
184 const std::string calibProviderName = getProperty<std::string>("CalibrationProviderName");
185 if (calibProviderName.empty())
186 {
187 auto mcalibprov =
188 visionx::MonocularCalibrationCapturingProviderInterfacePrx::checkedCast(
190 auto scalibprov =
191 visionx::StereoCalibrationInterfacePrx::checkedCast(_maskImageProvider);
192 ARMARX_CHECK_EXPRESSION(mcalibprov || scalibprov);
193 if (scalibprov)
194 {
196 scalibprov->getStereoCalibration().calibrationLeft.cameraParam.focalLength.at(
197 0);
199 scalibprov->getStereoCalibration().calibrationLeft.cameraParam.focalLength.at(
200 1);
201 }
202 else if (mcalibprov)
203 {
205 mcalibprov->getCalibration().cameraParam.focalLength.at(0);
207 mcalibprov->getCalibration().cameraParam.focalLength.at(1);
208 }
209 }
210 else
211 {
212 auto calibProvider = getProxy<Ice::ObjectPrx>(calibProviderName);
213 auto mcalibprov =
214 visionx::MonocularCalibrationCapturingProviderInterfacePrx::checkedCast(
215 calibProvider);
216 auto scalibprov = visionx::StereoCalibrationInterfacePrx::checkedCast(calibProvider);
217 ARMARX_CHECK_EXPRESSION(mcalibprov || scalibprov);
218 if (scalibprov)
219 {
221 scalibprov->getStereoCalibration().calibrationLeft.cameraParam.focalLength.at(
222 0);
224 scalibprov->getStereoCalibration().calibrationLeft.cameraParam.focalLength.at(
225 1);
226 }
227 else if (mcalibprov)
228 {
230 mcalibprov->getCalibration().cameraParam.focalLength.at(0);
232 mcalibprov->getCalibration().cameraParam.focalLength.at(1);
233 }
234 }
235 }
236 //gui
237 {
240
241 auto makeSlider = [&](std::string name, int val, int min = 0, int max = 255)
242 {
243 rootLayoutBuilder.addChild(
245 .addChild(RemoteGui::makeTextLabel(name))
246 .addChild(RemoteGui::makeIntSlider(name).min(min).max(max).value(val))
247 .addChild(
248 RemoteGui::makeIntSpinBox(name + "_spin").min(min).max(max).value(val)));
249 };
250 auto makeFSlider = [&](std::string name, int min, int max, float val)
251 {
252 rootLayoutBuilder.addChild(
254 .addChild(RemoteGui::makeTextLabel(name))
255 .addChild(RemoteGui::makeFloatSlider(name).min(min).max(max).value(val).steps(
256 static_cast<int>(max - min)))
257 .addChild(
258 RemoteGui::makeFloatSpinBox(name + "_spin").min(min).max(max).value(val)));
259 };
260
261 // ValueProxy<float> x1Slider = makeSlider ...
262 makeSlider("red lo", _redLo);
263 makeSlider("red hi", _redHi);
264 makeSlider("green lo", _greenLo);
265 makeSlider("green hi", _greenHi);
266 makeSlider("blue lo", _blueLo);
267 makeSlider("blue hi", _blueHi);
268
269
270 rootLayoutBuilder.addChild(
272 .addChild(RemoteGui::makeTextLabel("mask match one color range"))
274 .addChild(RemoteGui::makeTextLabel("flip x"))
275 .addChild(RemoteGui::makeCheckBox("flip x").value(_flipX))
276 .addChild(RemoteGui::makeTextLabel("flip y"))
277 .addChild(RemoteGui::makeCheckBox("flip y").value(_flipY)));
278
279 rootLayoutBuilder.addChild(
281 .addChild(RemoteGui::makeTextLabel("offset x"))
282 .addChild(
283 RemoteGui::makeIntSpinBox("offset x").min(-2000).max(2000).value(_offsetX))
284 .addChild(RemoteGui::makeTextLabel("offset y"))
285 .addChild(
286 RemoteGui::makeIntSpinBox("offset y").min(-2000).max(2000).value(_offsetY)));
287
289 const int focaladjrange = 10000;
290 makeFSlider(
291 "focal length adjustment", -focaladjrange, focaladjrange, _focalLengthAdjustment);
292 makeFSlider("Mask z rotation", -180, 180, _maskZRotation);
293
294 rootLayoutBuilder.addChild(RemoteGui::makeHBoxLayout()
295 .addChild(RemoteGui::makeTextLabel("report frame"))
296 .addChild(RemoteGui::makeComboBox("report frame")
297 .options(_localRobot->getRobotNodeNames())
298 .addOptions({"Global", "root"})
299 .value("root")));
300
301
302 auto checkboxBuilder = RemoteGui::makeCheckBox("Sync using timestamp");
303 checkboxBuilder.value(_syncRobotWithTimestamp);
304 checkboxBuilder.widget().label = "Sync using timestamp";
305 rootLayoutBuilder.addChild(checkboxBuilder);
306 rootLayoutBuilder.addChild(new RemoteGui::VSpacer());
307
309 [this]()
310 {
311 _guiTab.receiveUpdates();
312
313 _redLo = static_cast<std::uint8_t>(_guiTab.getValue<int>("red lo").get());
314 _guiTab.getValue<int>("red lo_spin").set(_redLo);
315
316 _redHi = static_cast<std::uint8_t>(_guiTab.getValue<int>("red hi").get());
317 _guiTab.getValue<int>("red hi_spin").set(_redHi);
318
319 _greenLo = static_cast<std::uint8_t>(_guiTab.getValue<int>("green lo").get());
320 _guiTab.getValue<int>("green lo_spin").set(_greenLo);
321
322 _greenHi = static_cast<std::uint8_t>(_guiTab.getValue<int>("green hi").get());
323 _guiTab.getValue<int>("green hi_spin").set(_greenHi);
324
325 _blueLo = static_cast<std::uint8_t>(_guiTab.getValue<int>("blue lo").get());
326 _guiTab.getValue<int>("blue lo_spin").set(_blueLo);
327
328 _blueHi = static_cast<std::uint8_t>(_guiTab.getValue<int>("blue hi").get());
329 _guiTab.getValue<int>("blue hi_spin").set(_blueHi);
330
331 _offsetX = _guiTab.getValue<int>("offset x").get();
332 _offsetY = _guiTab.getValue<int>("offset y").get();
333
334 _maskZRotation = _guiTab.getValue<float>("Mask z rotation").get();
335 _guiTab.getValue<float>("Mask z rotation_spin").set(_maskZRotation);
336
337 _focalLengthAdjustment = _guiTab.getValue<float>("focal length adjustment").get();
338 _guiTab.getValue<float>("focal length adjustment_spin").set(_focalLengthAdjustment);
339
340 _flipX = _guiTab.getValue<bool>("flip x").get();
341 _flipY = _guiTab.getValue<bool>("flip y").get();
342 _maskMatchOneRangeInsteadOfAll = _guiTab.getValue<bool>("ormode").get();
343
344 _guiTab.sendUpdates();
345
346 std::lock_guard<std::mutex> guard{_pointCloudReportFrameMutex};
347 _pointCloudReportFrame = _guiTab.getValue<std::string>("report frame").get();
348 _guiParamUpdated = true;
349 _syncRobotWithTimestamp = _guiTab.getValue<bool>("Sync using timestamp").get();
350 },
351 10);
352
353 RemoteGui::WidgetPtr rootLayout = rootLayoutBuilder;
354
355 _remoteGui->createTab(getName(), rootLayout);
357
358 _guiTask->start();
359 }
360}
361
362void
369
370std::pair<float, float>
376
377std::array<float, 3>
378MaskFilterPointCloudProcessor::uvz2xyz(int u, int v, float z, float /*fx*/, float /*fy*/) const
379{
380 const float alpha = -_maskZRotation / 180.0 * M_PI;
381 const float s = std::sin(alpha);
382 const float c = std::cos(alpha);
383
384 const auto width = _maskImageProviderInfo.imageFormat.dimension.width;
385 const auto height = _maskImageProviderInfo.imageFormat.dimension.height;
386
387 //middle to 0/0 and add offset
388 const float ushifted = u - +width / 2.f + _offsetX;
389 const float vshifted = v - +height / 2.f + _offsetY;
390
391 const float rotatedU = c * ushifted + s * vshifted;
392 const float rotatedV = -s * ushifted + c * vshifted;
393
394 const float x = (_flipX ? 1 : -1) * rotatedU;
395 const float y = (_flipY ? 1 : -1) * rotatedV;
396
397 return {x, y, z};
398}
399
400std::array<std::int64_t, 2>
401MaskFilterPointCloudProcessor::xyz2uv(float x, float y, float z, float fx, float fy) const
402{
403 const float alpha = _maskZRotation / 180.0 * M_PI;
404 const float s = std::sin(alpha);
405 const float c = std::cos(alpha);
406
407 //transform to uv
408 const float u = (_flipX ? 1 : -1) * (x / z) * fx;
409 const float v = (_flipY ? 1 : -1) * (y / z) * fy;
410
411 const float rotatedU = c * u + -s * v;
412 const float rotatedV = s * u + c * v;
413
414 const auto width = _maskImageProviderInfo.imageFormat.dimension.width;
415 const auto height = _maskImageProviderInfo.imageFormat.dimension.height;
416
417 // 0/0 is currently the middle of the image -> shift it and sub offsets
418 const std::int64_t imgx = static_cast<std::int64_t>(rotatedU + width / 2.f) - _offsetX;
419 const std::int64_t imgy = static_cast<std::int64_t>(rotatedV + height / 2.f) - _offsetY;
420
421 return {imgx, imgy};
422}
423
430
431template <typename PointType>
432void
434{
435 //something new to do?
436 {
438 {
439 _newPointCloud = true;
440 }
442 {
443 _newMaskImage = true;
444 }
445
447 {
448 return;
449 }
450 _newMaskImage = false;
451 _newPointCloud = false;
452 }
453
454 std::lock_guard<std::mutex> guard{_cloudMutex};
455
456 //working data
457 typename pcl::PointCloud<PointType>::Ptr inputCloud(new pcl::PointCloud<PointType>());
458 //get new data
459 {
461
463
465
467 {
469 _localRobot, _robotStateComponent, format->timeProvided);
470 }
471 else
472 {
474 }
475 }
476 Eigen::Matrix4f pclInCamFrame = Eigen::Matrix4f::Identity();
477 Eigen::Matrix4f camInReportFrame = Eigen::Matrix4f::Identity();
478 {
479 {
480 std::lock_guard<std::mutex> guard{_pointCloudReportFrameMutex};
481 if (_pointCloudReportFrame == "root")
482 {
483 _pointCloudReportFrame = _localRobot->getRootNode()->getName();
484 }
485 FramedPose fp{
486 Eigen::Matrix4f::Identity(), _maskImageProviderRefFrame, _localRobot->getName()};
488 camInReportFrame = fp.toEigen();
489 }
490 {
491 FramedPose fp{
492 Eigen::Matrix4f::Identity(), _pointCloudProviderRefFrame, _localRobot->getName()};
494 pclInCamFrame = fp.toEigen();
495 }
496 }
497
498 {
499 typename pcl::PointCloud<PointType>::Ptr tmpCloud(new pcl::PointCloud<PointType>());
500 pcl::transformPointCloud(*inputCloud, *tmpCloud, pclInCamFrame);
501 tmpCloud.swap(inputCloud);
502 }
503
504 const auto r = std::minmax(_redLo, _redHi);
505 const auto g = std::minmax(_greenLo, _greenHi);
506 const auto b = std::minmax(_blueLo, _blueHi);
507 const CByteImage& img = *_maskImageProviderImageOwner.front();
508 std::uint64_t pointsInImage = 0;
509 std::uint64_t pointsOutOfImage = 0;
510 _maskedCloud.reset(new pcl::PointCloud<pcl::PointXYZRGBA>());
511 _inputCloud.reset(new pcl::PointCloud<pcl::PointXYZRGBA>());
512 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr unmaskedCloud(new pcl::PointCloud<pcl::PointXYZRGBA>());
513 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr outOfImageCloud(
514 new pcl::PointCloud<pcl::PointXYZRGBA>());
515 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr visuCloud(new pcl::PointCloud<pcl::PointXYZRGBA>());
516
517 float fx, fy;
518 std::tie(fx, fy) = maskImageProviderFocalLength();
519 for (const auto& point : inputCloud->points)
520 {
521 pcl::PointXYZRGBA p;
522 p.x = point.x;
523 p.y = point.y;
524 p.z = point.z;
525 p.a = 255;
526
527 static_assert(std::is_same<PointType, pcl::PointXYZRGBA>::value ||
528 std::is_same<PointType, pcl::PointXYZRGB>::value ||
529 std::is_same<PointType, pcl::PointXYZRGBL>::value ||
530 std::is_same<PointType, pcl::PointXYZRGBNormal>::value,
531 "");
532 // if constexpr(
533 // std::is_same_v<PointType, pcl::PointXYZRGBA> ||
534 // std::is_same_v<PointType, pcl::PointXYZRGB> ||
535 // std::is_same_v<PointType, pcl::PointXYZRGBL> ||
536 // std::is_same_v<PointType, pcl::PointXYZRGBNormal>
537 // )
538 {
539 p.r = point.r;
540 p.g = point.g;
541 p.b = point.b;
542 }
543 // else
544 // {
545 // p.r = p.g = p.b = 0;
546 // }
547 const auto uv = xyz2uv(p.x, p.y, p.z, fx, fy);
548 const std::int64_t u = uv.at(0);
549 const std::int64_t v = uv.at(1);
550 if (u < 0 || u >= img.width || v < 0 || v >= img.height)
551 {
552 ++pointsOutOfImage;
553 _inputCloud->push_back(p);
554 p.r = p.b = p.a = 255;
555 p.g = 0;
556 outOfImageCloud->push_back(p);
557 continue; // point out of image
558 }
559 ++pointsInImage;
560
561 p.r = img.pixels[(u + v * img.width) * 3 + 0];
562 p.g = img.pixels[(u + v * img.width) * 3 + 1];
563 p.b = img.pixels[(u + v * img.width) * 3 + 2];
564
565 _inputCloud->push_back(p);
566
567 const bool okR = r.first <= p.r && r.second >= p.r;
568 const bool okG = g.first <= p.g && g.second >= p.g;
569 const bool okB = b.first <= p.b && b.second >= p.b;
570
571 if (_maskMatchOneRangeInsteadOfAll ? okR || okG || okB : okR && okG && okB)
572 {
573 _maskedCloud->push_back(p);
574 }
575 else
576 {
577 unmaskedCloud->push_back(p);
578 }
579 visuCloud->push_back(p);
580 }
581
582 {
583 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr tmpCloud(new pcl::PointCloud<pcl::PointXYZRGBA>());
584
585 pcl::transformPointCloud(*_maskedCloud, *tmpCloud, camInReportFrame);
586 provideResultPointClouds(tmpCloud, getName() + InMaskSuff);
587
588 pcl::transformPointCloud(*unmaskedCloud, *tmpCloud, camInReportFrame);
589 provideResultPointClouds(tmpCloud, getName() + OutOfMaskSuff);
590
591 pcl::transformPointCloud(*outOfImageCloud, *tmpCloud, camInReportFrame);
592 provideResultPointClouds(tmpCloud, getName() + OutOfMaskImgSuff);
593
594 pcl::transformPointCloud(*visuCloud, *tmpCloud, camInReportFrame);
595 provideResultPointClouds(tmpCloud, getName() + MaskVisuSuff);
596
597 //reuse visuCloud
598 visuCloud->clear();
599 for (int u = 0; u < img.width; ++u)
600 {
601 for (int v = 0; v < img.height; ++v)
602 {
603 //visu the mastk at the image plane
604 auto xyz = uvz2xyz(u, v, (fx + fy) / 2, fx, fy);
605 pcl::PointXYZRGBA p;
606 p.x = xyz.at(0);
607 p.y = xyz.at(1);
608 p.z = xyz.at(2);
609 p.a = 255;
610 p.r = img.pixels[(u + v * img.width) * 3 + 0];
611 p.g = img.pixels[(u + v * img.width) * 3 + 1];
612 p.b = img.pixels[(u + v * img.width) * 3 + 2];
613 visuCloud->push_back(p);
614 }
615 }
616 pcl::transformPointCloud(*visuCloud, *tmpCloud, camInReportFrame);
617 provideResultPointClouds(tmpCloud, getName() + MaskAsCloudSuff);
618 }
619}
#define call_template_function(F)
#define M_PI
Definition MathTools.h:17
#define VAROUT(x)
constexpr T c
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition Component.cpp:90
Property< PropertyType > getProperty(const std::string &name)
The FramedPose class.
Definition FramedPose.h:281
void changeFrame(const SharedRobotInterfacePrx &referenceRobot, const std::string &newFrame)
void offeringTopic(const std::string &name)
Registers a topic for retrival after initialization.
TopicProxyType getTopic(const std::string &name)
Returns a proxy of the specified topic.
bool usingProxy(const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list.
std::string getName() const
Retrieve name of object.
Ice::ObjectPrx getProxy(long timeoutMs=0, bool waitForScheduler=true) const
Returns the proxy of this object (optionally it waits for the proxy)
visionx::PointCloudProviderInterfacePrx _pointCloudProvider
visionx::ImageProviderInterfacePrx _maskImageProvider
void onDisconnectPointCloudAndImageProcessor() override
Implement this method in the PointCloudAndImageProcessor in order to execute parts when the component...
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr _maskedCloud
void onConnectPointCloudAndImageProcessor() override
Implement this method in your PointCloudAndImageProcessor in order execute parts when the component i...
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
void process() override
Process the vision component.
std::array< float, 3 > uvz2xyz(int u, int v, float z, float fx, float fy) const
std::vector< visionx::CByteImageUPtr > _maskImageProviderImageOwner
RobotStateComponentInterfacePrx _robotStateComponent
void onInitPointCloudAndImageProcessor() override
Setup the vision component.
visionx::PointCloudProviderInfo _pointCloudProviderInfo
std::pair< float, float > maskImageProviderFocalLength() const
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr _inputCloud
std::array< std::int64_t, 2 > xyz2uv(float x, float y, float z, float fx, float fy) const
static VirtualRobot::RobotPtr createLocalCloneFromFile(RobotStateComponentInterfacePrx robotStatePrx, VirtualRobot::RobotIO::RobotDescription loadMode=VirtualRobot::RobotIO::eFull)
This is a convenience function for createLocalClone, which automatically gets the filename from the R...
static bool synchronizeLocalClone(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx)
static bool synchronizeLocalCloneToTimestamp(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx, Ice::Long timestamp)
Synchronizes a local robot to a robot state at timestamp.
void usingImageProvider(std::string name)
Registers a delayed topic subscription and a delayed provider proxy retrieval which all will be avail...
bool waitForImages(int milliseconds=1000)
Wait for new images.
ImageProviderInfo getImageProvider(std::string name, ImageType destinationImageType=eRgb, bool waitForProxy=false)
Select an ImageProvider.
int getImages(CByteImage **ppImages)
Poll images from provider.
void enableResultPointClouds(std::string resultProviderName="")
Enables visualization.
int getPointClouds(const PointCloudPtrT &pointCloudPtr)
Poll PointClouds from provider.
MetaPointCloudFormatPtr getPointCloudFormat(std::string providerName)
void usingPointCloudProvider(std::string providerName)
Registers a delayed topic subscription and a delayed provider proxy retrieval which will be available...
PointCloudProviderInfo getPointCloudProvider(std::string name, bool waitForProxy=false)
Select an PointCloudProvider.
bool waitForPointClouds(int milliseconds=1000)
Wait for new PointClouds.
void provideResultPointClouds(const PointCloudPtrT &pointClouds, std::string providerName="")
sends result PointClouds for visualization
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
#define ARMARX_CHECK_GREATER_EQUAL(lhs, rhs)
This macro evaluates whether lhs is greater or equal (>=) rhs and if it turns out to be false it will...
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
#define ARMARX_INFO
The normal logging level.
Definition Logging.h:181
detail::IntSpinBoxBuilder makeIntSpinBox(std::string const &name)
detail::CheckBoxBuilder makeCheckBox(std::string const &name)
Definition BoolWidgets.h:27
detail::ComboBoxBuilder makeComboBox(std::string const &name)
detail::FloatSliderBuilder makeFloatSlider(std::string const &name)
detail::VBoxLayoutBuilder makeVBoxLayout(std::string const &name="")
detail::FloatSpinBoxBuilder makeFloatSpinBox(std::string const &name)
detail::LabelBuilder makeTextLabel(std::string const &text)
detail::HBoxLayoutBuilder makeHBoxLayout(std::string const &name="")
detail::IntSliderBuilder makeIntSlider(std::string const &name)
This file offers overloads of toIce() and fromIce() functions for STL container types.
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
std::vector< T > max(const std::vector< T > &v1, const std::vector< T > &v2)
SimplePeriodicTask(Ts...) -> SimplePeriodicTask< std::function< void(void)> >
std::vector< T > min(const std::vector< T > &v1, const std::vector< T > &v2)
CByteImage * createByteImage(const ImageFormatInfo &imageFormat, const ImageType imageType)
Creates a ByteImage for the destination type specified in the given imageProviderInfo.
Derived & addChild(WidgetPtr const &child)