32 #include <ArmarXCore/interface/observers/RequestableService.h>
34 #include <RobotAPI/interface/core/PoseBase.h>
35 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
40 #include <VisionX/interface/components/SimpleLocation.h>
43 #include <MemoryX/interface/core/ProbabilityMeasures.h>
45 #pragma GCC diagnostic push
46 #pragma GCC diagnostic ignored "-Wpedantic"
68 #include <pcl/recognition/cg/geometric_consistency.h>
69 #pragma GCC diagnostic pop
94 defineOptionalProperty<std::string>(
97 "Name of the agent for which the sensor values are provided");
98 defineOptionalProperty<std::string>(
101 "the robot node to use as source coordinate system for the captured point clouds");
102 defineOptionalProperty<std::string>(
104 "spraybottle:1;screwdriver:2;torch:3;cloth:4;cutter:5;pliers:6;brush:7",
105 "map between object names and mask rcnn names",
107 defineOptionalProperty<uint32_t>(
"BackgroundLabelId",
109 "Label in the pointcloud for the plane or background.",
112 defineOptionalProperty<std::string>(
113 "DebugDrawerTopic",
"DebugDrawerUpdates",
"Name of the DebugDrawerTopic");
129 virtual public armarx::SimpleLocationInterface,
139 return "MaskRCNNPointCloudObjectLocalizer";
142 void getLocation(armarx::FramedOrientationBasePtr& orientation,
143 armarx::FramedPositionBasePtr& position,
144 const Ice::Current&
c = ::Ice::Current())
override;
146 memoryx::ObjectLocalizationResultList
148 const Ice::Current&
c = ::Ice::Current())
override;
183 std::mutex pointCloudMutex;
186 std::string agentName;
188 std::string providerName;
189 std::string sourceNodeName;
192 std::mutex localizeMutex;
196 armarx::RequestableServiceListenerInterfacePrx serviceTopic;