32 #include <ArmarXCore/interface/observers/RequestableService.h>
35 #include <RobotAPI/interface/core/PoseBase.h>
38 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
40 #include <MemoryX/interface/core/ProbabilityMeasures.h>
45 #include <VisionX/interface/components/SimpleLocation.h>
47 #pragma GCC diagnostic push
48 #pragma GCC diagnostic ignored "-Wpedantic"
70 #include <pcl/recognition/cg/geometric_consistency.h>
71 #pragma GCC diagnostic pop
95 defineOptionalProperty<std::string>(
"agentName",
"Armar6",
"Name of the agent for which the sensor values are provided");
96 defineOptionalProperty<std::string>(
"sourceNodeName",
"DepthCamera",
"the robot node to use as source coordinate system for the captured point clouds");
97 defineOptionalProperty<std::string>(
"ObjectNameIdMap",
"spraybottle:1;screwdriver:2;torch:3;cloth:4;cutter:5;pliers:6;brush:7",
"map between object names and mask rcnn names",
armarx::PropertyDefinitionBase::eModifiable);
100 defineOptionalProperty<std::string>(
"DebugDrawerTopic",
"DebugDrawerUpdates",
"Name of the DebugDrawerTopic");
117 virtual public armarx::SimpleLocationInterface,
126 return "MaskRCNNPointCloudObjectLocalizer";
130 void getLocation(armarx::FramedOrientationBasePtr& orientation, armarx::FramedPositionBasePtr& position,
const Ice::Current&
c = ::Ice::Current())
override;
132 memoryx::ObjectLocalizationResultList
localizeObjectClasses(
const memoryx::ObjectClassNameList& objectClassNames,
const Ice::Current&
c = ::Ice::Current())
override;
167 std::mutex pointCloudMutex;
170 std::string agentName;
172 std::string providerName;
173 std::string sourceNodeName;
176 std::mutex localizeMutex;
180 armarx::RequestableServiceListenerInterfacePrx serviceTopic;