26#include <SimoxUtility/algorithm/string.h>
27#include <SimoxUtility/json.h>
28#include <VirtualRobot/Nodes/RobotNode.h>
29#include <VirtualRobot/Robot.h>
30#include <VirtualRobot/RobotNodeSet.h>
31#include <VirtualRobot/Visualization/CoinVisualization/CoinVisualization.h>
32#include <VirtualRobot/Visualization/VisualizationFactory.h>
33#include <VirtualRobot/XML/RobotIO.h>
48#include <RobotAPI/gui-plugins/KinematicUnitPlugin/ui_KinematicUnitConfigDialog.h>
49#include <RobotAPI/interface/core/NameValueMap.h>
50#include <RobotAPI/interface/units/KinematicUnitInterface.h>
57#include <QInputDialog>
63#include <QTableWidget>
70#include <Inventor/Qt/SoQt.h>
71#include <Inventor/SoDB.h>
88#define KINEMATIC_UNIT_NAME_DEFAULT "Robot"
101 qRegisterMetaType<DebugInfo>(
"DebugInfo");
108 enableValueValidator(true),
110 currentValueMax(5.0f)
121 ui.radioButtonUnknown->setHidden(
true);
138 std::string debugDrawerComponentName =
"KinemticUnitGUIDebugDrawer_" +
getName();
139 ARMARX_INFO <<
"Creating component " << debugDrawerComponentName;
159 std::unique_lock lock(*
mutex3D);
175 jointCurrentHistory.clear();
176 jointCurrentHistory.set_capacity(5);
187 Ice::StringSeq includePaths;
196 for (
const std::string& projectName : packages)
198 if (projectName.empty())
204 auto pathsString = project.getDataDir();
205 ARMARX_VERBOSE <<
"Data paths of ArmarX package " << projectName <<
": "
207 Ice::StringSeq projectIncludePaths =
Split(pathsString,
";,",
true,
true);
208 ARMARX_VERBOSE <<
"Result: Data paths of ArmarX package " << projectName <<
": "
209 << projectIncludePaths;
211 includePaths.end(), projectIncludePaths.begin(), projectIncludePaths.end());
228 ARMARX_INFO <<
"Loading robot from file " << rfile;
229 robot = loadRobotFile(rfile);
231 catch (
const std::exception& e)
251 if (not simox::alg::starts_with(
robot->getName(),
"Armar3"))
253 ARMARX_VERBOSE <<
"Disable the SetZero button because the robot name is '"
254 <<
robot->getName() <<
"'.";
255 ui.pushButtonKinematicUnitPos1->setDisabled(
true);
275 QMetaObject::invokeMethod(
this,
"resetSlider");
294 ARMARX_INFO <<
"Connection to kinemetic unit lost. Update task terminates.";
313 std::unique_lock lock(mutexNodeSet);
320 std::unique_lock lock(*
mutex3D);
341 std::unique_lock lock(*
mutex3D);
381 dialog->setName(dialog->getDefaultName());
384 return qobject_cast<KinematicUnitConfigDialog*>(dialog);
392 enableValueValidator = dialog->ui->checkBox->isChecked();
393 viewerEnabled = dialog->ui->checkBox3DViewerEnabled->isChecked();
394 historyTime = dialog->ui->spinBoxHistory->value() * 1000;
395 currentValueMax = dialog->ui->doubleSpinBoxMaxMinCurrent->value();
404 enableValueValidator = settings->value(
"enableValueValidator",
true).toBool();
405 viewerEnabled = settings->value(
"viewerEnabled",
true).toBool();
406 historyTime = settings->value(
"historyTime", 100).toInt() * 1000;
407 currentValueMax = settings->value(
"currentValueMax", 5.0).toFloat();
413 settings->setValue(
"kinematicUnitName", QString::fromStdString(
kinematicUnitName));
414 settings->setValue(
"enableValueValidator", enableValueValidator);
415 settings->setValue(
"viewerEnabled", viewerEnabled);
416 assert(historyTime % 1000 == 0);
417 settings->setValue(
"historyTime",
static_cast<int>(historyTime / 1000));
418 settings->setValue(
"currentValueMax", currentValueMax);
442 std::unique_lock lock(mutexNodeSet);
449 if (selectedControlMode == ePositionControl)
451 values = debugInfo.jointAngles;
453 else if (selectedControlMode == eVelocityControl)
455 values = debugInfo.jointVelocities;
460 for (
auto& kv : values)
462 serializer->setFloat(kv.first, kv.second);
464 const QString json = QString::fromStdString(serializer->asString(
true));
465 QClipboard* clipboard = QApplication::clipboard();
466 clipboard->setText(json);
467 QApplication::processEvents();
496 ARMARX_INFO <<
"viewer disabled - returning null scene";
504 connect(
ui.pushButtonKinematicUnitPos1,
507 SLOT(kinematicUnitZeroPosition()));
510 ui.nodeListComboBox, SIGNAL(currentIndexChanged(
int)),
this, SLOT(
selectJoint(
int)));
511 connect(
ui.horizontalSliderKinematicUnitPos,
512 SIGNAL(valueChanged(
int)),
516 connect(
ui.horizontalSliderKinematicUnitPos,
517 SIGNAL(sliderReleased()),
521 connect(
ui.radioButtonPositionControl,
522 SIGNAL(clicked(
bool)),
525 connect(
ui.radioButtonVelocityControl,
526 SIGNAL(clicked(
bool)),
535 connect(
ui.showDebugLayer,
536 SIGNAL(toggled(
bool)),
539 Qt::QueuedConnection);
545 Qt::QueuedConnection);
550 Qt::QueuedConnection);
555 Qt::QueuedConnection);
560 Qt::QueuedConnection);
565 Qt::QueuedConnection);
570 Qt::QueuedConnection);
575 Qt::QueuedConnection);
577 connect(
ui.tableJointList,
578 SIGNAL(cellDoubleClicked(
int,
int)),
581 Qt::QueuedConnection);
583 connect(
ui.checkBoxUseDegree,
587 Qt::QueuedConnection);
606 ui.widgetSliderFactor->setVisible(
false);
619 std::unique_lock lock(mutexNodeSet);
620 std::vector<VirtualRobot::RobotNodePtr> rn =
robotNodeSet->getAllRobotNodes();
622 NameControlModeMap jointModes;
624 for (
unsigned int i = 0; i < rn.size(); i++)
626 jointModes[rn[i]->getName()] = eVelocityControl;
627 vels[rn[i]->getName()] = 0.0f;
640 if (selectedControlMode == eVelocityControl)
642 ui.horizontalSliderKinematicUnitPos->setSliderPosition(SLIDER_ZERO_POSITION);
651 if (selectedControlMode == eVelocityControl || selectedControlMode == eTorqueControl)
655 else if (selectedControlMode == ePositionControl)
662 const bool isDeg =
ui.checkBoxUseDegree->isChecked();
665 const float conversionFactor = isDeg ? 180.0 /
M_PI : 1.0f;
666 const float pos =
currentNode->getJointValue() * conversionFactor;
668 ui.lcdNumberKinematicUnitJointValue->display((
int)pos);
669 ui.horizontalSliderKinematicUnitPos->setSliderPosition((
int)(pos * factor));
677 ui.lcdNumberKinematicUnitJointValue->display((
int)pos);
678 ui.horizontalSliderKinematicUnitPos->setSliderPosition((
int)(pos * factor));
689 if (selectedControlMode == eVelocityControl || selectedControlMode == eTorqueControl)
691 ui.horizontalSliderKinematicUnitPos->setSliderPosition(SLIDER_ZERO_POSITION);
692 ui.lcdNumberKinematicUnitJointValue->display(SLIDER_ZERO_POSITION);
699 ARMARX_VERBOSE <<
"Setting control mode of radio button group to " << controlMode;
705 case ePositionVelocityControl:
706 ui.radioButtonUnknown->setChecked(
true);
708 case ePositionControl:
709 ui.radioButtonPositionControl->setChecked(
true);
711 case eVelocityControl:
712 ui.radioButtonVelocityControl->setChecked(
true);
715 ui.radioButtonTorqueControl->setChecked(
true);
723 if (!
ui.radioButtonPositionControl->isChecked())
727 NameControlModeMap jointModes;
729 ui.widgetSliderFactor->setVisible(
false);
735 const QString unit = [&]() -> QString
740 if (
ui.checkBoxUseDegree->isChecked())
753 throw std::invalid_argument(
"unknown/unsupported joint type");
756 ui.labelUnit->setText(unit);
759 const auto [factor, conversionFactor] = [&]() -> std::pair<float, float>
764 const bool isDeg =
ui.checkBoxUseDegree->isChecked();
777 throw std::invalid_argument(
"unknown/unsupported joint type");
780 jointModes[
currentNode->getName()] = ePositionControl;
787 const float lo =
currentNode->getJointLimitLo() * conversionFactor;
788 const float hi =
currentNode->getJointLimitHi() * conversionFactor;
804 const float pos =
currentNode->getJointValue() * conversionFactor;
805 ARMARX_INFO <<
"Setting position control for current node "
806 <<
"(name '" <<
currentNode->getName() <<
"' with current value " << pos
811 ui.horizontalSliderKinematicUnitPos->blockSignals(
true);
813 const float sliderMax =
hi * factor;
814 const float sliderMin =
lo * factor;
816 ui.horizontalSliderKinematicUnitPos->setMaximum(sliderMax);
817 ui.horizontalSliderKinematicUnitPos->setMinimum(sliderMin);
819 const std::size_t desiredNumberOfTicks = 1'000;
821 const float tickInterval = (sliderMax - sliderMin) / desiredNumberOfTicks;
824 ui.horizontalSliderKinematicUnitPos->setTickInterval(tickInterval);
825 ui.lcdNumberKinematicUnitJointValue->display(pos);
827 ui.horizontalSliderKinematicUnitPos->blockSignals(
false);
835 if (!
ui.radioButtonVelocityControl->isChecked())
839 NameControlModeMap jointModes;
840 NameValueMap jointVelocities;
844 jointModes[
currentNode->getName()] = eVelocityControl;
850 const QString unit = [&]() -> QString
855 if (
ui.checkBoxUseDegree->isChecked())
860 return "rad/(100*s)";
868 throw std::invalid_argument(
"unknown/unsupported joint type");
872 ui.labelUnit->setText(unit);
873 ARMARX_INFO <<
"setting velocity control for current Node Name: "
876 const bool isDeg =
ui.checkBoxUseDegree->isChecked();
877 const bool isRot =
currentNode->isRotationalJoint() or
880 const float lo = isRot ? (isDeg ? -90 : -
M_PI * 100) : -1000;
881 const float hi = isRot ? (isDeg ? +90 : +
M_PI * 100) : 1000;
895 ui.widgetSliderFactor->setVisible(
true);
897 ui.horizontalSliderKinematicUnitPos->blockSignals(
true);
898 ui.horizontalSliderKinematicUnitPos->setMaximum(
hi);
899 ui.horizontalSliderKinematicUnitPos->setMinimum(
lo);
900 ui.horizontalSliderKinematicUnitPos->blockSignals(
false);
908 if (
ui.radioButtonPositionControl->isChecked())
910 return ControlMode::ePositionControl;
913 if (
ui.radioButtonVelocityControl->isChecked())
915 return ControlMode::eVelocityControl;
918 if (
ui.radioButtonTorqueControl->isChecked())
920 return ControlMode::eTorqueControl;
925 return ControlMode::eUnknown;
931 if (!
ui.radioButtonTorqueControl->isChecked())
935 NameControlModeMap jointModes;
939 jointModes[
currentNode->getName()] = eTorqueControl;
940 ui.labelUnit->setText(
"Ncm");
941 ARMARX_INFO <<
"setting torque control for current Node Name: "
955 ui.horizontalSliderKinematicUnitPos->blockSignals(
true);
956 ui.horizontalSliderKinematicUnitPos->setMaximum(20000.0);
957 ui.horizontalSliderKinematicUnitPos->setMinimum(-20000.0);
959 ui.widgetSliderFactor->setVisible(
true);
961 ui.horizontalSliderKinematicUnitPos->blockSignals(
false);
967 KinematicUnitWidgetController::loadRobotFile(std::string fileName)
979 ARMARX_INFO <<
"Could not find Robot XML file with name " << fileName <<
flush;
982 robot = VirtualRobot::RobotIO::loadRobot(fileName);
986 ARMARX_INFO <<
"Could not find Robot XML file with name " << fileName <<
"("
993 VirtualRobot::CoinVisualizationPtr
996 VirtualRobot::CoinVisualizationPtr coinVisualization;
1001 coinVisualization =
robot->getVisualization();
1003 if (!coinVisualization || !coinVisualization->getCoinVisualization())
1009 return coinVisualization;
1012 VirtualRobot::RobotNodeSetPtr
1014 std::string nodeSetName)
1016 VirtualRobot::RobotNodeSetPtr nodeSetPtr;
1020 nodeSetPtr =
robot->getRobotNodeSet(nodeSetName);
1024 ARMARX_INFO <<
"RobotNodeSet with name " << nodeSetName <<
" is not defined"
1033 KinematicUnitWidgetController::initGUIComboBox(VirtualRobot::RobotNodeSetPtr robotNodeSet)
1035 ui.nodeListComboBox->clear();
1039 std::vector<VirtualRobot::RobotNodePtr> rn =
robotNodeSet->getAllRobotNodes();
1041 for (
unsigned int i = 0; i < rn.size(); i++)
1044 QString name(rn[i]->
getName().c_str());
1045 ui.nodeListComboBox->addItem(name);
1047 ui.nodeListComboBox->setCurrentIndex(-1);
1054 KinematicUnitWidgetController::initGUIJointListTable(VirtualRobot::RobotNodeSetPtr robotNodeSet)
1056 uint numberOfColumns = 10;
1065 std::vector<VirtualRobot::RobotNodePtr> rn =
robotNodeSet->getAllRobotNodes();
1071 ui.tableJointList->setRowCount(rn.size());
1083 <<
"Angle [deg]/Position [mm]"
1084 <<
"Velocity [deg/s]/[mm/s]"
1085 <<
"Torque [Nm] / PWM"
1087 <<
"Temperature [C]"
1091 <<
"Emergency Stop";
1092 ui.tableJointList->setHorizontalHeaderLabels(s);
1094 <<
"Current table size: " <<
ui.tableJointList->columnCount();
1098 for (
unsigned int i = 0; i < rn.size(); i++)
1101 QString name(rn[i]->
getName().c_str());
1103 QTableWidgetItem* newItem =
new QTableWidgetItem(name);
1108 for (
unsigned int i = 0; i < rn.size(); i++)
1110 for (
unsigned int j = 1; j < numberOfColumns; j++)
1112 QString state =
"--";
1113 QTableWidgetItem* newItem =
new QTableWidgetItem(state);
1114 ui.tableJointList->setItem(i, j, newItem);
1135 std::unique_lock lock(mutexNodeSet);
1137 ARMARX_INFO <<
"Selected index: " <<
ui.nodeListComboBox->currentIndex();
1148 if (controlModes.count(
currentNode->getName()) == 0)
1151 <<
"` from kinematic unit!";
1155 const auto controlMode = controlModes.at(
currentNode->getName());
1158 if (controlMode == ePositionControl)
1162 else if (controlMode == eVelocityControl)
1165 ui.horizontalSliderKinematicUnitPos->setSliderPosition(SLIDER_ZERO_POSITION);
1167 else if (controlMode == eTorqueControl)
1170 ui.horizontalSliderKinematicUnitPos->setSliderPosition(SLIDER_ZERO_POSITION);
1179 ui.nodeListComboBox->setCurrentIndex(row);
1187 std::unique_lock lock(mutexNodeSet);
1194 const float value =
static_cast<float>(
ui.horizontalSliderKinematicUnitPos->value());
1198 const bool isDeg =
ui.checkBoxUseDegree->isChecked();
1202 if (currentControlMode == ePositionControl)
1206 float conversionFactor = isRot && isDeg ? 180.0 /
M_PI : 1.0f;
1208 NameValueMap jointAngles;
1210 jointAngles[
currentNode->getName()] = value / conversionFactor / factor;
1211 ui.lcdNumberKinematicUnitJointValue->display(value / factor);
1223 else if (currentControlMode == eVelocityControl)
1225 float conversionFactor = isRot ? (isDeg ? 180.0 /
M_PI : 100.f) : 1.0f;
1226 NameValueMap jointVelocities;
1228 value / conversionFactor *
1229 static_cast<float>(
ui.doubleSpinBoxKinematicUnitPosFactor->value());
1230 ui.lcdNumberKinematicUnitJointValue->display(value);
1243 else if (currentControlMode == eTorqueControl)
1245 NameValueMap jointTorques;
1246 float torqueTargetValue =
1248 static_cast<float>(
ui.doubleSpinBoxKinematicUnitPosFactor->value());
1249 jointTorques[
currentNode->getName()] = torqueTargetValue;
1250 ui.lcdNumberKinematicUnitJointValue->display(torqueTargetValue);
1271 const NameControlModeMap& reportedJointControlModes)
1278 std::unique_lock lock(mutexNodeSet);
1279 std::vector<VirtualRobot::RobotNodePtr> rn =
robotNodeSet->getAllRobotNodes();
1281 for (
unsigned int i = 0; i < rn.size(); i++)
1283 NameControlModeMap::const_iterator it;
1284 it = reportedJointControlModes.find(rn[i]->
getName());
1287 if (it == reportedJointControlModes.end())
1293 ControlMode currentMode = it->second;
1296 switch (currentMode)
1314 case ePositionControl:
1318 case eVelocityControl:
1322 case eTorqueControl:
1327 case ePositionVelocityControl:
1328 state =
"Position + Velocity";
1333 state = QString(
"<nyi Mode: %1>").arg(
static_cast<int>(currentMode));
1338 QTableWidgetItem* newItem =
new QTableWidgetItem(state);
1345 const NameStatusMap& reportedJointStatuses)
1352 std::unique_lock lock(mutexNodeSet);
1353 std::vector<VirtualRobot::RobotNodePtr> rn =
robotNodeSet->getAllRobotNodes();
1355 for (
unsigned int i = 0; i < rn.size(); i++)
1358 auto it = reportedJointStatuses.find(rn[i]->
getName());
1359 if (it == reportedJointStatuses.end())
1362 << rn[i]->getName() <<
" was not reported!";
1365 JointStatus currentStatus = it->second;
1368 QTableWidgetItem* newItem =
new QTableWidgetItem(state);
1372 newItem =
new QTableWidgetItem(state);
1375 state = currentStatus.enabled ?
"yes" :
"no";
1376 newItem =
new QTableWidgetItem(state);
1379 state = currentStatus.emergencyStop ?
"yes" :
"no";
1380 newItem =
new QTableWidgetItem(state);
1403 return "Initialized";
1432 std::unique_lock lock(mutexNodeSet);
1438 std::vector<VirtualRobot::RobotNodePtr> rn =
robotNodeSet->getAllRobotNodes();
1441 for (
unsigned int i = 0; i < rn.size(); i++)
1443 NameValueMap::const_iterator it;
1444 VirtualRobot::RobotNodePtr node = rn[i];
1445 it = reportedJointAngles.find(node->getName());
1447 if (it == reportedJointAngles.end())
1452 const float currentValue = it->second;
1455 float conversionFactor =
ui.checkBoxUseDegree->isChecked() &&
1456 (node->isRotationalJoint() or
1457 node->isHemisphereJoint() or node->isFourBarJoint())
1460 ui.tableJointList->model()->setData(
1462 (
int)(cutJitter(currentValue * conversionFactor) * 100) / 100.0f,
1464 ui.tableJointList->model()->setData(
1466 ui.tableJointList->model()->setData(
1473 const NameValueMap& reportedJointVelocities)
1480 std::unique_lock lock(mutexNodeSet);
1485 std::vector<VirtualRobot::RobotNodePtr> rn =
robotNodeSet->getAllRobotNodes();
1486 QTableWidgetItem* newItem;
1488 for (
unsigned int i = 0; i < rn.size(); i++)
1490 NameValueMap::const_iterator it;
1491 it = reportedJointVelocities.find(rn[i]->
getName());
1493 if (it == reportedJointVelocities.end())
1498 float currentValue = it->second;
1499 if (
ui.checkBoxUseDegree->isChecked() &&
1500 (rn[i]->isRotationalJoint() or rn[i]->isHemisphereJoint() or
1501 rn[i]->isFourBarJoint()))
1503 currentValue *= 180.0 /
M_PI;
1505 const QString Text = QString::number(cutJitter(currentValue),
'g', 2);
1506 newItem =
new QTableWidgetItem(Text);
1516 std::unique_lock lock(mutexNodeSet);
1521 std::vector<VirtualRobot::RobotNodePtr> rn =
robotNodeSet->getAllRobotNodes();
1522 QTableWidgetItem* newItem;
1523 NameValueMap::const_iterator it;
1525 for (
unsigned int i = 0; i < rn.size(); i++)
1527 it = reportedJointTorques.find(rn[i]->
getName());
1529 if (it == reportedJointTorques.end())
1534 const float currentValue = it->second;
1535 newItem =
new QTableWidgetItem(QString::number(cutJitter(currentValue)));
1542 const NameValueMap& reportedJointCurrents,
1543 const NameStatusMap& reportedJointStatuses)
1547 std::unique_lock lock(mutexNodeSet);
1552 std::vector<VirtualRobot::RobotNodePtr> rn =
robotNodeSet->getAllRobotNodes();
1553 QTableWidgetItem* newItem;
1557 NameValueMap::const_iterator it;
1559 for (
unsigned int i = 0; i < rn.size(); i++)
1561 it = reportedJointCurrents.find(rn[i]->
getName());
1563 if (it == reportedJointCurrents.end())
1568 const float currentValue = it->second;
1569 newItem =
new QTableWidgetItem(QString::number(cutJitter(currentValue)));
1578 const NameValueMap& reportedJointTemperatures)
1582 std::unique_lock lock(mutexNodeSet);
1587 std::vector<VirtualRobot::RobotNodePtr> rn =
robotNodeSet->getAllRobotNodes();
1588 QTableWidgetItem* newItem;
1589 NameValueMap::const_iterator it;
1591 for (
unsigned int i = 0; i < rn.size(); i++)
1593 it = reportedJointTemperatures.find(rn[i]->
getName());
1595 if (it == reportedJointTemperatures.end())
1600 const float currentValue = it->second;
1601 newItem =
new QTableWidgetItem(QString::number(cutJitter(currentValue)));
1611 std::unique_lock lock(mutexNodeSet);
1616 robot->setJointValues(reportedJointAngles);
1619 std::optional<float>
1620 mean(
const boost::circular_buffer<NameValueMap>& buffer,
const std::string& key)
1623 std::size_t count = 0;
1625 for (
const auto& element : buffer)
1627 if (element.count(key) > 0)
1629 sum += element.at(key);
1635 return std::nullopt;
1638 return sum /
static_cast<float>(count);
1643 const NameStatusMap& reportedJointStatuses)
1645 if (!enableValueValidator)
1650 std::unique_lock lock(mutexNodeSet);
1652 std::vector<VirtualRobot::RobotNodePtr> rn =
robotNodeSet->getAllRobotNodes();
1655 static std::vector<QBrush> standardColors;
1656 if (standardColors.size() == 0)
1658 for (
unsigned int i = 0; i < rn.size(); i++)
1661 standardColors.push_back(
1667 for (
unsigned int i = 0; i < rn.size(); i++)
1669 const auto& jointName = rn[i]->getName();
1671 const auto currentSmoothValOpt =
mean(jointCurrentHistory, jointName);
1672 if (not currentSmoothValOpt.has_value())
1677 const float smoothValue = std::fabs(currentSmoothValOpt.value());
1679 if (jointCurrentHistory.front().count(jointName) == 0)
1684 const float startValue = jointCurrentHistory.front().at(jointName);
1685 const bool isStatic = (smoothValue == startValue);
1687 NameStatusMap::const_iterator it;
1688 it = reportedJointStatuses.find(rn[i]->
getName());
1689 JointStatus currentStatus = it->second;
1693 if (currentStatus.operation != eOffline)
1699 else if (std::abs(smoothValue) > currentValueMax)
1728 customToolbar->setParent(parent);
1732 customToolbar =
new QToolBar(parent);
1735 return customToolbar.data();
1739 KinematicUnitWidgetController::cutJitter(
float value)
1741 return (
abs(value) <
static_cast<float>(
ui.jitterThresholdSpinBox->value())) ? 0 : value;
1777 RangeValueDelegate::paint(QPainter* painter,
1778 const QStyleOptionViewItem&
option,
1779 const QModelIndex&
index)
const
1787 if (hiDeg - loDeg <= 0)
1789 QStyledItemDelegate::paint(painter,
option,
index);
1793 QStyleOptionProgressBar progressBarOption;
1794 progressBarOption.rect =
option.rect;
1795 progressBarOption.minimum = loDeg;
1796 progressBarOption.maximum = hiDeg;
1797 progressBarOption.progress = jointValue;
1798 progressBarOption.text = QString::number(jointValue);
1799 progressBarOption.textVisible =
true;
1801 pal.setColor(QPalette::Background, Qt::red);
1802 progressBarOption.palette = pal;
1803 QApplication::style()->drawControl(QStyle::CE_ProgressBar, &progressBarOption, painter);
1807 QStyledItemDelegate::paint(painter,
option,
index);
1827 const auto text = QInputDialog::getMultiLineText(
1828 __widget, tr(
"JSON Joint values"), tr(
"Json:"),
"{\n}", &ok)
1831 if (!ok || text.empty())
1836 NameValueMap jointAngles;
1839 jointAngles = simox::json::json2NameValueMap(text);
1846 NameControlModeMap jointModes;
1847 for (
const auto& [key, _] : jointAngles)
1849 jointModes[key] = ePositionControl;
1867 robot->setJointValues(currentJointAngles);
constexpr float SLIDER_POS_RAD_MULTIPLIER
#define KINEMATIC_UNIT_NAME_DEFAULT
constexpr float SLIDER_POS_DEG_MULTIPLIER
constexpr float SLIDER_POS_HEMI_MULTIPLIER
SpamFilterDataPtr deactivateSpam(SpamFilterDataPtr const &spamFilter, float deactivationDurationSec, const std::string &identifier, bool deactivate)
static const std::string & GetProjectName()
static bool getAbsolutePath(const std::string &relativeFilename, std::string &storeAbsoluteFilename, const std::vector< std::string > &additionalSearchPaths={}, bool verbose=true)
std::enable_if<!HasGetWidgetName< ArmarXWidgetType >::value >::type addWidget()
The CMakePackageFinder class provides an interface to the CMake Package finder capabilities.
static DateTime Now()
Current time on the virtual clock.
static TPtr create(Ice::PropertiesPtr properties=Ice::createProperties(), const std::string &configName="", const std::string &configDomain="ArmarX")
Factory method for a component.
static Frequency Hertz(std::int64_t hertz)
The JSONObject class is used to represent and (de)serialize JSON objects.
bool usingProxy(const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list.
ArmarXObjectSchedulerPtr getObjectScheduler() const
std::string getName() const
Retrieve name of object.
Ice::ObjectPrx getProxy(long timeoutMs=0, bool waitForScheduler=true) const
Returns the proxy of this object (optionally it waits for the proxy)
ArmarXManagerPtr getArmarXManager() const
Returns the ArmarX manager used to add and remove components.
Ice::PropertiesPtr getIceProperties() const
Returns the set of Ice properties.
Simple rate limiter for use in loops to maintain a certain frequency given a clock.
Duration waitForNextTick() const
Wait and block until the target period is met.
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
#define ARMARX_CHECK_NOT_NULL(ptr)
This macro evaluates whether ptr is not null and if it turns out to be false it will throw an Express...
#define ARMARX_INFO
The normal logging level.
#define ARMARX_IMPORTANT
The logging level for always important information, but expected behaviour (in contrast to ARMARX_WAR...
#define ARMARX_ERROR
The logging level for unexpected behaviour, that must be fixed.
#define ARMARX_DEBUG
The logging level for output that is only interesting while debugging.
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
#define ARMARX_VERBOSE
The logging level for verbose information.
std::shared_ptr< class Robot > RobotPtr
double s(double t, double s0, double v0, double a0, double j)
This file offers overloads of toIce() and fromIce() functions for STL container types.
IceUtil::Handle< ArmarXManager > ArmarXManagerPtr
std::optional< float > mean(const boost::circular_buffer< NameValueMap > &buffer, const std::string &key)
std::vector< std::string > Split(const std::string &source, const std::string &splitBy, bool trimElements=false, bool removeEmptyElements=false)
std::vector< T > abs(const std::vector< T > &v)
IceInternal::Handle< JSONObject > JSONObjectPtr
const LogSender::manipulator flush