25#include <SimoxUtility/color/Color.h>
26#include <VirtualRobot/MathTools.h>
27#include <VirtualRobot/Nodes/RobotNode.h>
28#include <VirtualRobot/RobotNodeSet.h>
48 NJointControllerRegistration<NJointTaskspaceMixedImpedanceVelocityController>
50 "NJointTaskspaceMixedImpedanceVelocityController");
58 arm->kinematicChainName = nodeSetName;
59 VirtualRobot::RobotNodeSetPtr rtRns =
60 rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
61 VirtualRobot::RobotNodeSetPtr nonRtRns =
62 nonRtRobotPtr->getRobotNodeSet(arm->kinematicChainName);
65 ARMARX_IMPORTANT <<
"Creating Taskspace Impedance controller with kinematic chain: "
66 << arm->kinematicChainName <<
" with num of joints: (RT robot) "
67 << rtRns->getSize() <<
", and (non-RT robot) " << nonRtRns->getSize();
69 std::vector<size_t> jointIDTorqueMode;
70 std::vector<size_t> jointIDVelocityMode;
71 arm->jointNames.clear();
72 for (
size_t i = 0; i < rtRns->getSize(); ++i)
74 std::string jointName = rtRns->getNode(i)->getName();
75 arm->jointNames.push_back(jointName);
77 bool foundControlDevice =
false;
79 cfg.jointNameListTorque.begin(), cfg.jointNameListTorque.end(), jointName);
80 if (it != cfg.jointNameListTorque.end())
84 <<
"Could not get control target for " <<
QUOTED(jointName) <<
". "
85 <<
"If this joint is currently not available (e.g., belonging to an "
86 <<
"unavailable arm), make sure to select a controller config that respects "
88 auto* casted_ct = ct->
asA<ControlTarget1DoFActuatorTorque>();
90 arm->targetsTorque.push_back(casted_ct);
91 jointIDTorqueMode.push_back(i);
92 foundControlDevice =
true;
96 cfg.jointNameListVelocity.begin(), cfg.jointNameListVelocity.end(), jointName);
97 if (it != cfg.jointNameListVelocity.end())
101 auto* casted_ct = ct->
asA<ControlTarget1DoFActuatorVelocity>();
103 arm->targetsVel.push_back(casted_ct);
104 jointIDVelocityMode.push_back(i);
105 foundControlDevice =
true;
107 if (not foundControlDevice)
112 ARMARX_ERROR <<
"Does not found valid control device for joint name: " << jointName
113 <<
"Please check torque controlled joints: [" << namesTorque
114 <<
"] and velocity controlled joints: [" << namesVelocity <<
"].";
119 arm->sensorDevices.append(sv, jointName);
121 ARMARX_DEBUG <<
"Number of torque controlled joints " << jointIDTorqueMode.size();
122 ARMARX_DEBUG <<
"Number of velocity controlled joints " << jointIDVelocityMode.size();
124 jointIDTorqueMode.size() + jointIDVelocityMode.size());
126 arm->controller.initialize(nonRtRns, rtRns, jointIDTorqueMode, jointIDVelocityMode);
127 arm->controller.ftsensor.initialize(rtRns,
robotUnit, cfg.ftConfig);
131 arm->nonRtConfig = cfg;
132 arm->rtStatus.reset(rtRns->getSize(), jointIDTorqueMode, jointIDVelocityMode);
137 const NJointControllerConfigPtr& config,
143 ConfigPtrT cfg = ConfigPtrT::dynamicCast(config);
153 limb.emplace(pair.first, std::make_unique<ArmData>());
165 <<
hands->hands.at(pair.first)->kinematicChainName;
174 return "NJointTaskspaceMixedImpedanceVelocityController";
180 std::string taskName =
getClassName() +
"AdditionalTask";
192 while (
getState() == eManagedIceObjectStarted)
198 c.waitForCycleDuration();
206 arm->bufferConfigNonRtToRt.getWriteBuffer() = arm->nonRtConfig;
207 arm->bufferConfigNonRtToRt.commitWrite();
216 if (not rtTargetSafe)
222 std::tuple<bool, bool>
227 bool rtTargetSafe =
true;
228 bool forceTorqueSafe =
true;
229 for (
auto& pair :
limb)
231 auto& arm = pair.second;
232 arm->nonRtConfig = arm->bufferConfigUserToNonRt.getUpToDateReadBuffer();
233 arm->rtStatusInNonRT = arm->bufferRtStatusToNonRt.getUpToDateReadBuffer();
234 rtSafe = rtSafe and pair.second->rtStatusInNonRT.rtSafe;
235 rtTargetSafe = rtTargetSafe and pair.second->rtStatusInNonRT.rtTargetSafe;
236 forceTorqueSafe = forceTorqueSafe and pair.second->rtStatusInNonRT.forceTorqueSafe;
240 hands->nonRTUpdateStatus();
242 return std::make_tuple(rtTargetSafe, forceTorqueSafe);
248 for (
auto& pair :
limb)
254 hands->nonRTSetTarget();
261 for (
auto& pair :
limb)
263 if (not pair.second->rtReady)
266 if (not pair.second->rtStatusInNonRT.rtTargetSafe)
269 pair.second->rtStatusInNonRT.currentPose,
270 pair.second->rtStatusInNonRT.desiredPoseUnsafe,
282 arm->rtConfig = arm->bufferConfigNonRtToRt.getUpToDateReadBuffer();
283 arm->rtStatus.deltaT = deltaT;
284 arm->rtStatus.accumulateTime += deltaT;
286 arm->controller.ftsensor.updateStatus(arm->rtConfig.ftConfig,
287 arm->rtStatus.currentForceTorque,
288 arm->rtStatus.deltaT,
289 arm->rtFirstRun.load());
290 arm->rtStatus.safeFTGuardOffset.head<3>() =
291 arm->controller.ftsensor.getSafeGuardForceOffset();
293 arm->sensorDevices.updateJointValues(
294 arm->rtStatus.jointPosition, arm->rtStatus.jointVelocity, arm->rtStatus.jointTorque);
298 arm->bufferRtStatusToNonRt.getWriteBuffer() = arm->rtStatus;
299 arm->bufferRtStatusToNonRt.commitWrite();
300 arm->bufferRtStatusToUser.getWriteBuffer() = arm->rtStatus;
301 arm->bufferRtStatusToUser.commitWrite();
307 const size_t nDoFTorque,
308 const size_t nDoFVelocity,
309 const Eigen::VectorXf& targetTorque,
310 const Eigen::VectorXf& targetVelocity)
312 for (
size_t i = 0; i < nDoFTorque; i++)
314 auto jointIdx = arm->controller.jointIDTorqueMode[i];
315 arm->targetsTorque.at(i)->torque = targetTorque(jointIdx);
316 if (!arm->targetsTorque.at(i)->isValid())
318 arm->targetsTorque.at(i)->torque = 0;
321 for (
size_t i = 0; i < nDoFVelocity; i++)
323 auto jointIdx = arm->controller.jointIDVelocityMode[i];
324 arm->targetsVel.at(i)->velocity = targetVelocity(jointIdx);
326 if (!arm->targetsVel.at(i)->isValid())
328 arm->targetsVel.at(i)->velocity = 0;
331 arm->bufferRtStatusToOnPublish.getWriteBuffer() = arm->rtStatus;
332 arm->bufferRtStatusToOnPublish.commitWrite();
334 arm->bufferConfigRtToOnPublish.getWriteBuffer() = arm->rtConfig;
335 arm->bufferConfigRtToOnPublish.commitWrite();
337 arm->bufferConfigRtToUser.getWriteBuffer() = arm->rtConfig;
338 arm->bufferConfigRtToUser.commitWrite();
340 if (arm->rtFirstRun.load())
342 arm->rtFirstRun.store(
false);
343 arm->rtReady.store(
true);
350 double time_measure = IceUtil::Time::now().toMicroSecondsDouble();
354 arm->controller.run(arm->rtConfig, arm->rtStatus);
355 double time_run_rt = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
358 arm->rtStatus.nDoFTorque,
359 arm->rtStatus.nDoFVelocity,
360 arm->rtStatus.desiredJointTorque,
361 arm->rtStatus.desiredJointVelocity);
363 double time_set_target = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
364 time_measure = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
366 if (time_measure > 200)
369 "run_rt_limb: %.2f\n"
370 "set_target_limb: %.2f\n"
372 time_run_rt - time_measure,
373 time_set_target - time_run_rt,
375 .deactivateSpam(1.0f);
382 const std::string& key,
383 const Eigen::Matrix4f& targetPose,
385 const Eigen::Matrix4f& pose,
395 data.targetPose = targetPose;
396 data.targetPoseMode = targetPoseMode;
399 data.stiffness = stiffness;
405 targetPose, targetPoseMode, pose, vel, ft, stiffness));
417 bool rtReady =
false;
418 for (
const auto& nodeset :
coordinator->getNodesetList())
420 auto& rts =
limb.at(nodeset)->rtStatus;
421 auto& rtc =
limb.at(nodeset)->rtConfig;
422 rtReady =
limb.at(nodeset)->rtReady.load();
425 rtc.desiredPoseFrameMode,
428 rts.currentForceTorque,
436 for (
const auto& nodeset :
coordinator->getNodesetList())
439 limb.at(nodeset)->rtConfig.desiredPoseFrameMode = PoseFrameMode::root;
445 const IceUtil::Time& ,
446 const IceUtil::Time& timeSinceLastIteration)
448 double deltaT = timeSinceLastIteration.toSecondsDouble();
449 for (
auto& pair :
limb)
456 for (
auto& pair :
limb)
458 limbRT(pair.second, deltaT);
462 hands->updateRTStatus(deltaT);
469 const ::armarx::aron::data::dto::DictPtr& dto,
470 const Ice::Current& iceCurrent)
478 bool desiredPoseFrameModeSame = prevCfg.limbs.at(pair.first).desiredPoseFrameMode ==
479 pair.second.desiredPoseFrameMode;
481 pair.second.desiredPose,
482 prevCfg.limbs.at(pair.first).desiredPose,
484 "previous desired pose",
485 pair.second.safeDistanceMMToGoal,
486 pair.second.safeRotAngleDegreeToGoal,
487 "updateConfig_" + pair.first))
490 pair.second.desiredPose = prevCfg.limbs.at(pair.first).desiredPose;
492 limb.at(pair.first)->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
493 limb.at(pair.first)->bufferConfigUserToNonRt.commitWrite();
504 for (
auto& pair :
limb)
507 pair.second->bufferConfigRtToUser.getUpToDateReadBuffer();
519 for (
auto& pair :
limb)
522 pair.second->bufferConfigRtToUser.getUpToDateReadBuffer();
533 const std::string& nodeSetName,
534 const bool forceGuard,
535 const bool torqueGuard,
536 const Ice::Current& iceCurrent)
541 it->second.ftConfig.enableSafeGuardForce = forceGuard;
542 it->second.ftConfig.enableSafeGuardTorque = torqueGuard;
543 limb.at(nodeSetName)->controller.ftsensor.enableSafeGuard(forceGuard, torqueGuard);
545 <<
"reset safe guard with force torque sensors: safe? "
546 <<
limb.at(nodeSetName)->controller.ftsensor.isSafe(it->second.ftConfig);
547 limb.at(nodeSetName)->bufferConfigUserToNonRt.getWriteBuffer() = it->second;
548 limb.at(nodeSetName)->bufferConfigUserToNonRt.commitWrite();
553 <<
" found in the controllers.";
560 const std::string& nodeSetName,
561 const Ice::Current& iceCurrent)
566 return limb.at(nodeSetName)->controller.ftsensor.ftSafe.load();
570 <<
" found in the controllers.";
576 const Ice::Current& iceCurrent)
578 std::vector<float> tcpVel;
579 auto& arm =
limb.at(rns);
580 auto s = arm->bufferRtStatusToUser.getUpToDateReadBuffer();
581 for (
int i = 0; i < s.currentTwist.size(); i++)
583 tcpVel.push_back(s.currentTwist[i]);
590 const std::string& nodeSetName,
591 const Ice::Current& iceCurrent)
593 auto search =
limb.find(nodeSetName);
594 if (search ==
limb.end())
597 <<
"does not exist in the controller";
598 return std::vector<double>{};
601 auto& arm =
limb.at(nodeSetName);
602 auto currentPose = arm->bufferRtStatusToOnPublish.getUpToDateReadBuffer().currentPose;
611 const Ice::Current& iceCurrent)
615 for (
size_t i = 0; i < 4; ++i)
617 for (
int j = 0; j < 4; ++j)
619 pair.second.desiredPose(i, j) = targetPoseMap.at(pair.first)[i][j];
622 if (targetNullspaceMap.at(pair.first).size() > 0)
624 const size_t nDoF = pair.second.desiredNullspaceJointAngles.value().size();
626 <<
"the joint numbers does not match";
627 for (
size_t i = 0; i < nDoF; ++i)
629 pair.second.desiredNullspaceJointAngles.value()(i) =
630 targetNullspaceMap.at(pair.first)[i];
633 limb.at(pair.first)->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
634 limb.at(pair.first)->bufferConfigUserToNonRt.commitWrite();
643 const auto nDoF = arm->jointNames.size();
646 const auto checkNonNegative = [](
const auto& v) {
ARMARX_CHECK((v.array() >= 0).all()); };
648 if (!configData.desiredNullspaceJointAngles.has_value())
652 ARMARX_INFO <<
"No user defined nullspace target, reset to zero with "
654 configData.desiredNullspaceJointAngles = Eigen::VectorXf::Zero(nDoF);
655 arm->reInitPreActivate.store(
true);
660 arm->bufferConfigRtToUser.getUpToDateReadBuffer().desiredNullspaceJointAngles;
662 <<
"Controller is active, but no user defined nullspace target. \n"
663 "You should first get up-to-date config of this controller and then update "
665 " auto cfg = ctrl->getConfig(); \n"
666 " cfg.desiredPose = xxx;\n"
667 " ctrl->updateConfig(cfg);\n"
668 "Now, I decide by myself to use the existing values of nullspace target\n"
669 << currentValue.value();
670 configData.desiredNullspaceJointAngles = currentValue;
674 checkSize(configData.desiredNullspaceJointAngles.value());
675 checkSize(configData.kdNullspaceTorque);
676 checkSize(configData.kpNullspaceTorque);
677 checkSize(configData.kdNullspaceVel);
678 checkSize(configData.kpNullspaceVel);
680 checkNonNegative(configData.kdNullspaceTorque);
681 checkNonNegative(configData.kpNullspaceTorque);
682 checkNonNegative(configData.kpNullspaceVel);
683 checkNonNegative(configData.kdNullspaceVel);
684 checkNonNegative(configData.kdImpedance);
685 checkNonNegative(configData.kpImpedance);
694 auto rtData = arm->bufferConfigRtToOnPublish.getUpToDateReadBuffer();
695 auto rtStatus = arm->bufferRtStatusToOnPublish.getUpToDateReadBuffer();
699 if (rtData.desiredNullspaceJointAngles.has_value())
702 "desiredNullspaceJointAngles",
703 rtData.desiredNullspaceJointAngles.value());
712 float positionError =
716 datafields[
"poseError_position"] =
new Variant(positionError);
717 datafields[
"poseError_angle"] =
new Variant(angleError);
718 datafields[
"poseError_threshold_position"] =
new Variant(rtData.safeDistanceMMToGoal);
719 datafields[
"poseError_threshold_angle"] =
new Variant(rtData.safeRotAngleDegreeToGoal);
727 float currentForceNorm = rtStatus.currentForceTorque.head<3>().
norm();
728 float currentTorqueNorm = rtStatus.currentForceTorque.tail<3>().
norm();
729 float safeForceGuardOffsetNorm = rtStatus.safeFTGuardOffset.head<3>().
norm();
730 float safeTorqueGuardOffsetNorm = rtStatus.safeFTGuardOffset.tail<3>().
norm();
731 datafields[
"currentForceNorm"] =
new Variant(currentForceNorm);
732 datafields[
"currentTorqueNorm"] =
new Variant(currentTorqueNorm);
733 datafields[
"safeForceGuardOffsetNorm"] =
new Variant(safeForceGuardOffsetNorm);
734 datafields[
"safeTorqueGuardOffsetNorm"] =
new Variant(safeTorqueGuardOffsetNorm);
735 datafields[
"safeForceGuardDifference"] =
736 new Variant(currentForceNorm - safeForceGuardOffsetNorm);
737 datafields[
"safeTorqueGuardDifference"] =
738 new Variant(currentTorqueNorm - safeTorqueGuardOffsetNorm);
739 datafields[
"safeForceGuardThreshold"] =
740 new Variant(rtData.ftConfig.safeGuardForceThreshold);
741 datafields[
"safeTorqueGuardThreshold"] =
742 new Variant(rtData.ftConfig.safeGuardTorqueThreshold);
744 datafields[
"rtSafe"] =
new Variant(rtStatus.rtSafe * 1.0);
745 datafields[
"rtTargetSafe"] =
new Variant(rtStatus.rtTargetSafe * 1.0);
746 bool forceTrigger = (not rtStatus.rtSafe) and rtStatus.rtTargetSafe;
747 datafields[
"forceTrigger"] =
new Variant(forceTrigger * 1.0);
748 datafields[
"forceTorqueSafe"] =
new Variant(rtStatus.forceTorqueSafe * 1.0);
757 debugObs->setDebugChannel(
getClassName() +
"_" + arm->kinematicChainName, datafields);
763 rtStatus.forceImpedance.head<3>() * 5.0)
764 .
color(simox::Color::green()));
774 for (
auto& pair :
limb)
776 if (not pair.second->rtReady.load())
782 hands->onPublish(debugObs);
796 auto& cfg =
coordinator->bufferUserCfgToPublish.getUpToDateReadBuffer();
797 auto data =
coordinator->bufferDataRtToPublish.getUpToDateReadBuffer();
808 using namespace armarx::control::common::coordination::arondto;
809 auto followerIsolation = cfg.followerConnectionMode == ConnectionMode::follower_isolated;
810 auto leftAsLeader = cfg.leadershipMode == LeadershipMode::left_as_leader;
811 auto rightAsLeader = cfg.leadershipMode == LeadershipMode::right_as_leader;
812 auto followerInLeaderLocalFrame =
813 cfg.followerFrameMode == common::arondto::PoseFrameMode::leader;
814 datafields[
"followerIsolation"] =
new Variant(followerIsolation);
815 datafields[
"leftAsLeader"] =
new Variant(leftAsLeader);
816 datafields[
"rightAsLeader"] =
new Variant(rightAsLeader);
817 datafields[
"followerInLeaderLocalFrame"] =
new Variant(followerInLeaderLocalFrame);
819 debugObs->setDebugChannel(
"SyncModeCoordinator", datafields);
832 .fromTo(objCenter, objCenter + 100.0f *
data.currentFT.head<3>())
833 .
color(simox::Color::yellow()));
835 .fromTo(objCenter, objCenter + 100.0f *
data.currentFT.tail<3>())
836 .
color(simox::Color::green()));
837 arviz.commit(layerFT);
840 viz::Layer layerVirtualStatus =
arviz.layer(
"coordinator_virtual_status");
841 layerVirtualStatus.
add(
843 .fromTo(objCenter, objCenter + 1000.0f *
data.virtualVel.head<3>())
844 .
color(simox::Color::blue()));
845 layerVirtualStatus.
add(
847 .fromTo(objCenter, objCenter + 1000.0f *
data.poseError.head<3>())
848 .
color(simox::Color::black()));
849 arviz.commit(layerVirtualStatus);
856 for (
auto& pair :
limb)
858 pair.second->rtReady.store(
false);
864 const std::string& type,
865 const ::armarx::aron::data::dto::DictPtr& dto,
866 const Ice::Current& )
868 ARMARX_INFO <<
"Adding coordinator of type " << type;
874 coordinator = std::make_shared<common::coordination::SyncCoordination>(dto);
881 for (
const auto& nodeset :
coordinator->getNodesetList())
883 if (
limb.find(nodeset) ==
limb.end())
886 ARMARX_WARNING <<
"The requested nodeset by coordinator " << nodeset
887 <<
" does not exist in the current controller, disable coordinator";
908 ARMARX_WARNING <<
"Coordinator is not created yet, use `useCoordinator` to create!";
912 for (
const auto& nodeset :
coordinator->getNodesetList())
914 auto& arm =
limb.at(nodeset);
915 auto& cfgRT = arm->bufferConfigRtToUser.getUpToDateReadBuffer();
916 arm->bufferConfigUserToNonRt.getWriteBuffer().desiredPose = cfgRT.desiredPose;
917 arm->bufferConfigUserToNonRt.commitWrite();
928 VirtualRobot::RobotNodeSetPtr rns =
rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
929 Eigen::Matrix4f currentPose = rns->getTCP()->getPoseInRootFrame();
930 auto quat = VirtualRobot::MathTools::eigen4f2quat(currentPose);
932 "[ %.2f, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f ].",
941 if (arm->reInitPreActivate.load())
943 arm->rtConfig.desiredNullspaceJointAngles.value() = rns->getJointValuesEigen();
944 arm->rtConfig.desiredPose = currentPose;
946 arm->bufferConfigUserToNonRt.reinitAllBuffers(arm->rtConfig);
947 arm->reInitPreActivate.store(
false);
950 arm->nonRtConfig = arm->rtConfig;
951 arm->bufferConfigNonRtToRt.reinitAllBuffers(arm->rtConfig);
952 arm->bufferConfigRtToOnPublish.reinitAllBuffers(arm->rtConfig);
953 arm->bufferConfigRtToUser.reinitAllBuffers(arm->rtConfig);
956 arm->sensorDevices.updateJointValues(arm->rtStatus.jointPosition,
957 arm->rtStatus.jointVelocity,
958 arm->rtStatus.jointTorque);
959 arm->rtStatus.rtPreActivate(currentPose);
961 arm->rtStatusInNonRT = arm->rtStatus;
962 arm->nonRTDeltaT = 0.0;
963 arm->nonRTAccumulateTime = 0.0;
964 arm->bufferRtStatusToOnPublish.reinitAllBuffers(arm->rtStatus);
965 arm->bufferRtStatusToNonRt.reinitAllBuffers(arm->rtStatus);
966 arm->bufferRtStatusToUser.reinitAllBuffers(arm->rtStatus);
969 arm->controller.preactivateInit(rns);
975 for (
auto& pair :
limb)
979 userConfig.limbs.at(pair.first) = pair.second->rtConfig;
983 hands->rtPreActivate();
1005 const std::map<std::string, ConstControlDevicePtr>& controlDevices,
1006 const std::map<std::string, ConstSensorDevicePtr>&)
1012 ::armarx::WidgetDescription::WidgetSeq widgets;
1015 LabelPtr label =
new Label;
1016 label->text =
"select a controller config";
1018 StringComboBoxPtr cfgBox =
new StringComboBox;
1019 cfgBox->name =
"config_box";
1020 cfgBox->defaultIndex = 0;
1021 cfgBox->multiSelect =
false;
1023 cfgBox->options = std::vector<std::string>{
1024 "default",
"default_right",
"default_a7_right",
"default_a6_right"};
1027 layout->children.emplace_back(label);
1028 layout->children.emplace_back(cfgBox);
1031 layout->children.insert(layout->children.end(), widgets.begin(), widgets.end());
1040 auto cfgName = values.at(
"config_box")->getString();
1043 "controller_config/NJointTaskspaceMixedImpedanceVelocityController/" + cfgName +
1051 return new ConfigurableNJointControllerConfig{cfgDTO.toAronDTO()};
#define ARMARX_RT_LOGF_WARN(...)
#define ARMARX_RT_LOGF_INFO(...)
armarx::viz::Client arviz
Brief description of class JointControlTargetBase.
This util class helps with keeping a cycle time during a control cycle.
ArmarXObjectSchedulerPtr getObjectScheduler() const
int getState() const
Retrieve current state of the ManagedIceObject.
bool isControllerActive(const Ice::Current &=Ice::emptyCurrent) const final override
const SensorValueBase * useSensorValue(const std::string &sensorDeviceName) const
Get a const ptr to the given SensorDevice's SensorValue.
void runTask(const std::string &taskName, Task &&task)
Executes a given task in a separate thread from the Application ThreadPool.
const VirtualRobot::RobotPtr & useSynchronizedRtRobot(bool updateCollisionModel=false)
Requests a VirtualRobot for use in rtRun *.
const VirtualRobot::RobotPtr & rtGetRobot()
TODO make protected and use attorneys.
ControlTargetBase * useControlTarget(const std::string &deviceName, const std::string &controlMode)
Declares to calculate the ControlTarget for the given ControlDevice in the given ControlMode when rtR...
static std::filesystem::path toSystemPath(const data::PackagePath &pp)
The SensorValueBase class.
The Variant class is described here: Variants.
static bool pinThreadToCPU(unsigned int cpu)
Pins the calling thread to the CPU with the given id.
static bool elevateThreadPriority(int priority)
Elevate the thread priority of the calling thread to the given priority.
static constexpr int RT_THREAD_PRIORITY
The thread priority for rt-threads.
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
std::map< std::string, VirtualRobot::RobotNodeSetPtr > controllableNodeSets
void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &) override
static WidgetDescription::WidgetPtr GenerateConfigDescription(const VirtualRobot::RobotPtr &, const std::map< std::string, ConstControlDevicePtr > &, const std::map< std::string, ConstSensorDevicePtr > &)
--------------------------------— GUI Widget ------------------------------------------—
void onInitNJointController() override
NJointControllerBase interface.
ConfigurableNJointControllerConfigPtr ConfigPtrT
void limbRT(ArmPtr &arm, const double deltaT)
Ice::DoubleSeq getCurrentTCPPose(const std::string &nodeSetName, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
std::shared_ptr< common::coordination::SyncCoordination > coordinator
void limbNonRT(ArmPtr &arm)
void onPublishCoordinator(const DebugObserverInterfacePrx &debugObs)
::armarx::aron::data::dto::DictPtr getConfig(const Ice::Current &iceCurrent=Ice::emptyCurrent) override
Ice::FloatSeq getTCPVel(const std::string &rns, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
void limbReInit(ArmPtr &arm)
void useCoordinator(const std::string &type, const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
std::map< std::string, ArmPtr > limb
bool isSafeForceTorque(const std::string &nodeSetName, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
-----------------------------— Other interaces ----------------------------------------—
law::TaskspaceMixedImpedanceVelocityController::Config Config
std::atomic_bool coordinatorEnabled
coordinator
void validateConfigData(Config &config, ArmPtr &arm)
static ConfigPtrT GenerateConfigFromVariants(const StringVariantBaseMap &values)
void limbRTSetTarget(ArmPtr &arm, const size_t nDoFTorque, const size_t nDoFVelocity, const Eigen::VectorXf &targetTorque, const Eigen::VectorXf &targetVelocity)
core::HandControlPtr hands
void enableSafeGuardForceTorque(const std::string &nodeSetName, const bool forceGuard, const bool torqueGuard, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
std::tuple< bool, bool > additionalTaskUpdateStatus()
void rtPostDeactivateController() override
This function is called after the controller is deactivated.
void updateInputData(const std::string &key, const Eigen::Matrix4f &targetPose, const PoseFrameMode &targetPoseMode, const Eigen::Matrix4f &pose, const Eigen::Vector6f &vel, const Eigen::Vector6f &ft, const Eigen::Vector6f &stiffness)
some method for coordinator
void rtRunCoordinator(double deltaT)
coordinator
virtual void additionalTask()
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration) override
TODO make protected and use attorneys.
void limbInit(const std::string nodeSetName, ArmPtr &arm, Config &cfg, VirtualRobot::RobotPtr &nonRtRobotPtr)
std::unique_ptr< ArmData > ArmPtr
void additionalTaskSetTarget()
std::map< std::string, common::coordination::InputData > coordinatorInputData
void updateConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
NJointController interface.
bool updateTargetPose(const TargetPoseMap &targetPoseMap, const TargetNullspaceMap &targetNullspaceMap, const Ice::Current &=Ice::emptyCurrent) override
void limbPublish(ArmPtr &arm, const DebugObserverInterfacePrx &debugObs)
void handleRTNotSafeInNonRT()
armarx::control::common::arondto::PoseFrameMode PoseFrameMode
VirtualRobot::RobotPtr nonRtRobot
NJointTaskspaceMixedImpedanceVelocityController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
void rtPreActivateController() override
This function is called before the controller is activated.
void limbRTUpdateStatus(ArmPtr &arm, const double deltaT)
-----------------------------— Real time cotnrol --------------------------------------—
DerivedT & color(Color color)
DerivedT & scale(Eigen::Vector3f scale)
#define ARMARX_CHECK_GREATER(lhs, rhs)
This macro evaluates whether lhs is greater (>) than rhs and if it turns out to be false it will thro...
#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(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
#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.
armarx::aron::data::dto::Dict getRTStatus()
void disableCoordinator()
void calibrateFTSensor()
ft sensor
Matrix< float, 6, 1 > Vector6f
std::shared_ptr< class Robot > RobotPtr
::IceInternal::Handle< Dict > DictPtr
void reportPoseDeviationWarning(const std::string &who, const Eigen::Matrix4f &pose1, const Eigen::Matrix4f &pose2, const std::string &namePose1, const std::string &namePose2)
bool detectAndReportPoseDeviationWarning(const Eigen::Matrix4f &pose1, const Eigen::Matrix4f &pose2, const std::string &namePose1, const std::string &namePose2, float positionThrMM, float angleThrDeg, const std::string &who)
void debugEigenVec(StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
float getDeltaAngleBetweenPose(const Eigen::Matrix4f &pose1, const Eigen::Matrix4f &pose2)
void debugEigenPose(StringVariantBaseMap &datafields, const std::string &name, Eigen::Matrix4f pose)
DVec mat4ToDVec(const Eigen::Matrix4f &mat)
convert Eigen:Matrix4f to 7D double vector.
std::string sVecToString(const std::vector< std::string > &vec, const std::string &delimiter)
Eigen::Block< Eigen::Matrix4f, 3, 1 > getPos(Eigen::Matrix4f &matrix)
NJointControllerRegistration< NJointTaskspaceMixedImpedanceVelocityController > registrationControllerNJointTaskspaceMixedImpedanceVelocityController("NJointTaskspaceMixedImpedanceVelocityController")
dictionary< string, Ice::FloatSeq > TargetNullspaceMap
dictionary< string, FloatSeqSeq > TargetPoseMap
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface > DebugObserverInterfacePrx
std::map< std::string, VariantBasePtr > StringVariantBaseMap
AronDTO readFromJson(const std::filesystem::path &filename)
IceUtil::Handle< class RobotUnit > RobotUnitPtr
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface > DebugDrawerInterfacePrx
detail::ControlThreadOutputBufferEntry SensorAndControl
double norm(const Point &a)
void add(ElementT const &element)