27#include <pcl/common/colors.h>
28#include <pcl/filters/statistical_outlier_removal.h>
29#include <pcl/surface/convex_hull.h>
31#include <SimoxUtility/math/convert/mat4f_to_pos.h>
32#include <SimoxUtility/math/convert/mat4f_to_rpy.h>
33#include <SimoxUtility/math/convert/pos_rpy_to_mat4f.h>
34#include <VirtualRobot/CollisionDetection/CollisionModel.h>
35#include <VirtualRobot/MathTools.h>
36#include <VirtualRobot/math/Helpers.h>
58 "RobotStateComponentName",
"RobotStateComponent",
"Name of the robot state component.");
61 "sourceFrameNameAuto",
63 "If enabled, try to get and use source frame name from point cloud provider.");
65 "sourceFrameName",
"DepthCamera",
"The source frame name.");
71 "Format of the input and output point cloud (XYZRGBA, XYZL, XYZRGBL).");
79 "Enable StatisticalOutlierRemoval (pre downsampling)");
81 "StatisticalOutlierRemoval_MeanK",
83 "(pcl parameter) number of nearest neighbors to use for mean distance estimation. ");
86 "(pcl parameter) standard deviation multiplier for the "
87 "distance threshold calculation. ");
91 Eigen::Vector3f(-1000.0f, -1000.0f, 0.0f),
92 "Minimal point of cropping box.",
95 Eigen::Vector3f(4800.0f, 11500.0f, 1800.0f),
96 "Maximal point of cropping box.",
101 "Roll, Pitch and Yaw applied to the points in the croping frame",
105 "ProviderFrameTranslation", Eigen::Vector3f(0.0f, 0.0f, 0.0f),
"",
',');
107 "ProviderFrameRotation", Eigen::Vector3f(0.0f, 0.0f, 0.0f),
"",
',');
110 "croppingFrame",
"Global",
"The coordinate frame in which cropping is applied.");
114 "Discard points that appear to belong to the robot itself.");
117 "RemoteGuiName",
"RemoteGuiProvider",
"Name of the remote GUI provider");
121 "If cropping is enabled, the points outside of the area are "
122 "reported in a separate cloud");
128 return "PointCloudFilter";
134 std::unique_lock lock(parametersMutex);
135 return parameters.targetFrameName;
140 const Vector3BasePtr&
max,
141 const std::string& frame,
144 std::unique_lock lock(parametersMutex);
145 parameters.croppingEnabled =
true;
146 parameters.croppingMinPoint = Vector3Ptr::dynamicCast(
min)->toEigen();
147 parameters.croppingMaxPoint = Vector3Ptr::dynamicCast(
max)->toEigen();
148 parameters.croppingFrameName = frame;
157 getProperty(parameters.sourceFrameName,
"sourceFrameName");
158 getProperty(parameters.targetFrameName,
"targetFrameName");
160 getProperty(parameters.croppingEnabled,
"EnableCropping");
161 getProperty(parameters.croppingFrameName,
"croppingFrame");
162 getProperty(parameters.croppingMinPoint,
"minPoint");
163 getProperty(parameters.croppingMaxPoint,
"maxPoint");
166 getProperty(parameters.downsamplingEnabled,
"EnableDownsampling");
169 getProperty(parameters.statisticalOutlierRemoval.enabled,
170 "StatisticalOutlierRemoval_enabled");
171 getProperty(parameters.statisticalOutlierRemoval.meanK,
"StatisticalOutlierRemoval_MeanK");
172 getProperty(parameters.statisticalOutlierRemoval.stddevMulThresh,
173 "StatisticalOutlierRemoval_StddevMulThresh");
176 parameters.providerFrameTransformation = simox::math::pos_rpy_to_mat4f(
182 if (!robotStateComponentName.empty())
188 ARMARX_INFO <<
"No RobotStateComponent configured, not performing any point cloud "
192 getProperty(parameters.applyCollisionModelFilter,
"applyCollisionModelFilter");
193 getProperty(parameters.reportCloudOutsideOfCroppingArea,
194 "reportCloudOutsideOfCroppingArea");
195 if (parameters.applyCollisionModelFilter && robotStateComponentName.empty())
197 ARMARX_WARNING <<
"Collision model filter activated, but no RobotStateComponent "
198 "configured, deactivating collision model filtering";
199 parameters.applyCollisionModelFilter =
false;
202 debugDrawer.setLayer(
getName());
203 debugDrawer.offeringTopic(*
this);
204 debugDrawer.setEnabled(
false);
210 const std::string robotStateComponentName =
212 if (!robotStateComponentName.empty())
214 getProxy(robotStateComponent, robotStateComponentName);
216 robotStateComponent, VirtualRobot::RobotIO::RobotDescription::eStructure);
224 if (
getProperty<bool>(
"sourceFrameNameAuto") && !providerSourceFrameName.empty())
226 ARMARX_INFO <<
"Using source frame '" << providerSourceFrameName
227 <<
"' from provider '" << providerNames.front() <<
"'.";
228 this->parameters.sourceFrameName = providerSourceFrameName;
232 if (pointCloudFormat ==
"XYZRGBA")
237 else if (pointCloudFormat ==
"XYZL")
242 else if (pointCloudFormat ==
"XYZRGBL")
249 ARMARX_ERROR <<
"Could not initialize point cloud, because format '" << pointCloudFormat
251 <<
"\nKnown formats are: XYZL, XYZRGBA, XYZGBL.";
260 remoteGuiTask->start();
263 debugDrawer.getTopic(*
this);
265 debugDrawer.getTopic()->clearLayer(debugDrawer.getLayer());
276 if (pointCloudFormat ==
"XYZRGBA")
280 else if (pointCloudFormat ==
"XYZL")
284 else if (pointCloudFormat ==
"XYZRGBL")
290 ARMARX_ERROR <<
"Could not process point cloud, because format '" << pointCloudFormat
292 <<
"\nKnown formats are: XYZL, XYZRGBA, XYZRGBL.";
301 remoteGuiTask->stop();
302 remoteGuiTask =
nullptr;
306 remoteGui->removeTab(
getName());
311 toUpper(
const std::string&
string)
314 std::transform(
string.begin(),
string.end(), std::back_inserter(upper), ::toupper);
318 template <
typename Po
intT>
322 using PointCloudPtr =
typename pcl::PointCloud<PointT>::Ptr;
327 std::unique_lock lock(parametersMutex);
328 params = this->parameters;
333 PointCloudPtr tempCloud(
new pcl::PointCloud<PointT>());
342 ARMARX_VERBOSE <<
"Timeout or error while waiting for point cloud data.";
346 const uint32_t originalWidth = inputCloud.
cloud->width;
347 const uint32_t originalHeight = inputCloud.
cloud->height;
350 if (robotStateComponent)
355 long timestampMicroseconds =
static_cast<long>(inputCloud.
cloud->header.stamp);
357 (void)timestampMicroseconds;
361 if (params.statisticalOutlierRemoval.
enabled)
365 pcl::StatisticalOutlierRemoval<PointT> sor;
366 sor.setMeanK(params.statisticalOutlierRemoval.
meanK);
367 sor.setStddevMulThresh(params.statisticalOutlierRemoval.
stddevMulThresh);
369 sor.setInputCloud(inputCloud.
cloud);
371 sor.filter(*tempCloud);
372 tempCloud.swap(inputCloud.
cloud);
375 if (params.downsamplingEnabled)
379 pcl::ApproximateVoxelGrid<PointT> grid;
380 grid.setLeafSize(params.gridLeafSize, params.gridLeafSize, params.gridLeafSize);
381 grid.setInputCloud(inputCloud.
cloud);
384 grid.filter(*tempCloud);
386 tempCloud.swap(inputCloud.
cloud);
391 ARMARX_DEBUG <<
"transformBy\n" << params.providerFrameTransformation;
392 inputCloud.
transformBy(params.providerFrameTransformation);
395 if (params.croppingEnabled)
400 changePointCloudFrame(inputCloud,
"cropping", params.croppingFrameName);
402 catch (
const armarx::LocalException& e)
405 <<
"Caught armarx::LocalException (stopping processing).\n"
415 outsideCloud.
cloud->clear();
418 VirtualRobot::MathTools::rpy2eigen3f(params.croppingRPY).inverse();
419 for (
const auto& p : inputCloud.
cloud->points)
421 const Eigen::Vector3f transfed =
transform * Eigen::Vector3f{p.x, p.y, p.z};
422 if (transfed(0) >= params.croppingMinPoint(0) &&
423 transfed(0) <= params.croppingMaxPoint(0) &&
424 transfed(1) >= params.croppingMinPoint(1) &&
425 transfed(1) <= params.croppingMaxPoint(1) &&
426 transfed(2) >= params.croppingMinPoint(2) &&
427 transfed(2) <= params.croppingMaxPoint(2))
429 tempCloud->push_back(p);
431 else if (params.reportCloudOutsideOfCroppingArea)
433 outsideCloud.
cloud->push_back(p);
436 tempCloud.swap(inputCloud.
cloud);
439 if (debugDrawer.enabled())
443 aabb.col(0) = params.croppingMinPoint;
444 aabb.col(1) = params.croppingMaxPoint;
445 debugDrawer.drawBoxEdges(
"cropBox",
448 VirtualRobot::MathTools::rpy2eigen4f(params.croppingRPY));
452 debugDrawer.removeboxEdges(
"cropBox");
455 const bool collisionModelFilterEnabled =
456 params.applyCollisionModelFilter && robotStateComponent;
457 if (collisionModelFilterEnabled)
461 if (params.reportCloudOutsideOfCroppingArea)
468 PointCloudPtr collisionCloudPtr(
new pcl::PointCloud<PointT>());
470 for (VirtualRobot::CollisionModelPtr collisionModel : localRobot->getCollisionModels())
472 std::vector<Eigen::Vector3f> vertices = collisionModel->getModelVeticesGlobal();
474 pcl::PointCloud<PointT> hullCloud;
475 hullCloud.width =
static_cast<uint32_t
>(vertices.size());
476 hullCloud.height = 1;
477 hullCloud.points.resize(vertices.size());
478 for (
size_t i = 0; i < vertices.size(); ++i)
480 hullCloud.points[i].getVector3fMap() = vertices[i].cast<
float>();
483 (*collisionCloudPtr) += hullCloud;
486 pcl::ConvexHull<PointT> hull;
487 hull.setInputCloud(collisionCloudPtr);
488 hull.setDimension(3);
490 std::vector<pcl::Vertices> polygons;
491 PointCloudPtr surfaceHull(
new pcl::PointCloud<PointT>);
492 hull.reconstruct(*surfaceHull, polygons);
494 pcl::CropHull<PointT> cropHull;
496 cropHull.setHullIndices(polygons);
497 cropHull.setHullCloud(surfaceHull);
498 cropHull.setCropOutside(
false);
499 cropHull.setInputCloud(inputCloud.
cloud);
502 cropHull.filter(*tempCloud);
504 tempCloud.swap(inputCloud.
cloud);
506 if (params.reportCloudOutsideOfCroppingArea)
508 cropHull.setInputCloud(outsideCloud.
cloud);
510 cropHull.filter(*tempCloud);
511 tempCloud.swap(outsideCloud.
cloud);
519 changePointCloudFrame(inputCloud,
"target", params.targetFrameName);
520 if (params.reportCloudOutsideOfCroppingArea)
522 changePointCloudFrame(
523 outsideCloud,
"collision model filter", params.targetFrameName);
526 catch (
const armarx::LocalException& e)
529 <<
"Caught armarx::LocalException (stopping processing).\n"
535 PointCloudPtr resultCloud = inputCloud.
cloud;
538 << originalHeight <<
" --> Filtered cloud " << resultCloud->width <<
" x "
539 << resultCloud->height;
546 PointCloudFilter::drawFrame(
const FramedPose& frame,
const std::string& role)
554 template <
typename Po
intT>
557 const std::string& role,
558 const std::string& frame)
560 ARMARX_DEBUG <<
"Transform from " << pointCloud.getFrame() <<
" to " << toUpper(role)
561 <<
" (" << frame <<
")";
562 pointCloud.changeFrame(frame, localRobot);
563 drawFrame(pointCloud.getFramedPose(localRobot), role);
574 PointCloudFilter::remoteGuiCreate()
578 const auto& p = parameters;
595 .
value(p.sourceFrameName)))
601 .
value(p.targetFrameName))
606 .addChild(
makeCheckBox(
"StatisticalOutlierRemoval_enabled")
608 .
value(p.statisticalOutlierRemoval.enabled))
613 .
value(p.statisticalOutlierRemoval.meanK))
619 .
value(p.statisticalOutlierRemoval.stddevMulThresh)))
625 .
value(p.downsamplingEnabled))
631 .
value(p.gridLeafSize)))
636 .
value(p.applyCollisionModelFilter)));
641 const Eigen::Vector3f pos = simox::math::mat4f_to_pos(p.providerFrameTransformation);
642 const Eigen::Vector3f rpy = simox::math::mat4f_to_rpy(p.providerFrameTransformation);
673 .
value(p.reportCloudOutsideOfCroppingArea)
674 .
label(
"Report points outside");
678 .addOptions(localRobot->getRobotNodeNames())
679 .
value(p.croppingFrameName);
685 .
value(p.croppingRPY)
701 rootLayout.addChild(
makeGroupBox(
"CropGroup").label(
"Cropping").child(cropGroupLayout));
714 makeGroupBox(
"VisuGroup").label(
"Visualization").child(visuGroupLayout));
718 const std::string tabName =
getName();
719 remoteGui->createTab(tabName, rootLayout);
720 remoteGuiTab = armarx::RemoteGui::TabProxy(remoteGui, tabName);
724 PointCloudFilter::remoteGuiRun()
726 int cycleDurationMs = 50;
727 CycleUtil
c(cycleDurationMs);
728 while (!remoteGuiTask->isStopped())
730 remoteGuiTab.receiveUpdates();
732 remoteGuiUpdate(remoteGuiTab);
734 remoteGuiTab.sendUpdates();
735 c.waitForCycleDuration();
740 PointCloudFilter::remoteGuiUpdate(RemoteGui::TabProxy& tab)
742 using namespace armarx::RemoteGui;
745 std::unique_lock lock(parametersMutex);
748 ValueProxy<std::string> sourceFrame = tab.
getValue<std::string>(
"SourceFrame");
750 if (tab.
getValue<
bool>(
"SourceFrameAutoEnabled").get())
752 parameters.sourceFrameName = this->providerSourceFrameName;
753 sourceFrame.
set(parameters.sourceFrameName);
758 parameters.sourceFrameName = sourceFrame.
get();
762 tab.
getValue(parameters.targetFrameName,
"TargetFrame");
765 tab.
getValue(parameters.downsamplingEnabled,
"DownsamplingEnabled");
766 tab.
getValue(parameters.gridLeafSize,
"DownsamplingGridLeafSize");
767 tab.
getValue(parameters.applyCollisionModelFilter,
"CollisionModelFilterEnabled");
768 tab.
getValue(parameters.reportCloudOutsideOfCroppingArea,
769 "reportCloudOutsideOfCroppingArea");
770 tab.
getValue(parameters.statisticalOutlierRemoval.enabled,
771 "StatisticalOutlierRemoval_enabled");
772 tab.
getValue(parameters.statisticalOutlierRemoval.meanK,
773 "StatisticalOutlierRemoval_MeanK");
774 tab.
getValue(parameters.statisticalOutlierRemoval.stddevMulThresh,
775 "StatisticalOutlierRemoval_StddevMulThresh");
778 tab.
getValue(parameters.croppingEnabled,
"CropEnabled");
779 tab.
getValue(parameters.croppingFrameName,
"CropFrame");
780 tab.
getValue(parameters.croppingMinPoint,
"CropMin");
781 tab.
getValue(parameters.croppingMaxPoint,
"CropMax");
782 tab.
getValue(parameters.croppingRPY,
"CropRPY");
784 parameters.providerFrameTransformation =
785 simox::math::pos_rpy_to_mat4f(tab.
getValue<Eigen::Vector3f>(
"transform.XYC").get(),
786 tab.
getValue<Eigen::Vector3f>(
"transform.RPY").get());
790 bool visuEnabled = tab.
getValue<
bool>(
"VisuEnabled").get();
794 debugDrawer.clearLayer(
false);
797 debugDrawer.setEnabled(visuEnabled);
SpamFilterDataPtr deactivateSpam(SpamFilterDataPtr const &spamFilter, float deactivationDurationSec, const std::string &identifier, bool deactivate)
bool usingProxyFromProperty(const std::string &propertyName, const std::string &endpoints="")
Use a proxy whose name is specified by the given property.
ProxyType getProxyFromProperty(const std::string &propertyName, bool addToDependencies=false, const std::string &endpoints="", bool throwOnProxyError=true)
Get a proxy whose name is specified by the given property.
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Property< PropertyType > getProperty(const std::string &name)
void drawPose(const VisuID &id, const Eigen::Matrix4f &pose, bool ignoreLengthScale=false)
Draw a pose (with the preset scale).
bool enabled() const
Indicate whether visualization is enabled, i.e. a topic is set and enabled flag is set.
std::string getFrame() const
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)
virtual Eigen::Matrix4f toEigen() const
PropertyDefinition< EigenVectorType > & defineOptionalPropertyVector(const std::string &name, EigenVectorType defaultValue, const std::string &description="", const std::string &delimiter=" ", PropertyDefinitionBase::PropertyConstness constness=PropertyDefinitionBase::eConstant)
Define a required property for an Eigen vector type.
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)
ValueProxy< T > getValue(std::string const &name)
void set(std::atomic< T1 > const &value)
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)
A point cloud which keeps track of its reference coordinate frame and allows changing frames using ar...
void setFrameWithoutTransformation(const std::string &f)
armarx::FramedPose getFramedPose(const std::string &agentName) const
Get the current pose as FramedPose.
void transformBy(const Eigen::Matrix4f &transform)
PointCloudPtrT cloud
The point cloud.
Eigen::Matrix4f getGlobalPose(const VirtualRobot::RobotConstPtr &robot) const
Get the current global pose.
std::string getFrame() const
Get the current frame.
PointCloudFilterPropertyDefinitions(std::string prefix)
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
virtual void process() override
virtual void onExitPointCloudProcessor() override
virtual std::string getReferenceFrame(const Ice::Current &=Ice::emptyCurrent) override
virtual void onConnectPointCloudProcessor() override
virtual void onDisconnectPointCloudProcessor() override
virtual void setCroppingParameters(const armarx::Vector3BasePtr &min, const armarx::Vector3BasePtr &max, const std::string &frame, const Ice::Current &=Ice::emptyCurrent) override
virtual void onInitPointCloudProcessor() override
virtual std::string getDefaultName() const override
PointCloudProcessorPropertyDefinitions(std::string prefix)
std::string getPointCloudFrame(const std::string &providerName, const std::string &defaultFrame="")
Get the reference frame of the point cloud by given provider.
void enableResultPointClouds(std::string resultProviderName="")
Enables visualization.
int getPointClouds(const PointCloudPtrT &pointCloudPtr)
Poll PointClouds from provider.
bool waitForPointClouds(int milliseconds=1000)
Wait for new PointClouds.
void provideResultPointClouds(const PointCloudPtrT &pointClouds, std::string providerName="")
sends result PointClouds for visualization
std::vector< std::string > getPointCloudProviderNames() const
Get the names of providers for which usingPointCloudProvider() has been called.
#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.
#define ARMARX_ERROR
The logging level for unexpected behaviour, that must be fixed.
#define ARMARX_DEBUG
The logging level for output that is only interesting while debugging.
#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.
Matrix< float, 3, 2 > Matrix32f
A 3x2 matrix.
detail::IntSpinBoxBuilder makeIntSpinBox(std::string const &name)
detail::CheckBoxBuilder makeCheckBox(std::string const &name)
detail::ComboBoxBuilder makeComboBox(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::Vector3fSpinBoxesBuilder makeVector3fSpinBoxes(std::string const &name, float limpos=1000)
detail::SimpleGridLayoutBuilder makeSimpleGridLayout(std::string const &name="")
detail::GroupBoxBuilder makeGroupBox(std::string const &name="")
This file offers overloads of toIce() and fromIce() functions for STL container types.
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.
std::vector< T > max(const std::vector< T > &v1, const std::vector< T > &v2)
std::vector< T > min(const std::vector< T > &v1, const std::vector< T > &v2)
SimpleRunningTask(Ts...) -> SimpleRunningTask< std::function< void(void)> >
std::shared_ptr< Value > value()
Derived & addChild(WidgetPtr const &child)
ComboBoxBuilder & addOptions(std::vector< std::string > const &options)
ComboBoxBuilder & options(std::vector< std::string > const &options)
Derived & label(std::string const &label)
SimpleGridLayoutBuilder & addChild(WidgetPtr const &child, int colspan)
Derived & value(ValueT const &value)
Vector3fSpinBoxesBuilder & decimals(const Eigen::Vector3i decimals)