31 #include <QDoubleSpinBox>
32 #include <QFormLayout>
33 #include <QHBoxLayout>
36 #include <QPushButton>
37 #include <QRadioButton>
38 #include <QSignalBlocker>
39 #include <qboxlayout.h>
40 #include <qformlayout.h>
42 #include <qnamespace.h>
44 #include <qobjectdefs.h>
45 #include <qsizepolicy.h>
47 #include <SimoxUtility/math/convert/deg_to_rad.h>
48 #include <SimoxUtility/math/convert/mat4f_to_rpy.h>
49 #include <SimoxUtility/math/convert/rad_to_deg.h>
50 #include <SimoxUtility/math/convert/rpy_to_mat3f.h>
51 #include <SimoxUtility/math/pose/pose.h>
52 #include <VirtualRobot/XML/BaseIO.h>
53 #include <VirtualRobot/XML/RobotIO.h>
77 setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Minimum);
79 name =
new QLineEdit(
this);
80 name->setReadOnly(
true);
81 locationID =
new QLineEdit(
this);
82 locationID->setReadOnly(
true);
84 agent =
new QComboBox(
this);
85 agent->setSizeAdjustPolicy(QComboBox::AdjustToContents);
87 frame =
new QComboBox(
this);
88 frame->setSizeAdjustPolicy(QComboBox::AdjustToContents);
90 removeInstanceButton =
new QPushButton(
"Remove Instance");
91 removeInstanceButton->setToolTip(
92 "Remove the instance id from the agent and make this location relative to an object "
93 "class instead of a specific object instance.");
95 x =
new QDoubleSpinBox(
this);
96 y =
new QDoubleSpinBox(
this);
97 z =
new QDoubleSpinBox(
this);
99 roll =
new QDoubleSpinBox(
this);
100 pitch =
new QDoubleSpinBox(
this);
101 yaw =
new QDoubleSpinBox(
this);
103 angleUnitDeg =
new QRadioButton(
"Degrees");
104 angleUnitRad =
new QRadioButton(
"Radians");
106 _useCurrentRobotPose =
new QPushButton(
"Use Current Robot Pose");
107 _useCurrentRobotPose->setEnabled(
false);
108 _useCurrentRobotPose->setToolTip(
109 "Use the robot's current global pose (requires connection to robot state).");
112 for (QDoubleSpinBox* pos : _positionSpinBoxes())
114 pos->setSuffix(
" mm");
115 pos->setMinimum(-1e6);
116 pos->setMaximum(+1e6);
117 pos->setSingleStep(50);
119 for (QDoubleSpinBox* spinBox : _allSpinBoxes())
121 spinBox->setValue(0);
122 spinBox->setAlignment(Qt::AlignRight);
125 QHBoxLayout* angleUnitLayout =
new QHBoxLayout();
126 for (QRadioButton* angleUnit : {angleUnitDeg, angleUnitRad})
128 angleUnitLayout->addWidget(angleUnit);
131 QFormLayout* layout =
new QFormLayout();
132 this->setLayout(layout);
134 layout->addRow(
"Name", name);
135 layout->addRow(
"Entity ID", locationID);
136 layout->addRow(
"Agent", agent);
137 layout->addRow(
"Frame", frame);
138 layout->addRow(removeInstanceButton);
139 layout->addRow(
"X", x);
140 layout->addRow(
"Y", y);
141 layout->addRow(
"Z", z);
142 layout->addRow(
"Roll", roll);
143 layout->addRow(
"Pitch", pitch);
144 layout->addRow(
"Yaw", yaw);
145 layout->addRow(
"Angle Units", angleUnitLayout);
146 layout->addRow(_useCurrentRobotPose);
151 for (QRadioButton* angleUnit : {angleUnitDeg, angleUnitRad})
153 connect(angleUnit, &QRadioButton::toggled,
this, &This::_updateAngleUnit);
157 QOverload<int>::of(&QComboBox::currentIndexChanged),
159 &This::_updateVertexAgent);
161 QOverload<int>::of(&QComboBox::currentIndexChanged),
163 &This::_updateVertexFrame);
164 connect(removeInstanceButton, &QPushButton::pressed,
this, &This::_removeInstance);
166 for (QDoubleSpinBox* spinBox : _allSpinBoxes())
169 QOverload<qreal>::of(&QDoubleSpinBox::valueChanged),
171 &This::_updateVertexAttribs);
174 connect(_useCurrentRobotPose, &QPushButton::pressed,
this, &This::_setFromCurrentRobotPose);
177 angleUnitDeg->click();
180 std::optional<GuiGraph::Vertex>
189 QSignalBlocker blocker(
this);
199 _vertex = std::nullopt;
206 return {x->value(), y->value(), z->value()};
212 Eigen::Vector3d raw = _rpyRaw();
213 if (angleUnitRad->isChecked())
226 Eigen::Vector3d raw = _rpyRaw();
227 if (angleUnitDeg->isChecked())
229 return simox::math::deg_to_rad(raw);
246 this->_robotConnection = connection;
247 _useCurrentRobotPose->setEnabled(_robotConnection !=
nullptr);
253 this->_objectPosesConnection = connection;
254 if (_vertex.has_value())
256 QSignalBlocker blocker(
this);
258 _loadFramedPoseFromVertex(_vertex.value());
263 VertexDataWidget::_setFromVertex(
const GuiGraph::Vertex& vertex)
267 name->setText(QString::fromStdString(attrib.
getName()));
269 QString::fromStdString(aron::fromAron<armem::MemoryID>(attrib.
aron.locationID).str()));
271 _loadFramedPoseFromVertex(
vertex);
277 VertexDataWidget::_getToVertex(GuiGraph::Vertex& vertex)
279 VertexData& attrib =
vertex.attrib();
285 frame->currentText().toStdString(),
286 agent->currentText().toStdString());
287 attrib.setPose(framed);
291 VertexDataWidget::_updateAngleUnit()
293 std::function<double(
double)> convertValue;
294 QString suffix =
" \u00b0";
300 if (angleUnitRad->isChecked())
302 convertValue = [](
double deg) {
return simox::math::deg_to_rad(deg); };
304 min = simox::math::deg_to_rad(
min);
305 max = simox::math::deg_to_rad(
max);
306 step = simox::math::deg_to_rad(step);
312 convertValue = [](
double rad) {
return simox::math::rad_to_deg(rad); };
315 std::vector<QSignalBlocker> blockers;
316 for (QDoubleSpinBox*
angle : _angleSpinBoxes())
318 blockers.emplace_back(
angle);
320 angle->setSuffix(suffix);
323 angle->setSingleStep(step);
324 angle->setDecimals(decimals);
326 if (_vertex.has_value())
329 simox::math::mat4f_to_rpy(_vertex->attrib().getPose().toEigen().cast<qreal>()));
336 VertexDataWidget::_updateVertexAttribs()
338 if (not signalsBlocked() and _vertex.has_value())
340 _getToVertex(_vertex.value());
341 _vertex->attrib().changed =
true;
347 VertexDataWidget::_updateVertexAgent()
349 if (not signalsBlocked() and _vertex.has_value() and _objectPosesConnection !=
nullptr)
352 QSignalBlocker blocker(
this);
355 frame->setCurrentIndex(0);
357 _framedPoseCoordinateConversion();
359 _updateVertexAttribs();
364 VertexDataWidget::_updateVertexFrame()
366 if (not signalsBlocked() and _vertex.has_value() and _objectPosesConnection !=
nullptr)
369 QSignalBlocker blocker(
this);
371 _framedPoseCoordinateConversion();
373 _updateVertexAttribs();
378 VertexDataWidget::_removeInstance()
380 if (not signalsBlocked() and _vertex.has_value())
383 if (agent->currentText().isEmpty())
389 QSignalBlocker blocker(
this);
391 ObjectID currentAgent(agent->currentText().toStdString());
392 QString newAgent = QString::fromStdString(currentAgent.getClassID().str());
393 if (agent->findText(newAgent) < 0)
395 agent->insertItem(0, newAgent);
397 agent->setCurrentText(newAgent);
399 _updateVertexAttribs();
403 std::vector<QDoubleSpinBox*>
404 VertexDataWidget::_positionSpinBoxes()
409 std::vector<QDoubleSpinBox*>
410 VertexDataWidget::_angleSpinBoxes()
412 return {roll, pitch, yaw};
415 std::vector<QDoubleSpinBox*>
416 VertexDataWidget::_allSpinBoxes()
418 return {x, y, z, roll, pitch, yaw};
424 _setXyz(simox::math::position(
pose.matrix()));
425 _setRpyRad(simox::math::mat4f_to_rpy(
pose.matrix()));
429 VertexDataWidget::_setXyz(
const Eigen::Vector3d& xyz)
431 x->setValue(
xyz.x());
432 y->setValue(
xyz.y());
433 z->setValue(
xyz.z());
437 VertexDataWidget::_rpyRaw()
const
439 return {roll->value(), pitch->value(), yaw->value()};
443 VertexDataWidget::_setRpyRaw(
const Eigen::Vector3d& rpy)
const
445 roll->setValue(rpy(0));
446 pitch->setValue(rpy(1));
447 yaw->setValue(rpy(2));
451 VertexDataWidget::_setRpyDeg(
const Eigen::Vector3d& rpyDeg)
const
453 if (angleUnitDeg->isChecked())
457 else if (angleUnitRad->isChecked())
459 _setRpyRaw(simox::math::deg_to_rad(
rpyDeg));
464 VertexDataWidget::_setRpyRad(
const Eigen::Vector3d& rpyRad)
const
466 if (angleUnitDeg->isChecked())
468 _setRpyRaw(simox::math::rad_to_deg(
rpyRad));
470 else if (angleUnitRad->isChecked())
477 VertexDataWidget::_setFromCurrentRobotPose()
481 QSignalBlocker blocker(
this);
484 _updateVertexAttribs();
488 VertexDataWidget::_loadFramedPoseFromVertex(
const GuiGraph::Vertex& vertex)
491 QString currAgent = QString::fromStdString(
vertex.attrib().getPose().agent);
492 if (agent->findText(currAgent) < 0)
494 agent->insertItem(0, currAgent);
496 agent->setCurrentText(currAgent);
500 QString currFrame = QString::fromStdString(
vertex.attrib().getPose().frame);
501 if (frame->findText(currFrame) < 0)
503 frame->insertItem(0, currFrame);
505 frame->setCurrentText(currFrame);
509 VertexDataWidget::_updateAgentMenu()
513 if (_objectPosesConnection ==
nullptr)
518 agent->addItem(QString::fromAscii(
""));
520 for (
const auto& [
id,
object] : map)
522 agent->addItem(QString::fromStdString(
id.
str()));
527 VertexDataWidget::_updateFrameMenu()
531 if (_objectPosesConnection ==
nullptr)
536 const auto nodes = [&]() -> std::optional<std::vector<std::string>>
538 const auto& currentObj = agent->currentText().toStdString();
539 if (currentObj.empty())
546 std::optional<ObjectInfo> info = finder.
findObject(currentObj);
547 if (!info.has_value())
552 std::optional<PackageFileLocation> articulatedModel = info->articulatedSimoxXML();
553 if (!articulatedModel.has_value())
559 articulatedModel.value().relativePath);
560 const auto robot = VirtualRobot::RobotIO::loadRobot(
561 modelPath.toSystemPath(), VirtualRobot::BaseIO::eStructure);
562 if (robot ==
nullptr)
567 return robot->getRobotNodeNames();
570 std::vector<std::string> frames = nodes().value_or(std::vector<std::string>{
"root"});
572 for (
const auto& i : frames)
574 frame->addItem(QString::fromStdString(i));
579 VertexDataWidget::_framedPoseCoordinateConversion()
582 std::vector<ObjectInfo> objectInfo = _objectPosesConnection->
getObjectInfo();
585 const auto globalPose =
587 if (!globalPose.pose.has_value())
591 const core::Pose_d global_T_location = globalPose.pose.value().cast<
double>();
594 const std::string newAgent = agent->currentText().toStdString();
595 const std::string newFrame = frame->currentText().toStdString();
599 if (!
object.
pose.has_value())
603 const core::Pose_d global_T_object =
object.pose.value().cast<
double>();
604 const core::Pose_d object_T_global = global_T_object.inverse();
606 const core::Pose_d object_T_location = object_T_global * global_T_location;
607 _setPose(object_T_location);