HandEyeCalibrationWidgetController.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * \package RobotComponents::gui-plugins::HandEyeCalibrationWidgetController
17  * \author Stefan Reither ( stef dot reither at web dot de )
18  * \date 2018
19  * \copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
24 
26 #include <VisionX/interface/components/Calibration.h>
27 
35 
36 #include <QClipboard>
37 #include <QFileDialog>
38 #include <QFileInfo>
39 #include <QMessageBox>
40 
41 #include <pcl/common/transforms.h>
42 #include <pcl/filters/filter.h>
43 #include <pcl/filters/passthrough.h>
44 
45 #include <iomanip>
46 #include <cctype>
47 
48 const QString defaultFileName("HandEyeCalib_Data.json");
49 
50 using namespace armarx;
51 
53  = default;
54 
55 
57  = default;
58 
59 
61 {
62 
63 }
64 
66 {
67 
68 }
69 
70 QPointer<QDialog> HandEyeCalibrationWidgetController::getConfigDialog(QWidget* parent)
71 {
72  if (!dialog)
73  {
74  dialog = new SimpleConfigDialog(parent);
75  dialog->addProxyFinder<visionx::PointCloudProviderInterfacePrx>({"PointCloudProvider", "PointCloudProvider", "*"});
76  dialog->addProxyFinder<RobotStateComponentInterfacePrx>({"RobotStateComponent", "RobotStateComponent", "RobotState*"});
77  }
78  return qobject_cast<SimpleConfigDialog*>(dialog);
79 }
80 
82 {
83  providerName = dialog->getProxyName("PointCloudProvider");
84  robotStateComponentName = dialog->getProxyName("RobotStateComponent");
85 }
86 
88 {
89  ARMARX_INFO << "onInitPointCloudProcessor";
90 
91  QMetaObject::invokeMethod(this, "initUI");
92 
93  usingProxy(robotStateComponentName);
94 }
95 
96 void HandEyeCalibrationWidgetController::initUI()
97 {
98  widget.setupUi(getWidget());
99  widget.lineEdit_file->setText(QDir::currentPath() + "/" + defaultFileName);
100  getWidget()->setEnabled(false);
101 }
102 
103 void HandEyeCalibrationWidgetController::saveDatapoint()
104 {
105  if (activeEndEffector)
106  {
107  SimpleJsonLoggerEntry entry;
108  entry.Add("EndEffector", activeEndEffector->getName());
109 
110  std::map<std::string, float> config = localRobot->getConfig()->getRobotNodeJointValueMap();
111  entry.Add("RobotConfig", config);
112 
113  Eigen::Matrix4f offset = getOffsetMatrixForEEF(activeEndEffector);
114  entry.AddMatrix("Offset", offset);
115 
116  std::string fileName = widget.lineEdit_file->text().toStdString();
117  SimpleJsonLogger logger(fileName, true);
118  logger.log(entry);
119  logger.close();
120 
121  QMessageBox::information(getWidget(),
122  tr("HandEyeCalibration"),
123  tr("Datapoint successful written to file."));
124  }
125 }
126 
127 void HandEyeCalibrationWidgetController::selectFile()
128 {
129  QString fileName = QFileDialog::getOpenFileName(getWidget(),
130  tr("Select file for saving data points"),
131  QDir::currentPath(),
132  tr("JSON-File (*.json);; All Files (*)"));
133  if (!fileName.isEmpty())
134  {
135  widget.lineEdit_file->setText(fileName);
136  }
137 }
138 
139 VirtualRobot::RobotPtr HandEyeCalibrationWidgetController::getEEFRobot(VirtualRobot::EndEffectorPtr eef) const
140 {
141  if (eef && robotEEFMap.count(eef->getName()) == 1)
142  {
143  return robotEEFMap.at(eef->getName()).first;
144  }
145  return VirtualRobot::RobotPtr();
146 }
147 
148 Eigen::Matrix4f HandEyeCalibrationWidgetController::getOffsetMatrixForEEF(const VirtualRobot::EndEffectorPtr eef) const
149 {
150  if (eef && robotEEFMap.count(eef->getName()) == 1)
151  {
152  return robotEEFMap.at(eef->getName()).second;
153  }
154  return Eigen::Matrix4f::Identity();
155 }
156 
157 void HandEyeCalibrationWidgetController::setOffsetMatrixForEEF(const VirtualRobot::EndEffectorPtr eef, const Eigen::Matrix4f& offset)
158 {
159  if (eef && robotEEFMap.count(eef->getName()) == 1)
160  {
161  robotEEFMap.at(eef->getName()).second = offset;
162  }
163 }
164 
166 {
167  ARMARX_INFO << "onConnectPointCloudProcessor";
168 
169  robotStateComponentPrx = getProxy<RobotStateComponentInterfacePrx>(robotStateComponentName, true);
170 
171  usingPointCloudProvider(providerName);
172  providerInfo = getPointCloudProvider(providerName, true);
173  referenceFrame = getProviderFrame();
174  providerBuffer.reset(new pcl::PointCloud<PointT>());
175 
176  localRobot = loadRobotFromFile();
177  try
178  {
179  pointcloudRobot = RemoteRobot::createLocalClone(robotStateComponentPrx);
180  }
181  catch (...)
182  {
183  ARMARX_ERROR << "Exception while creating local clone of robot in onConnectPointCLoudProcessor()";
185  }
186 
187  // Setup periodic tasks
188  taskEEFManipulation = new PeriodicTask<HandEyeCalibrationWidgetController>(this, &HandEyeCalibrationWidgetController::taskEEFManipulationCB, 30.0f);
189  taskLocalRobotUpdate = new PeriodicTask<HandEyeCalibrationWidgetController>(this, &HandEyeCalibrationWidgetController::taskLocalRobotUpdateCB, 50.0f);
190 
191  // Setup visualizations
192  QMetaObject::invokeMethod(this, "connectQt", Qt::BlockingQueuedConnection);
193 
194  // Finally connecting the signals and slots
195  connect(this, SIGNAL(pointCloudUpdated()), this, SLOT(processPointCloud()));
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)));
199 
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()));
203 
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)));
210 
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)));
214 
215  connect(widget.pushButton_changeFile, SIGNAL(clicked()), this, SLOT(selectFile()));
216  connect(widget.pushButton_saveDatapoint, SIGNAL(clicked()), this, SLOT(saveDatapoint()));
217 
218  taskEEFManipulation->start();
219  taskLocalRobotUpdate->start();
220  enableMainWidgetAsync(true);
221 }
222 
223 void HandEyeCalibrationWidgetController::connectQt()
224 {
225  pointCloudVisu = new PointCloudVisualization();
226  widget.displayWidget->getDisplay()->getRootNode()->addChild(pointCloudVisu);
227 
228  manipulatorVisu = new ManipulatorVisualization();
229  widget.displayWidget->getDisplay()->getRootNode()->addChild((SoNode*)manipulatorVisu);
230 
231  widget.displayWidget->getDisplay()->cameraViewAll();
232 
233  if (manipulatorVisu)
234  {
235  setupEndEffectorSelection(localRobot);
236  }
237  else
238  {
239  ARMARX_WARNING << "ManipulatorVisu not present";
240  }
241  setupCameraNodeSlider(pointcloudRobot);
242  disableGuiElements();
243 }
244 
246 {
247  ARMARX_INFO << "onDisconnectPointCloudProcessor";
248 
249  taskEEFManipulation->stop();
250  taskLocalRobotUpdate->stop();
251 
252  releasePointCloudProvider(providerName);
253  QMetaObject::invokeMethod(this, "disconnectQt");
254 
255  localRobot.reset();
256  pointcloudRobot.reset();
257  activeEndEffector.reset();
258  providerBuffer.reset();
259 }
260 
261 void HandEyeCalibrationWidgetController::disconnectQt()
262 {
263  disableGuiElements();
264 
265  widget.comboBox_endEffectorSelection->clear();
266  manipulatorVisu->removeVisualization();
267  pointCloudVisu->removeAllChildren();
268  widget.displayWidget->getDisplay()->getRootNode()->removeAllChildren();
269 
270  // disconnect signals that would interfere with the gui setup
271  QObject::disconnect(widget.comboBox_endEffectorSelection, 0, 0, 0);
272 }
273 
275 {
276  ARMARX_INFO << "onExitPointCloudProcessor";
277 }
278 
279 void HandEyeCalibrationWidgetController::setupEndEffectorSelection(VirtualRobot::RobotPtr robot)
280 {
281  try
282  {
283  armarx::RemoteRobot::synchronizeLocalClone(robot, robotStateComponentPrx);
284  }
285  catch (...)
286  {
288  }
289 
290  std::vector<VirtualRobot::EndEffectorPtr> endEffectors;
291  robot->getEndEffectors(endEffectors);
292  for (VirtualRobot::EndEffectorPtr e : endEffectors)
293  {
294  widget.comboBox_endEffectorSelection->addItem(QString::fromStdString(e->getName()));
295  VirtualRobot::RobotPtr r = e->createEefRobot(e->getName(), e->getName());
296  r->setGlobalPoseForRobotNode(r->getRobotNode(e->getTcp()->getName()), e->getTcp()->getGlobalPose());
297  robotEEFMap.insert(std::make_pair(e->getName(), std::make_pair(r, Eigen::Matrix4f::Identity())));
298  }
299  widget.comboBox_endEffectorSelection->setCurrentIndex(-1);
300 }
301 
302 bool HandEyeCalibrationWidgetController::findStringIC(const std::string& strHaystack, const std::string& strNeedle) const
303 {
304  auto it = std::search(
305  strHaystack.begin(), strHaystack.end(),
306  strNeedle.begin(), strNeedle.end(),
307  [](char ch1, char ch2)
308  {
309  return std::toupper(ch1) == std::toupper(ch2);
310  }
311  );
312  return (it != strHaystack.end());
313 }
314 
315 void HandEyeCalibrationWidgetController::setupCameraNodeSlider(VirtualRobot::RobotPtr robot)
316 {
317  if (robot)
318  {
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)));
321 
322  cameraNode = robot->getRobotNode(referenceFrame);
323  auto trans = VirtualRobot::MathTools::eigen4f2posrpy(cameraNode->getLocalTransformation());
324 
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)));
331  }
332 }
333 
334 VirtualRobot::RobotPtr HandEyeCalibrationWidgetController::loadRobotFromFile() const
335 {
336  Ice::StringSeq includePaths;
337 
338  try
339  {
340  Ice::StringSeq packages = robotStateComponentPrx->getArmarXPackages();
341  packages.push_back(Application::GetProjectName());
342 
343  for (const std::string& projectName : packages)
344  {
345  if (projectName.empty())
346  {
347  continue;
348  }
349 
350  CMakePackageFinder project(projectName);
351  auto pathsString = project.getDataDir();
352  Ice::StringSeq projectIncludePaths = armarx::Split(pathsString, ";,", true, true);
353  includePaths.insert(includePaths.end(), projectIncludePaths.begin(), projectIncludePaths.end());
354  }
355  }
356  catch (...)
357  {
358  ARMARX_ERROR << "Unable to retrieve robot filename." << std::endl;
359  return VirtualRobot::RobotPtr();
360  }
361 
362  try
363  {
364  std::string rfile = robotStateComponentPrx->getRobotFilename();
365  ArmarXDataPath::getAbsolutePath(rfile, rfile, includePaths);
366  return VirtualRobot::RobotIO::loadRobot(rfile);
367  }
368  catch (...)
369  {
370  ARMARX_ERROR << "Unable to load robot from file" << std::endl;
371  return VirtualRobot::RobotPtr();
372  }
373 }
374 
375 std::string HandEyeCalibrationWidgetController::getProviderFrame() const
376 {
377  std::string frame = "Global";
378  try
379  {
380  visionx::ReferenceFrameInterfacePrx refFramePrx = visionx::ReferenceFrameInterfacePrx::checkedCast(providerInfo.proxy);
381  if (refFramePrx)
382  {
383  frame = refFramePrx->getReferenceFrame();
384  }
385  }
386  catch (...)
387  {
389  }
390  return frame;
391 }
392 
393 std::string HandEyeCalibrationWidgetController::formatTransformationMatrix(Eigen::Matrix4f mat, int decimalPlacesOrientation, int decimalPlacesPosition) const
394 {
395  std::stringstream ss;
396  ss.imbue(std::locale::classic());
397  ss << std::fixed;
398 
399  // The first three rows behave the same
400  for (int i = 0; i < 3; i++)
401  {
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))
407  {
408  ss << " ";
409  }
410  ss << x0 << " ";
411  if (!std::signbit(x1))
412  {
413  ss << " ";
414  }
415  ss << x1 << " ";
416  if (!std::signbit(x2))
417  {
418  ss << " ";
419  }
420  ss << x2 << " ";
421 
422  ss << std::setprecision(decimalPlacesPosition);
423  if (!std::signbit(mat(i, 3)))
424  {
425  ss << " ";
426  }
427  ss << mat(i, 3);
428  ss << std::endl;
429  }
430  return ss.str();
431 }
432 
433 void HandEyeCalibrationWidgetController::enableGuiElements()
434 {
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);
449 
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);
456 
457  widget.label_offsetMatrix->setText(QString("No Endeffector selected"));
458  widget.label_offsetMatrix->setStyleSheet("QLabel { color : black; }");
459 
460  showPointCloud = true;
461 }
462 
463 void HandEyeCalibrationWidgetController::disableGuiElements()
464 {
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);
479 
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);
486 
487  widget.label_offsetMatrix->setText(QString("No Endeffector selected"));
488  widget.label_offsetMatrix->setStyleSheet("QLabel { color : red; }");
489 
490  showPointCloud = false;
491 }
492 
493 void HandEyeCalibrationWidgetController::updateManipulatorVisualization()
494 {
495  if (activeEndEffector && manipulatorVisu)
496  {
497  Eigen::Matrix4f modelPoseInRoot = localRobot->getRobotNode(activeEndEffector->getTcp()->getName())->getPoseInRootFrame();
498  Eigen::Matrix4f offset = getOffsetMatrixForEEF(activeEndEffector);
499  // Apply offset in root frame (multiplication order matters!!)
500  Eigen::Matrix4f pointCloudInRoot = offset * modelPoseInRoot;
501  Eigen::Matrix4f pointCloudGlobal = localRobot->getGlobalPose() * pointCloudInRoot;
502 
503  // Apply global pose to manipulator visu
504  manipulatorVisu->setUserDesiredPose(pointCloudGlobal);
505 
506  // Update the local eefRobot
507  getEEFRobot(activeEndEffector)->setGlobalPoseForRobotNode(activeEndEffector->getTcp(), pointCloudGlobal);
508 
509  // Update Matrix label
510  if (widget.checkBox_offsetInverted->isChecked())
511  {
512  offset = offset.inverse();
513  }
514  widget.label_offsetMatrix->setText(QString::fromStdString(formatTransformationMatrix(offset)));
515  }
516 }
517 
519 {
520  if (!waitForPointClouds(providerName, 500))
521  {
522  ARMARX_WARNING << "Timeout or error in waiting for pointclouds from provider: " << providerName;
523  }
524  else
525  {
526  getPointClouds(providerName, providerBuffer);
527 
528  emit pointCloudUpdated();
529  }
530 }
531 
532 void HandEyeCalibrationWidgetController::processPointCloud()
533 {
534  if (showPointCloud && pointcloudRobot)
535  {
536  // Copy buffer to be able to edit it
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>());
540 
541  Eigen::Matrix4f sourceFrameGlobalPose = Eigen::Matrix4f::Identity();
542  if (referenceFrame != "Global")
543  {
544  visionx::MetaPointCloudFormatPtr info = this->getPointCloudFormat(providerName);
545 
546  try
547  {
548  RemoteRobot::synchronizeLocalCloneToTimestamp(pointcloudRobot, robotStateComponentPrx, info->timeProvided);
549  }
550  catch (...)
551  {
552  ARMARX_ERROR << "Exception while synchronizing robot for pointcloud-processing";
554  }
555 
556  sourceFrameGlobalPose = pointcloudRobot->getRobotNode(referenceFrame)->getGlobalPose();
557  }
558  Eigen::Matrix4f cameraToGlobal = sourceFrameGlobalPose;
559 
560  // Crop pointcloud around endeffector
561  if (croppingActive && manipulatorVisu && manipulatorVisu->getIsVisualizing())
562  {
563  Eigen::Matrix4f eefGlobal = manipulatorVisu->getUserDesiredPose();
564  Eigen::Matrix4f eefInReferenceFrame = sourceFrameGlobalPose.inverse() * eefGlobal;
565 
566  float cropRange = (float) widget.horizontalSlider_croppingBox->value();
567 
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;
572 
573  pcl::PassThrough<PointT> pass;
574 
575  pass.setInputCloud(localBufferIn);
576  pass.setFilterFieldName("z");
577  pass.setFilterLimits(cropMin(2), cropMax(2));
578  pass.filter(*localBufferOut);
579  localBufferOut.swap(localBufferIn);
580 
581  pass.setInputCloud(localBufferIn);
582  pass.setFilterFieldName("x");
583  pass.setFilterLimits(cropMin(0), cropMax(0));
584  pass.filter(*localBufferOut);
585  localBufferOut.swap(localBufferIn);
586 
587  pass.setInputCloud(localBufferIn);
588  pass.setFilterFieldName("y");
589  pass.setFilterLimits(cropMin(1), cropMax(1));
590  pass.filter(*localBufferOut);
591  localBufferOut.swap(localBufferIn);
592  }
593 
594 
595  // Transform pointcloud into GlobalFrame
596  pcl::transformPointCloud(*localBufferIn, *localBufferOut, cameraToGlobal);
597  localBufferOut.swap(localBufferIn);
598 
599  if (pointCloudVisu)
600  {
601  pointCloudVisu->setVisualization(localBufferIn);
602  }
603  }
604 }
605 
606 void HandEyeCalibrationWidgetController::cb_inverted_changed(bool checked)
607 {
608  if (checked)
609  {
610  widget.label_titleOffsetMatrix->setText("Offset from Pointcloud to Model:");
611  }
612  else
613  {
614  widget.label_titleOffsetMatrix->setText("Offset from Model to Pointcloud:");
615  }
616 }
617 
618 void HandEyeCalibrationWidgetController::btn_copyToClipboard_pressed()
619 {
620  if (activeEndEffector)
621  {
622  Eigen::Matrix4f offset = this->getOffsetMatrixForEEF(activeEndEffector);
623 
624  if (widget.checkBox_offsetInverted->isChecked())
625  {
626  offset = offset.inverse();
627  }
628 
629  PosePtr pose = new Pose(offset);
630 
631  JSONObjectPtr obj = new JSONObject();
632  obj->serializeIceObject(pose);
633 
634  QClipboard* clipboard = QApplication::clipboard();
635  clipboard->setText(QString::fromStdString(obj->asString(true)));
636  }
637 }
638 
639 void HandEyeCalibrationWidgetController::btn_resetToModel_pressed()
640 {
641  if (activeEndEffector)
642  {
643  setOffsetMatrixForEEF(activeEndEffector, Eigen::Matrix4f::Identity());
644  updateManipulatorVisualization();
645  widget.displayWidget->getDisplay()->cameraViewNode((SoNode*) manipulatorVisu, 1.0);
646  }
647 }
648 
649 void HandEyeCalibrationWidgetController::btn_backgroundColor_pressed()
650 {
651  QColor selectedColor = this->colorDialog.getColor();
652  widget.displayWidget->getDisplay()->setBackgroundColor(SbColor(selectedColor.red() / 255.0f, selectedColor.green() / 255.0f, selectedColor.blue() / 255.0f));
653 }
654 
655 void HandEyeCalibrationWidgetController::btn_pointCloudColor_pressed()
656 {
657  QColor selectedColor = this->colorDialog.getColor();
658  this->pointCloudVisu->setDrawColor(SbColor(selectedColor.red() / 255.0f, selectedColor.green() / 255.0f, selectedColor.blue() / 255.0f));
659 }
660 
661 void HandEyeCalibrationWidgetController::sB_pointSize_changed(int value)
662 {
663  this->pointCloudVisu->setPointSize(value);
664 }
665 
666 void HandEyeCalibrationWidgetController::cameraNodeTransformationChanged(double value)
667 {
668  if (cameraNode)
669  {
670  auto t = VirtualRobot::MathTools::eigen4f2posrpy(cameraNode->getLocalTransformation());
671  QObject* obj = sender();
672  if (obj == widget.doubleSpinBox_camera_x)
673  {
674  t(0) = (float) value;
675  }
676  else if (obj == widget.doubleSpinBox_camera_y)
677  {
678  t(1) = (float) value;
679  }
680  else if (obj == widget.doubleSpinBox_camera_z)
681  {
682  t(2) = (float) value;
683  }
684  else if (obj == widget.doubleSpinBox_camera_roll)
685  {
686  t(3) = VirtualRobot::MathTools::deg2rad((float) value);
687  }
688  else if (obj == widget.doubleSpinBox_camera_pitch)
689  {
690  t(4) = VirtualRobot::MathTools::deg2rad((float) value);
691  }
692  else if (obj == widget.doubleSpinBox_camera_yaw)
693  {
694  t(5) = VirtualRobot::MathTools::deg2rad((float) value);
695  }
696  Eigen::Matrix4f transformation = VirtualRobot::MathTools::posrpy2eigen4f(t(0), t(1), t(2), t(3), t(4), t(5));
697  cameraNode->setLocalTransformation(transformation);
698  }
699 }
700 
701 void HandEyeCalibrationWidgetController::taskEEFManipulationCB()
702 {
703  float x[3];
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)
708  {
710  offsetInRoot(0, 3) = x[0];
711  offsetInRoot(1, 3) = x[1];
712  offsetInRoot(2, 3) = x[2];
713 
714  setOffsetMatrixForEEF(activeEndEffector, offsetInRoot);
715  }
716 }
717 
718 void HandEyeCalibrationWidgetController::taskLocalRobotUpdateCB()
719 {
720  if (!robotStateComponentPrx)
721  {
722  return;
723  }
724  try
725  {
726  RemoteRobot::synchronizeLocalClone(localRobot, robotStateComponentPrx);
727  updateManipulatorVisualization();
728  }
729  catch (...)
730  {
731  }
732 }
733 
734 void HandEyeCalibrationWidgetController::activeEndEffectorChanged(QString endEffectorName)
735 {
736  if (localRobot && manipulatorVisu)
737  {
738  std::string eefName = endEffectorName.toStdString();
739  if (!eefName.empty())
740  {
741  if (robotEEFMap.count(eefName) == 1)
742  {
743  activeEndEffector = robotEEFMap.at(eefName).first->getEndEffector(eefName);
744  manipulatorVisu->setVisualization(activeEndEffector);
745  widget.displayWidget->getDisplay()->cameraViewNode((SoNode*) manipulatorVisu, 1.0);
746  enableGuiElements();
747  }
748  else
749  {
750  ARMARX_ERROR << "Robot " << localRobot->getName() << " does not have endeffector with name " << eefName;
751  }
752  }
753  }
754 }
755 
756 void HandEyeCalibrationWidgetController::slider_croppingRange_changed(int value)
757 {
758  this->widget.label_croppingBoxValue->setText(QString::fromStdString(ValueToString(value)));
759 }
760 
761 void HandEyeCalibrationWidgetController::cb_croppingActive_changed(int state)
762 {
763  if (state == Qt::Unchecked)
764  {
765  this->croppingActive = true;
766  }
767  else
768  {
769  this->croppingActive = false;
770  }
771 }
772 
773 
armarx::PointCloudVisualization::setDrawColor
void setDrawColor(SbColor color)
Definition: PointCloudVisualization.cpp:116
RemoteRobot.h
armarx::HandEyeCalibrationWidgetController::onExitPointCloudProcessor
void onExitPointCloudProcessor() override
Exit the ImapeProcessor component.
Definition: HandEyeCalibrationWidgetController.cpp:274
armarx::Application::GetProjectName
static const std::string & GetProjectName()
Definition: Application.cpp:861
armarx::HandEyeCalibrationWidgetController::onInitPointCloudProcessor
void onInitPointCloudProcessor() override
Setup the vision component.
Definition: HandEyeCalibrationWidgetController.cpp:87
armarx::PointCloudVisualization
Definition: PointCloudVisualization.h:37
visionx::PointCloudProcessor::getPointCloudFormat
MetaPointCloudFormatPtr getPointCloudFormat(std::string providerName)
Definition: PointCloudProcessor.cpp:506
JSONObject.h
armarx::navigation::core::Pose
Eigen::Isometry3f Pose
Definition: basic_types.h:31
armarx::HandEyeCalibrationWidgetController::onDisconnectPointCloudProcessor
void onDisconnectPointCloudProcessor() override
Implement this method in the PointCloudProcessor in order execute parts when the component looses net...
Definition: HandEyeCalibrationWidgetController.cpp:245
armarx::RemoteRobot::synchronizeLocalClone
static bool synchronizeLocalClone(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx)
Definition: RemoteRobot.cpp:448
Pose.h
SimpleJsonLogger.h
armarx::JSONObject
The JSONObject class is used to represent and (de)serialize JSON objects.
Definition: JSONObject.h:43
visionx::PointCloudProviderInfo::proxy
PointCloudProviderInterfacePrx proxy
Proxy to PointCloud provider.
Definition: PointCloudProcessor.h:87
armarx::Split
std::vector< std::string > Split(const std::string &source, const std::string &splitBy, bool trimElements=false, bool removeEmptyElements=false)
Definition: StringHelperTemplates.h:35
armarx::HandEyeCalibrationWidgetController::~HandEyeCalibrationWidgetController
virtual ~HandEyeCalibrationWidgetController()
Controller destructor.
armarx::SimpleJsonLoggerEntry::AddMatrix
void AddMatrix(const std::string &key, const Eigen::MatrixXf &mat)
Definition: SimpleJsonLoggerEntry.cpp:54
armarx::HandEyeCalibrationWidgetController::HandEyeCalibrationWidgetController
HandEyeCalibrationWidgetController()
Controller Constructor.
armarx::CMakePackageFinder
The CMakePackageFinder class provides an interface to the CMake Package finder capabilities.
Definition: CMakePackageFinder.h:53
defaultFileName
const QString defaultFileName("HandEyeCalib_Data.json")
armarx::SimpleJsonLogger
Definition: SimpleJsonLogger.h:42
project
std::string project
Definition: VisualizationRobot.cpp:83
StringHelpers.h
IceInternal::Handle< Pose >
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:523
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:926
armarx::ValueToString
std::string ValueToString(const T &value)
Definition: StringHelpers.h:58
visionx::PointCloudProcessor::waitForPointClouds
bool waitForPointClouds(int milliseconds=1000)
Wait for new PointClouds.
Definition: PointCloudProcessor.cpp:433
armarx::HandEyeCalibrationWidgetController::onConnectPointCloudProcessor
void onConnectPointCloudProcessor() override
Implement this method in the PointCloudProcessor in order execute parts when the component is fully i...
Definition: HandEyeCalibrationWidgetController.cpp:165
armarx::SimpleJsonLoggerEntry::Add
void Add(const std::string &key, const std::string &value)
Definition: SimpleJsonLoggerEntry.cpp:59
SimpleJsonLoggerEntry.h
armarx::HandEyeCalibrationWidgetController::getConfigDialog
QPointer< QDialog > getConfigDialog(QWidget *parent=0) override
getConfigDialog returns a pointer to the a configuration widget of this controller.
Definition: HandEyeCalibrationWidgetController.cpp:70
armarx::HandEyeCalibrationWidgetController::process
void process() override
Process the vision component.
Definition: HandEyeCalibrationWidgetController.cpp:518
ARMARX_ERROR
#define ARMARX_ERROR
Definition: Logging.h:189
visionx::PointCloudProcessor::getPointClouds
int getPointClouds(const PointCloudPtrT &pointCloudPtr)
Poll PointClouds from provider.
Definition: PointCloudProcessor.h:373
armarx::PointCloudVisualization::setPointSize
void setPointSize(int size)
Definition: PointCloudVisualization.cpp:122
armarx::PointCloudVisualization::setVisualization
void setVisualization(pcl::PointCloud< PointT >::ConstPtr cloud)
Definition: PointCloudVisualization.cpp:50
CMakePackageFinder.h
visionx::PointCloudProcessor::releasePointCloudProvider
void releasePointCloudProvider(std::string providerName)
Removes topic subscription and provider proxy dependency to release a point cloud provider.
Definition: PointCloudProcessor.cpp:275
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
ARMARX_CHECK_EXPRESSION
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
Definition: ExpressionException.h:73
armarx::HandEyeCalibrationWidgetController::configured
void configured() override
This function must be implemented by the user, if he supplies a config dialog.
Definition: HandEyeCalibrationWidgetController.cpp:81
float
#define float
Definition: 16_Level.h:22
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
armarx::ArmarXWidgetController::enableMainWidgetAsync
void enableMainWidgetAsync(bool enable)
This function enables/disables the main widget asynchronously (if called from a non qt thread).
Definition: ArmarXWidgetController.cpp:174
armarx::RemoteRobot::createLocalClone
VirtualRobot::RobotPtr createLocalClone()
Clones the structure of this remote robot to a local instance.
Definition: RemoteRobot.cpp:328
armarx::RemoteRobot::synchronizeLocalCloneToTimestamp
static bool synchronizeLocalCloneToTimestamp(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx, Ice::Long timestamp)
Synchronizes a local robot to a robot state at timestamp.
Definition: RemoteRobot.cpp:487
visionx::PointCloudProcessor::usingPointCloudProvider
void usingPointCloudProvider(std::string providerName)
Registers a delayed topic subscription and a delayed provider proxy retrieval which will be available...
Definition: PointCloudProcessor.cpp:261
IceInternal::ProxyHandle<::IceProxy::armarx::RobotStateComponentInterface >
armarx::ManipulatorVisualization
Definition: ManipulatorVisualization.h:51
armarx::ArmarXWidgetController::getWidget
virtual QPointer< QWidget > getWidget()
getWidget returns a pointer to the a widget of this controller.
Definition: ArmarXWidgetController.cpp:54
visionx::PointCloudProcessor::getPointCloudProvider
PointCloudProviderInfo getPointCloudProvider(std::string name, bool waitForProxy=false)
Select an PointCloudProvider.
Definition: PointCloudProcessor.cpp:304
armarx::HandEyeCalibrationWidgetController::saveSettings
void saveSettings(QSettings *settings) override
Definition: HandEyeCalibrationWidgetController.cpp:65
armarx::HandEyeCalibrationWidgetController::pointCloudUpdated
void pointCloudUpdated()
armarx::ArmarXDataPath::getAbsolutePath
static bool getAbsolutePath(const std::string &relativeFilename, std::string &storeAbsoluteFilename, const std::vector< std::string > &additionalSearchPaths={}, bool verbose=true)
Definition: ArmarXDataPath.cpp:111
armarx::PeriodicTask
Definition: ArmarXManager.h:70
armarx::handleExceptions
void handleExceptions()
Definition: Exception.cpp:141
armarx::SimpleJsonLoggerEntry
Definition: SimpleJsonLoggerEntry.h:35
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
armarx::HandEyeCalibrationWidgetController::loadSettings
void loadSettings(QSettings *settings) override
Definition: HandEyeCalibrationWidgetController.cpp:60
HandEyeCalibrationWidgetController.h
armarx::ManagedIceObject::usingProxy
bool usingProxy(const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list.
Definition: ManagedIceObject.cpp:151
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
Application.h
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:18
armarx::SimpleConfigDialog
A config-dialog containing one (or multiple) proxy finders.
Definition: SimpleConfigDialog.h:84