34 #include <RobotAPI/interface/core/PoseBase.h>
37 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
39 #include <MemoryX/interface/core/ProbabilityMeasures.h>
44 #include <VisionX/interface/components/SimpleLocation.h>
46 #pragma GCC diagnostic push
47 #pragma GCC diagnostic ignored "-Wpedantic"
48 #include <pcl/point_types.h>
50 #include <pcl/common/transforms.h>
52 #include <pcl/io/pcd_io.h>
54 #include <pcl/filters/filter.h>
55 #include <pcl/filters/passthrough.h>
56 #include <pcl/filters/approximate_voxel_grid.h>
58 #include <pcl/features/normal_3d.h>
59 #include <pcl/features/normal_3d_omp.h>
60 #include <pcl/features/fpfh_omp.h>
61 #include <pcl/features/shot_omp.h>
62 #include <pcl/search/kdtree.h>
63 #include <pcl/kdtree/kdtree_flann.h>
65 #include <pcl/registration/icp.h>
66 #include <pcl/registration/gicp6d.h>
68 #include <pcl/correspondence.h>
69 #include <pcl/recognition/cg/geometric_consistency.h>
70 #pragma GCC diagnostic pop
78 using PointT = pcl::PointXYZRGBA;
79 using PointL = pcl::PointXYZRGBL;
80 using PointD = pcl::FPFHSignature33;
94 defineOptionalProperty<std::string>(
"agentName",
"Armar3",
"Name of the agent for which the sensor values are provided");
95 defineOptionalProperty<std::string>(
"modelFileName",
"VisionX/examples/point_cloud_models/wateringcan2.pcd",
"path to the model to match");
96 defineOptionalProperty<std::string>(
"providerName",
"PointCloudSegmenterResult",
"name of the point cloud provider");
97 defineOptionalProperty<double>(
"recGCSize", 5.0f,
"the consensus set resolution");
98 defineOptionalProperty<int>(
"recGCThreshold", 20,
"minimum cluster size");
99 defineOptionalProperty<float>(
"leafSize", 6.0f,
"the voxel grid leaf size");
100 defineOptionalProperty<float>(
"sceneLeafSize", 3.0f,
"the voxel grid leaf size");
101 defineOptionalProperty<bool>(
"icpOnly",
true,
"");
102 defineOptionalProperty<std::string>(
"DebugDrawerTopic",
"DebugDrawerUpdates",
"Name of the DebugDrawerTopic");
103 defineOptionalProperty<std::string>(
"sourceNodeName",
armarx::GlobalFrame,
"the robot node to use as source coordinate system for the captured point clouds");
104 defineOptionalProperty<std::string>(
"objectClassName",
"wateringcan",
"Name of the objectClass this component localizes.");
121 virtual public armarx::SimpleLocationInterface,
130 return "PointCloudObjectLocalizer";
134 void getLocation(armarx::FramedOrientationBasePtr& orientation, armarx::FramedPositionBasePtr& position,
const Ice::Current&
c = Ice::emptyCurrent)
override;
136 memoryx::ObjectLocalizationResultList
localizeObjectClasses(
const memoryx::ObjectClassNameList& objectClassNames,
const Ice::Current&
c = Ice::emptyCurrent)
override;
171 std::mutex pointCloudMutex;
175 std::string agentName;
177 std::string providerName;
178 std::string sourceNodeName;
180 pcl::NormalEstimationOMP<PointT, pcl::Normal> normalEstimation;
181 pcl::FPFHEstimationOMP<PointT, pcl::Normal, PointD> featureEstimation;
184 pcl::KdTreeFLANN<PointD> matchSearchTree;
185 pcl::GeometricConsistencyGrouping<PointT, PointT> clusterer;
186 pcl::IterativeClosestPoint<PointT, PointT> icp;
190 pcl::PointCloud<PointD>::Ptr modelDescriptors;
191 pcl::PointCloud<PointT>::Ptr modelKeypoints;
193 pcl::ApproximateVoxelGrid<PointT> grid;
195 std::mutex localizeMutex;