26 #include <VisionX/interface/components/Calibration.h>
37 #include <QFileDialog>
39 #include <QMessageBox>
41 #include <pcl/common/transforms.h>
42 #include <pcl/filters/filter.h>
43 #include <pcl/filters/passthrough.h>
75 dialog->addProxyFinder<visionx::PointCloudProviderInterfacePrx>({
"PointCloudProvider",
"PointCloudProvider",
"*"});
78 return qobject_cast<SimpleConfigDialog*>(dialog);
83 providerName = dialog->getProxyName(
"PointCloudProvider");
84 robotStateComponentName = dialog->getProxyName(
"RobotStateComponent");
91 QMetaObject::invokeMethod(
this,
"initUI");
96 void HandEyeCalibrationWidgetController::initUI()
99 widget.lineEdit_file->setText(QDir::currentPath() +
"/" +
defaultFileName);
103 void HandEyeCalibrationWidgetController::saveDatapoint()
105 if (activeEndEffector)
108 entry.
Add(
"EndEffector", activeEndEffector->getName());
110 std::map<std::string, float> config = localRobot->getConfig()->getRobotNodeJointValueMap();
111 entry.
Add(
"RobotConfig", config);
116 std::string fileName = widget.lineEdit_file->text().toStdString();
122 tr(
"HandEyeCalibration"),
123 tr(
"Datapoint successful written to file."));
127 void HandEyeCalibrationWidgetController::selectFile()
129 QString fileName = QFileDialog::getOpenFileName(
getWidget(),
130 tr(
"Select file for saving data points"),
132 tr(
"JSON-File (*.json);; All Files (*)"));
133 if (!fileName.isEmpty())
135 widget.lineEdit_file->setText(fileName);
139 VirtualRobot::RobotPtr HandEyeCalibrationWidgetController::getEEFRobot(VirtualRobot::EndEffectorPtr eef)
const
141 if (eef && robotEEFMap.count(eef->getName()) == 1)
143 return robotEEFMap.at(eef->getName()).first;
148 Eigen::Matrix4f HandEyeCalibrationWidgetController::getOffsetMatrixForEEF(
const VirtualRobot::EndEffectorPtr eef)
const
150 if (eef && robotEEFMap.count(eef->getName()) == 1)
152 return robotEEFMap.at(eef->getName()).second;
157 void HandEyeCalibrationWidgetController::setOffsetMatrixForEEF(
const VirtualRobot::EndEffectorPtr eef,
const Eigen::Matrix4f& offset)
159 if (eef && robotEEFMap.count(eef->getName()) == 1)
161 robotEEFMap.at(eef->getName()).second = offset;
169 robotStateComponentPrx = getProxy<RobotStateComponentInterfacePrx>(robotStateComponentName,
true);
173 referenceFrame = getProviderFrame();
174 providerBuffer.reset(
new pcl::PointCloud<PointT>());
176 localRobot = loadRobotFromFile();
183 ARMARX_ERROR <<
"Exception while creating local clone of robot in onConnectPointCLoudProcessor()";
192 QMetaObject::invokeMethod(
this,
"connectQt", Qt::BlockingQueuedConnection);
196 connect(widget.comboBox_endEffectorSelection, SIGNAL(currentIndexChanged(QString)),
this, SLOT(activeEndEffectorChanged(QString)));
197 connect(widget.horizontalSlider_croppingBox, SIGNAL(valueChanged(
int)),
this, SLOT(slider_croppingRange_changed(
int)));
198 connect(widget.checkBox_croppingActive, SIGNAL(stateChanged(
int)),
this, SLOT(cb_croppingActive_changed(
int)));
200 connect(widget.checkBox_offsetInverted, SIGNAL(toggled(
bool)),
this, SLOT(cb_inverted_changed(
bool)));
201 connect(widget.pushButton_copyToClipboard, SIGNAL(clicked()),
this, SLOT(btn_copyToClipboard_pressed()));
202 connect(widget.pushButton_resetEndeffector, SIGNAL(clicked()),
this, SLOT(btn_resetToModel_pressed()));
204 connect(widget.doubleSpinBox_camera_x, SIGNAL(valueChanged(
double)),
this, SLOT(cameraNodeTransformationChanged(
double)));
205 connect(widget.doubleSpinBox_camera_y, SIGNAL(valueChanged(
double)),
this, SLOT(cameraNodeTransformationChanged(
double)));
206 connect(widget.doubleSpinBox_camera_z, SIGNAL(valueChanged(
double)),
this, SLOT(cameraNodeTransformationChanged(
double)));
207 connect(widget.doubleSpinBox_camera_roll, SIGNAL(valueChanged(
double)),
this, SLOT(cameraNodeTransformationChanged(
double)));
208 connect(widget.doubleSpinBox_camera_pitch, SIGNAL(valueChanged(
double)),
this, SLOT(cameraNodeTransformationChanged(
double)));
209 connect(widget.doubleSpinBox_camera_yaw, SIGNAL(valueChanged(
double)),
this, SLOT(cameraNodeTransformationChanged(
double)));
211 connect(widget.pushButton_backgroundColor, SIGNAL(clicked()),
this, SLOT(btn_backgroundColor_pressed()));
212 connect(widget.pushButton_pointcloudColor, SIGNAL(clicked()),
this, SLOT(btn_pointCloudColor_pressed()));
213 connect(widget.spinBox_pointSize, SIGNAL(valueChanged(
int)),
this, SLOT(sB_pointSize_changed(
int)));
215 connect(widget.pushButton_changeFile, SIGNAL(clicked()),
this, SLOT(selectFile()));
216 connect(widget.pushButton_saveDatapoint, SIGNAL(clicked()),
this, SLOT(saveDatapoint()));
218 taskEEFManipulation->start();
219 taskLocalRobotUpdate->start();
223 void HandEyeCalibrationWidgetController::connectQt()
226 widget.displayWidget->getDisplay()->getRootNode()->addChild(pointCloudVisu);
229 widget.displayWidget->getDisplay()->getRootNode()->addChild((SoNode*)manipulatorVisu);
231 widget.displayWidget->getDisplay()->cameraViewAll();
235 setupEndEffectorSelection(localRobot);
241 setupCameraNodeSlider(pointcloudRobot);
242 disableGuiElements();
249 taskEEFManipulation->stop();
250 taskLocalRobotUpdate->stop();
253 QMetaObject::invokeMethod(
this,
"disconnectQt");
256 pointcloudRobot.reset();
257 activeEndEffector.reset();
258 providerBuffer.reset();
261 void HandEyeCalibrationWidgetController::disconnectQt()
263 disableGuiElements();
265 widget.comboBox_endEffectorSelection->clear();
266 manipulatorVisu->removeVisualization();
267 pointCloudVisu->removeAllChildren();
268 widget.displayWidget->getDisplay()->getRootNode()->removeAllChildren();
271 QObject::disconnect(widget.comboBox_endEffectorSelection, 0, 0, 0);
290 std::vector<VirtualRobot::EndEffectorPtr> endEffectors;
291 robot->getEndEffectors(endEffectors);
292 for (VirtualRobot::EndEffectorPtr e : endEffectors)
294 widget.comboBox_endEffectorSelection->addItem(QString::fromStdString(e->getName()));
296 r->setGlobalPoseForRobotNode(r->getRobotNode(e->getTcp()->getName()), e->getTcp()->getGlobalPose());
299 widget.comboBox_endEffectorSelection->setCurrentIndex(-1);
302 bool HandEyeCalibrationWidgetController::findStringIC(
const std::string& strHaystack,
const std::string& strNeedle)
const
304 auto it = std::search(
305 strHaystack.begin(), strHaystack.end(),
306 strNeedle.begin(), strNeedle.end(),
307 [](
char ch1,
char ch2)
309 return std::toupper(ch1) == std::toupper(ch2);
312 return (it != strHaystack.end());
319 ARMARX_CHECK_EXPRESSION(robot->hasRobotNode(referenceFrame)) <<
"Robot " + robot->getName() +
" does not have node with name " + referenceFrame;
320 widget.label_cameraNodeName->setText(QString::fromStdString((referenceFrame)));
322 cameraNode = robot->getRobotNode(referenceFrame);
323 auto trans = VirtualRobot::MathTools::eigen4f2posrpy(cameraNode->getLocalTransformation());
325 widget.doubleSpinBox_camera_x->setValue(trans(0));
326 widget.doubleSpinBox_camera_y->setValue(trans(1));
327 widget.doubleSpinBox_camera_z->setValue(trans(2));
328 widget.doubleSpinBox_camera_roll->setValue(VirtualRobot::MathTools::rad2deg(trans(3)));
329 widget.doubleSpinBox_camera_pitch->setValue(VirtualRobot::MathTools::rad2deg(trans(4)));
330 widget.doubleSpinBox_camera_yaw->setValue(VirtualRobot::MathTools::rad2deg(trans(5)));
336 Ice::StringSeq includePaths;
340 Ice::StringSeq packages = robotStateComponentPrx->getArmarXPackages();
343 for (
const std::string& projectName : packages)
345 if (projectName.empty())
351 auto pathsString =
project.getDataDir();
352 Ice::StringSeq projectIncludePaths =
armarx::Split(pathsString,
";,",
true,
true);
353 includePaths.insert(includePaths.end(), projectIncludePaths.begin(), projectIncludePaths.end());
358 ARMARX_ERROR <<
"Unable to retrieve robot filename." << std::endl;
364 std::string rfile = robotStateComponentPrx->getRobotFilename();
366 return VirtualRobot::RobotIO::loadRobot(rfile);
370 ARMARX_ERROR <<
"Unable to load robot from file" << std::endl;
375 std::string HandEyeCalibrationWidgetController::getProviderFrame()
const
377 std::string frame =
"Global";
380 visionx::ReferenceFrameInterfacePrx refFramePrx = visionx::ReferenceFrameInterfacePrx::checkedCast(providerInfo.
proxy);
383 frame = refFramePrx->getReferenceFrame();
393 std::string HandEyeCalibrationWidgetController::formatTransformationMatrix(
Eigen::Matrix4f mat,
int decimalPlacesOrientation,
int decimalPlacesPosition)
const
395 std::stringstream ss;
396 ss.imbue(std::locale::classic());
400 for (
int i = 0; i < 3; i++)
402 float x0 = mat(i, 0);
403 float x1 = mat(i, 1);
404 float x2 = mat(i, 2);
405 ss << std::setprecision(decimalPlacesOrientation);
406 if (!std::signbit(x0))
411 if (!std::signbit(x1))
416 if (!std::signbit(x2))
422 ss << std::setprecision(decimalPlacesPosition);
423 if (!std::signbit(mat(i, 3)))
433 void HandEyeCalibrationWidgetController::enableGuiElements()
435 widget.horizontalSlider_croppingBox->setEnabled(
true);
436 widget.horizontalSlider_x->setEnabled(
true);
437 widget.horizontalSlider_y->setEnabled(
true);
438 widget.horizontalSlider_z->setEnabled(
true);
439 widget.checkBox_croppingActive->setEnabled(
true);
440 widget.checkBox_offsetInverted->setEnabled(
true);
441 widget.pushButton_copyToClipboard->setEnabled(
true);
442 widget.pushButton_resetEndeffector->setEnabled(
true);
443 widget.pushButton_pointcloudColor->setEnabled(
true);
444 widget.pushButton_backgroundColor->setEnabled(
true);
445 widget.spinBox_pointSize->setEnabled(
true);
446 widget.pushButton_changeFile->setEnabled(
true);
447 widget.pushButton_saveDatapoint->setEnabled(
true);
448 widget.lineEdit_file->setEnabled(
true);
450 widget.doubleSpinBox_camera_x->setEnabled(
true);
451 widget.doubleSpinBox_camera_y->setEnabled(
true);
452 widget.doubleSpinBox_camera_z->setEnabled(
true);
453 widget.doubleSpinBox_camera_roll->setEnabled(
true);
454 widget.doubleSpinBox_camera_pitch->setEnabled(
true);
455 widget.doubleSpinBox_camera_yaw->setEnabled(
true);
457 widget.label_offsetMatrix->setText(QString(
"No Endeffector selected"));
458 widget.label_offsetMatrix->setStyleSheet(
"QLabel { color : black; }");
460 showPointCloud =
true;
463 void HandEyeCalibrationWidgetController::disableGuiElements()
465 widget.horizontalSlider_croppingBox->setEnabled(
false);
466 widget.horizontalSlider_x->setEnabled(
false);
467 widget.horizontalSlider_y->setEnabled(
false);
468 widget.horizontalSlider_z->setEnabled(
false);
469 widget.checkBox_croppingActive->setEnabled(
false);
470 widget.checkBox_offsetInverted->setEnabled(
false);
471 widget.pushButton_copyToClipboard->setEnabled(
false);
472 widget.pushButton_resetEndeffector->setEnabled(
false);
473 widget.pushButton_pointcloudColor->setEnabled(
false);
474 widget.pushButton_backgroundColor->setEnabled(
false);
475 widget.spinBox_pointSize->setEnabled(
false);
476 widget.pushButton_changeFile->setEnabled(
false);
477 widget.pushButton_saveDatapoint->setEnabled(
false);
478 widget.lineEdit_file->setEnabled(
false);
480 widget.doubleSpinBox_camera_x->setEnabled(
false);
481 widget.doubleSpinBox_camera_y->setEnabled(
false);
482 widget.doubleSpinBox_camera_z->setEnabled(
false);
483 widget.doubleSpinBox_camera_roll->setEnabled(
false);
484 widget.doubleSpinBox_camera_pitch->setEnabled(
false);
485 widget.doubleSpinBox_camera_yaw->setEnabled(
false);
487 widget.label_offsetMatrix->setText(QString(
"No Endeffector selected"));
488 widget.label_offsetMatrix->setStyleSheet(
"QLabel { color : red; }");
490 showPointCloud =
false;
493 void HandEyeCalibrationWidgetController::updateManipulatorVisualization()
495 if (activeEndEffector && manipulatorVisu)
497 Eigen::Matrix4f modelPoseInRoot = localRobot->getRobotNode(activeEndEffector->getTcp()->getName())->getPoseInRootFrame();
501 Eigen::Matrix4f pointCloudGlobal = localRobot->getGlobalPose() * pointCloudInRoot;
504 manipulatorVisu->setUserDesiredPose(pointCloudGlobal);
507 getEEFRobot(activeEndEffector)->setGlobalPoseForRobotNode(activeEndEffector->getTcp(), pointCloudGlobal);
510 if (widget.checkBox_offsetInverted->isChecked())
512 offset = offset.inverse();
514 widget.label_offsetMatrix->setText(QString::fromStdString(formatTransformationMatrix(offset)));
522 ARMARX_WARNING <<
"Timeout or error in waiting for pointclouds from provider: " << providerName;
532 void HandEyeCalibrationWidgetController::processPointCloud()
534 if (showPointCloud && pointcloudRobot)
537 pcl::PointCloud<PointT>::Ptr localBufferIn(
new pcl::PointCloud<PointT>());
538 pcl::copyPointCloud(*providerBuffer, *localBufferIn);
539 pcl::PointCloud<PointT>::Ptr localBufferOut(
new pcl::PointCloud<PointT>());
542 if (referenceFrame !=
"Global")
552 ARMARX_ERROR <<
"Exception while synchronizing robot for pointcloud-processing";
556 sourceFrameGlobalPose = pointcloudRobot->getRobotNode(referenceFrame)->getGlobalPose();
561 if (croppingActive && manipulatorVisu && manipulatorVisu->getIsVisualizing())
564 Eigen::Matrix4f eefInReferenceFrame = sourceFrameGlobalPose.inverse() * eefGlobal;
566 float cropRange = (
float) widget.horizontalSlider_croppingBox->value();
568 Eigen::Vector3f cropMin;
569 cropMin << eefInReferenceFrame(0, 3) - cropRange, eefInReferenceFrame(1, 3) - cropRange, eefInReferenceFrame(2, 3) - cropRange;
570 Eigen::Vector3f cropMax;
571 cropMax << eefInReferenceFrame(0, 3) + cropRange, eefInReferenceFrame(1, 3) + cropRange, eefInReferenceFrame(2, 3) + cropRange;
573 pcl::PassThrough<PointT> pass;
575 pass.setInputCloud(localBufferIn);
576 pass.setFilterFieldName(
"z");
577 pass.setFilterLimits(cropMin(2), cropMax(2));
578 pass.filter(*localBufferOut);
579 localBufferOut.swap(localBufferIn);
581 pass.setInputCloud(localBufferIn);
582 pass.setFilterFieldName(
"x");
583 pass.setFilterLimits(cropMin(0), cropMax(0));
584 pass.filter(*localBufferOut);
585 localBufferOut.swap(localBufferIn);
587 pass.setInputCloud(localBufferIn);
588 pass.setFilterFieldName(
"y");
589 pass.setFilterLimits(cropMin(1), cropMax(1));
590 pass.filter(*localBufferOut);
591 localBufferOut.swap(localBufferIn);
596 pcl::transformPointCloud(*localBufferIn, *localBufferOut, cameraToGlobal);
597 localBufferOut.swap(localBufferIn);
606 void HandEyeCalibrationWidgetController::cb_inverted_changed(
bool checked)
610 widget.label_titleOffsetMatrix->setText(
"Offset from Pointcloud to Model:");
614 widget.label_titleOffsetMatrix->setText(
"Offset from Model to Pointcloud:");
618 void HandEyeCalibrationWidgetController::btn_copyToClipboard_pressed()
620 if (activeEndEffector)
622 Eigen::Matrix4f offset = this->getOffsetMatrixForEEF(activeEndEffector);
624 if (widget.checkBox_offsetInverted->isChecked())
626 offset = offset.inverse();
632 obj->serializeIceObject(pose);
634 QClipboard* clipboard = QApplication::clipboard();
635 clipboard->setText(QString::fromStdString(obj->asString(
true)));
639 void HandEyeCalibrationWidgetController::btn_resetToModel_pressed()
641 if (activeEndEffector)
644 updateManipulatorVisualization();
645 widget.displayWidget->getDisplay()->cameraViewNode((SoNode*) manipulatorVisu, 1.0);
649 void HandEyeCalibrationWidgetController::btn_backgroundColor_pressed()
651 QColor selectedColor = this->colorDialog.getColor();
652 widget.displayWidget->getDisplay()->setBackgroundColor(SbColor(selectedColor.red() / 255.0f, selectedColor.green() / 255.0f, selectedColor.blue() / 255.0f));
655 void HandEyeCalibrationWidgetController::btn_pointCloudColor_pressed()
657 QColor selectedColor = this->colorDialog.getColor();
658 this->pointCloudVisu->
setDrawColor(SbColor(selectedColor.red() / 255.0f, selectedColor.green() / 255.0f, selectedColor.blue() / 255.0f));
661 void HandEyeCalibrationWidgetController::sB_pointSize_changed(
int value)
666 void HandEyeCalibrationWidgetController::cameraNodeTransformationChanged(
double value)
670 auto t = VirtualRobot::MathTools::eigen4f2posrpy(cameraNode->getLocalTransformation());
671 QObject* obj = sender();
672 if (obj == widget.doubleSpinBox_camera_x)
676 else if (obj == widget.doubleSpinBox_camera_y)
680 else if (obj == widget.doubleSpinBox_camera_z)
684 else if (obj == widget.doubleSpinBox_camera_roll)
686 t(3) = VirtualRobot::MathTools::deg2rad((
float)
value);
688 else if (obj == widget.doubleSpinBox_camera_pitch)
690 t(4) = VirtualRobot::MathTools::deg2rad((
float)
value);
692 else if (obj == widget.doubleSpinBox_camera_yaw)
694 t(5) = VirtualRobot::MathTools::deg2rad((
float)
value);
696 Eigen::Matrix4f transformation = VirtualRobot::MathTools::posrpy2eigen4f(t(0), t(1), t(2), t(3), t(4), t(5));
697 cameraNode->setLocalTransformation(transformation);
701 void HandEyeCalibrationWidgetController::taskEEFManipulationCB()
704 x[0] = (
float) widget.horizontalSlider_x->value();
705 x[1] = (
float) widget.horizontalSlider_y->value();
706 x[2] = (
float) widget.horizontalSlider_z->value();
707 if (activeEndEffector)
710 offsetInRoot(0, 3) = x[0];
711 offsetInRoot(1, 3) = x[1];
712 offsetInRoot(2, 3) = x[2];
714 setOffsetMatrixForEEF(activeEndEffector, offsetInRoot);
718 void HandEyeCalibrationWidgetController::taskLocalRobotUpdateCB()
720 if (!robotStateComponentPrx)
727 updateManipulatorVisualization();
734 void HandEyeCalibrationWidgetController::activeEndEffectorChanged(QString endEffectorName)
736 if (localRobot && manipulatorVisu)
738 std::string eefName = endEffectorName.toStdString();
739 if (!eefName.empty())
741 if (robotEEFMap.count(eefName) == 1)
743 activeEndEffector = robotEEFMap.at(eefName).first->getEndEffector(eefName);
744 manipulatorVisu->setVisualization(activeEndEffector);
745 widget.displayWidget->getDisplay()->cameraViewNode((SoNode*) manipulatorVisu, 1.0);
750 ARMARX_ERROR <<
"Robot " << localRobot->getName() <<
" does not have endeffector with name " << eefName;
756 void HandEyeCalibrationWidgetController::slider_croppingRange_changed(
int value)
758 this->widget.label_croppingBoxValue->setText(QString::fromStdString(
ValueToString(
value)));
761 void HandEyeCalibrationWidgetController::cb_croppingActive_changed(
int state)
763 if (state == Qt::Unchecked)
765 this->croppingActive =
true;
769 this->croppingActive =
false;