64 if (numImages < 1 || numImages > 2)
70 images =
new CByteImage*[numImages];
72 for (
int i = 0; i < numImages; i++)
77 result =
new CByteImage*[numImages];
82 ImageDimension dimension(images[0]->width, images[0]->height);
93 this->debugDrawerTopic->clearLayer(
"RGBDHandLocalizer");
99 for (
int i = 0; i < numImages; i++)
105 for (
int i = 0; i < numImages; i++)
118 ARMARX_WARNING <<
"Timeout or error while waiting for image data";
132 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr currentPointCloud(
133 new pcl::PointCloud<pcl::PointXYZRGBA>());
134 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr filteredPointCloud(
135 new pcl::PointCloud<pcl::PointXYZRGBA>());
137 std::vector<Eigen::Vector3f> medianCoordinates;
142 if (!currentPointCloud->isOrganized())
149 IplImage* iplImage = IplImageAdaptor::Adapt(images[0]);
150 cv::Mat RGBImage = cv::cvarrToMat(iplImage);
153 cv::cvtColor(RGBImage, HSVImage, cv::COLOR_RGB2HSV);
164 cv::inRange(HSVImage, minColor, maxColor, mask);
167 cv::erode(mask, mask, getStructuringElement(cv::MORPH_ELLIPSE, cv::Size(6, 6)));
168 cv::dilate(mask, mask, getStructuringElement(cv::MORPH_ELLIPSE, cv::Size(6, 6)));
170 cv::dilate(mask, mask, getStructuringElement(cv::MORPH_ELLIPSE, cv::Size(3, 3)));
171 cv::erode(mask, mask, getStructuringElement(cv::MORPH_ELLIPSE, cv::Size(3, 3)));
178 Eigen::Vector3f(0, 0, 0), markerFrameName, currentRobot->getName());
180 armarx::FramedPositionPtr::dynamicCast(kinematicMarkerPosition->clone());
181 copy->changeFrame(currentRobot, sensorFrameName);
182 Eigen::Vector3f guessMM = copy->toEigen();
183 this->cropFilter(currentPointCloud,
192 mask, filteredPointCloud, medianCoordinates);
195 Eigen::Vector3f(0, 0, 0), handFrameName, currentRobot->getName());
196 kinematicHandPosition->changeFrame(currentRobot, markerFrameName);
198 kinematicHandPosition->toEigen(), markerFrameName, currentRobot->getName());
201 offsetToHand->changeFrame(sharedRobot, sensorFrameName);
204 if (medianCoordinates.size() > 0)
206 float distance = std::numeric_limits<float>::max();
208 for (Eigen::Vector3f currentMedian : medianCoordinates)
211 currentMedian, sensorFrameName, currentRobot->getName());
213 float currentDist = (kinematicMarkerPosition->toEigen() - currentMedian).norm();
223 Eigen::Vector3f handPositionEigen = markerPosition->toEigen() + offsetToHand->toEigen();
228 int numCalibrations = 20;
229 if (calibrationCounter < numCalibrations)
232 armarx::FramedPositionPtr::dynamicCast(kinematicHandPosition->clone());
233 kinCopy->changeFrame(currentRobot, sensorFrameName);
234 Eigen::Vector3f diff = kinCopy->toEigen() - handPositionEigen;
235 this->calibrationSum = this->calibrationSum + diff;
236 calibrationCounter++;
240 handPositionEigen = handPositionEigen + (calibrationSum / numCalibrations);
246 handPositionEigen, sensorFrameName, currentRobot->getName());
250 currentRobot->getRobotNode(handFrameName)->getPoseInRootFrame());
254 handOrientation->changeFrame(currentRobot, sensorFrameName);
256 std::scoped_lock lock(positionLock);
259 realHandPosition->toEigen(),
261 currentRobot->getName());
266 this->debugDrawerTopic->setPoseVisu(
"RGBDHandLocalizer",
267 "Real_Hand_Position",
268 this->realHandPose->toGlobal(currentRobot));
269 this->debugDrawerTopic->setPoseVisu(
"RGBDHandLocalizer",
270 "Kinematic_Hand_Position",
271 handRootPose->toGlobal(currentRobot));
272 this->debugDrawerTopic->setPoseVisu(
275 currentRobot->getRobotNode(sensorFrameName)->getGlobalPose());
276 this->debugDrawerTopic->setSphereVisu(
280 armarx::DrawColor{1, 1, 0, 0.5},
282 this->debugDrawerTopic->setSphereVisu(
284 "MarkerPos_Kinematic",
285 new armarx::Vector3(kinematicMarkerPosition->toGlobalEigen(currentRobot)),
286 armarx::DrawColor{1, 0, 1, 0.5},
298 IplImage* img = cvCreateImage(cvSize(640, 480), IPL_DEPTH_8U, 3);
299 cv::Mat outMat = cv::cvarrToMat(img);
300 cv::cvtColor(mask, outMat, cv::COLOR_GRAY2RGB);
302 result[1] = images[0];
303 result[0] = IplImageAdaptor::Adapt(img);
305 cvReleaseImage(&img);
311 RGBDHandLocalizer::calcPositions(cv::Mat& binaryImage,
312 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr pointcloud,
313 std::vector<Eigen::Vector3f>& medianCoordinates)
315 medianCoordinates.clear();
317 cv::Mat labeledImage;
318 std::vector<std::vector<cv::Point>> blobList;
319 labeler.
labelBlobs(binaryImage, labeledImage, blobList);
321 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr outputCloud(
322 new pcl::PointCloud<pcl::PointXYZRGBA>());
324 for (std::vector<cv::Point> blob : blobList)
326 Eigen::Vector3f sum = Eigen::Vector3f::Zero();
328 int numberOfPixels = 0;
329 for (cv::Point picturePoint : blob)
331 pcl::PointXYZRGBA point3D = pointcloud->at(picturePoint.x, picturePoint.y);
337 outputCloud->push_back(point3D);
339 Eigen::Vector3f vector;
340 vector << point3D.x, point3D.y, point3D.z;
346 if (numberOfPixels != 0)
348 Eigen::Vector3f median = sum / numberOfPixels;
350 median = median + markerRadius * median.normalized();
351 medianCoordinates.push_back(median);
354 labeledImage.release();
360 RGBDHandLocalizer::cropFilter(pcl::PointCloud<pcl::PointXYZRGBA>::Ptr input,
361 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr output,
363 Eigen::Vector3f guessMM)
370 this->cropper.setInputCloud(input);
371 this->cropper.setKeepOrganized(
true);
372 this->cropper.setMax(Eigen::Vector4f(uncertaintyMM, uncertaintyMM, uncertaintyMM, 1));
373 this->cropper.setMin(Eigen::Vector4f(-uncertaintyMM, -uncertaintyMM, -uncertaintyMM, 1));
374 this->cropper.setTranslation(guessMM);
375 this->cropper.setRotation(Eigen::Vector3f::Zero());
376 this->cropper.filter(*output);
379 memoryx::ObjectLocalizationResultList
384 memoryx::ObjectLocalizationResultList resultList;
387 if (classNames.size() == 1)
391 if (this->realHandPose)
394 std::scoped_lock lock(positionLock);
396 memoryx::ObjectLocalizationResult localizationResult;
398 localizationResult.objectClassName =
400 localizationResult.timeStamp = this->timestamp;
401 localizationResult.orientation = this->realHandPose->getOrientation();
402 localizationResult.position = this->realHandPose->getPosition();
403 localizationResult.recognitionCertainty = 1.0;
404 Eigen::Vector3f mean = Eigen::Vector3f::Zero();
405 Eigen::Matrix3f covar = Eigen::Matrix3f::Identity() * 10000;
406 memoryx::MultivariateNormalDistributionBasePtr dummy =
408 localizationResult.positionNoise = dummy;
411 resultList.push_back(localizationResult);
412 ARMARX_INFO <<
"Hand found at: " << localizationResult.position->output();
void labelBlobs(cv::Mat &binaryImage, cv::Mat &outputImage, std::vector< std::vector< cv::Point > > &blobList)
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Property< PropertyType > getProperty(const std::string &name)
FramedDirection is a 3 dimensional direction vector with a reference frame.
The FramedPosition class.
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.
Ice::ObjectPrx getProxy(long timeoutMs=0, bool waitForScheduler=true) const
Returns the proxy of this object (optionally it waits for the proxy)
Mimics the behaviour of the VirtualRobot::Robot class while redirecting everything to an Ice proxy.
static TimestampVariantPtr nowPtr()
The MultivariateNormalDistribution class.
void enableResultImages(int numberImages, ImageDimension imageDimension, ImageType imageType, const std::string &name="")
Enables visualization.
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 provideResultImages(CByteImage **images, armarx::MetaInfoSizeBasePtr info=nullptr)
sends result images for visualization
int numberImages
Number of images.
void enableResultPointClouds(std::string resultProviderName="")
Enables visualization.
int getPointClouds(const PointCloudPtrT &pointCloudPtr)
Poll PointClouds from provider.
void usingPointCloudProvider(std::string providerName)
Registers a delayed topic subscription and a delayed provider proxy retrieval which will be available...
bool waitForPointClouds(int milliseconds=1000)
Wait for new PointClouds.
void provideResultPointClouds(const PointCloudPtrT &pointClouds, std::string providerName="")
sends result PointClouds for visualization
void onDisconnectPointCloudAndImageProcessor() override
Implement this method in the PointCloudAndImageProcessor in order to execute parts when the component...
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.
void onInitPointCloudAndImageProcessor() override
Setup the vision component.
memoryx::ObjectLocalizationResultList localizeObjectClasses(const memoryx::ObjectClassNameList &, const Ice::Current &) override
void onExitPointCloudAndImageProcessor() override
Exit the ImapeProcessor component.
#define ARMARX_INFO
The normal logging level.
#define ARMARX_FATAL
The logging level for unexpected behaviour, that will lead to a seriously malfunctioning program and ...
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
std::shared_ptr< class Robot > RobotPtr
IceInternal::Handle< FramedDirection > FramedDirectionPtr
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
IceInternal::Handle< FramedPosition > FramedPositionPtr
::IceInternal::ProxyHandle<::IceProxy::armarx::SharedRobotInterface > SharedRobotInterfacePrx
IceInternal::Handle< FramedOrientation > FramedOrientationPtr
IceInternal::Handle< FramedPose > FramedPosePtr
bool isfinite(const std::vector< T, Ts... > &v)
double distance(const Point &a, const Point &b)