25#include <SimoxUtility/color/Color.h>
26#include <VirtualRobot/MathTools.h>
27#include <VirtualRobot/Nodes/RobotNode.h>
28#include <VirtualRobot/RobotNodeSet.h>
46 NJointControllerRegistration<NJointTaskspaceImpedanceController>
48 "NJointTaskspaceImpedanceController");
56 arm->kinematicChainName = nodeSetName;
57 VirtualRobot::RobotNodeSetPtr rtRns =
58 rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
59 VirtualRobot::RobotNodeSetPtr nonRtRns =
60 nonRtRobotPtr->getRobotNodeSet(arm->kinematicChainName);
63 ARMARX_IMPORTANT <<
"Creating Taskspace Impedance controller with kinematic chain: "
64 << arm->kinematicChainName <<
" with num of joints: (RT robot) "
65 << rtRns->getSize() <<
", and (non-RT robot) " << nonRtRns->getSize();
67 arm->controller.initialize(nonRtRns, rtRns);
68 arm->controller.ftsensor.initialize(rtRns,
robotUnit, cfg.ftConfig);
69 arm->jointNames.clear();
70 std::vector<size_t> jointIDTorqueMode;
71 std::vector<size_t> jointIDVelocityMode;
72 for (
size_t i = 0; i < rtRns->getSize(); ++i)
74 std::string jointName = rtRns->getNode(i)->getName();
75 arm->jointNames.push_back(jointName);
79 <<
"Could not get control target for " <<
QUOTED(jointName) <<
". "
80 <<
"If this joint is currently not available (e.g., belonging to an "
81 <<
"unavailable arm), make sure to select a controller config that respects this.";
82 auto* casted_ct = ct->
asA<ControlTarget1DoFActuatorTorque>();
84 arm->targets.push_back(casted_ct);
88 arm->sensorDevices.append(sv, jointName);
89 jointIDTorqueMode.push_back(i);
94 arm->nonRtConfig = cfg;
96 auto nDoF = rtRns->getSize();
97 arm->rtStatus.reset(nDoF, jointIDTorqueMode, jointIDVelocityMode);
102 const NJointControllerConfigPtr& config,
108 ConfigPtrT cfg = ConfigPtrT::dynamicCast(config);
118 limb.emplace(pair.first, std::make_unique<ArmData>());
130 <<
hands->hands.at(pair.first)->kinematicChainName;
139 return "NJointTaskspaceImpedanceController";
145 std::string taskName =
getClassName() +
"AdditionalTask";
157 while (
getState() == eManagedIceObjectStarted)
163 c.waitForCycleDuration();
171 arm->bufferConfigNonRtToRt.getWriteBuffer() = arm->nonRtConfig;
172 arm->bufferConfigNonRtToRt.commitWrite();
180 if (not rtTargetSafe)
186 std::tuple<bool, bool>
191 bool rtTargetSafe =
true;
192 bool forceTorqueSafe =
true;
193 for (
auto& pair :
limb)
195 auto& arm = pair.second;
196 arm->nonRtConfig = arm->bufferConfigUserToNonRt.getUpToDateReadBuffer();
197 arm->rtStatusInNonRT = arm->bufferRtStatusToNonRt.getUpToDateReadBuffer();
198 rtSafe = rtSafe and pair.second->rtStatusInNonRT.rtSafe;
199 rtTargetSafe = rtTargetSafe and pair.second->rtStatusInNonRT.rtTargetSafe;
200 forceTorqueSafe = forceTorqueSafe and pair.second->rtStatusInNonRT.forceTorqueSafe;
204 hands->nonRTUpdateStatus();
206 return std::make_tuple(rtTargetSafe, forceTorqueSafe);
212 for (
auto& pair :
limb)
218 hands->nonRTSetTarget();
225 for (
auto& pair :
limb)
227 if (not pair.second->rtReady)
230 if (not pair.second->rtStatusInNonRT.rtTargetSafe)
233 pair.second->rtStatusInNonRT.currentPose,
234 pair.second->rtStatusInNonRT.desiredPoseUnsafe,
245 arm->rtConfig = arm->bufferConfigNonRtToRt.getUpToDateReadBuffer();
246 arm->rtStatus.deltaT = deltaT;
247 arm->rtStatus.accumulateTime += deltaT;
249 arm->controller.ftsensor.updateStatus(arm->rtConfig.ftConfig,
250 arm->rtStatus.currentForceTorque,
251 arm->rtStatus.deltaT,
252 arm->rtFirstRun.load());
253 arm->rtStatus.safeFTGuardOffset.head<3>() =
254 arm->controller.ftsensor.getSafeGuardForceOffset();
256 arm->sensorDevices.updateJointValues(
257 arm->rtStatus.jointPosition, arm->rtStatus.jointVelocity, arm->rtStatus.jointTorque);
260 arm->bufferRtStatusToNonRt.getWriteBuffer() = arm->rtStatus;
261 arm->bufferRtStatusToNonRt.commitWrite();
262 arm->bufferRtStatusToUser.getWriteBuffer() = arm->rtStatus;
263 arm->bufferRtStatusToUser.commitWrite();
268 const Eigen::VectorXf& targetTorque)
270 for (
unsigned int i = 0; i < targetTorque.size(); i++)
272 arm->targets.at(i)->torque = targetTorque(i);
273 if (!arm->targets.at(i)->isValid())
275 arm->targets.at(i)->torque = 0;
278 arm->bufferRtStatusToOnPublish.getWriteBuffer() = arm->rtStatus;
279 arm->bufferRtStatusToOnPublish.commitWrite();
281 arm->bufferConfigRtToOnPublish.getWriteBuffer() = arm->rtConfig;
282 arm->bufferConfigRtToOnPublish.commitWrite();
284 arm->bufferConfigRtToUser.getWriteBuffer() = arm->rtConfig;
285 arm->bufferConfigRtToUser.commitWrite();
287 if (arm->rtFirstRun.load())
289 arm->rtFirstRun.store(
false);
290 arm->rtReady.store(
true);
297 double time_measure = IceUtil::Time::now().toMicroSecondsDouble();
301 arm->controller.run(arm->rtConfig, arm->rtStatus);
302 double time_run_rt = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
306 double time_set_target = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
307 time_measure = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
309 if (time_measure > 200)
312 "run_rt_limb: %.2f\n"
313 "set_target_limb: %.2f\n"
315 time_run_rt - time_measure,
316 time_set_target - time_run_rt,
318 .deactivateSpam(1.0f);
325 const Eigen::Matrix4f& targetPose,
327 const Eigen::Matrix4f& pose,
337 data.targetPose = targetPose;
338 data.targetPoseMode = targetPoseMode;
341 data.stiffness = stiffness;
347 targetPose, targetPoseMode, pose, vel, ft, stiffness));
359 bool rtReady =
false;
360 for (
const auto& nodeset :
coordinator->getNodesetList())
362 auto& rts =
limb.at(nodeset)->rtStatus;
363 auto& rtc =
limb.at(nodeset)->rtConfig;
364 rtReady =
limb.at(nodeset)->rtReady.load();
367 rtc.desiredPoseFrameMode,
370 rts.currentForceTorque,
378 for (
const auto& nodeset :
coordinator->getNodesetList())
381 limb.at(nodeset)->rtConfig.desiredPoseFrameMode = PoseFrameMode::root;
387 const IceUtil::Time& timeSinceLastIteration)
389 double deltaT = timeSinceLastIteration.toSecondsDouble();
390 for (
auto& pair :
limb)
397 for (
auto& pair :
limb)
399 limbRT(pair.second, deltaT);
403 hands->updateRTStatus(deltaT);
410 const Ice::Current& iceCurrent)
418 bool desiredPoseFrameModeSame = prevCfg.limbs.at(pair.first).desiredPoseFrameMode ==
419 pair.second.desiredPoseFrameMode;
421 pair.second.desiredPose,
422 prevCfg.limbs.at(pair.first).desiredPose,
424 "previous desired pose",
425 pair.second.safeDistanceMMToGoal,
426 pair.second.safeRotAngleDegreeToGoal,
427 "updateConfig_" + pair.first))
430 pair.second.desiredPose = prevCfg.limbs.at(pair.first).desiredPose;
444 limb.at(pair.first)->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
445 limb.at(pair.first)->bufferConfigUserToNonRt.commitWrite();
456 for (
auto& pair :
limb)
459 pair.second->bufferConfigRtToUser.getUpToDateReadBuffer();
470 const bool forceGuard,
471 const bool torqueGuard,
472 const Ice::Current& iceCurrent)
477 it->second.ftConfig.enableSafeGuardForce = forceGuard;
478 it->second.ftConfig.enableSafeGuardTorque = torqueGuard;
479 limb.at(nodeSetName)->controller.ftsensor.enableSafeGuard(forceGuard, torqueGuard);
481 <<
"reset safe guard with force torque sensors: safe? "
482 <<
limb.at(nodeSetName)->controller.ftsensor.isSafe(it->second.ftConfig);
483 limb.at(nodeSetName)->bufferConfigUserToNonRt.getWriteBuffer() = it->second;
484 limb.at(nodeSetName)->bufferConfigUserToNonRt.commitWrite();
489 <<
" found in the controllers.";
496 const Ice::Current& iceCurrent)
501 return limb.at(nodeSetName)->controller.ftsensor.ftSafe.load();
505 <<
" found in the controllers.";
511 const Ice::Current& iceCurrent)
513 std::vector<float> tcpVel;
514 auto& arm =
limb.at(rns);
515 auto s = arm->bufferRtStatusToUser.getUpToDateReadBuffer();
516 for (
int i = 0; i < s.currentTwist.size(); i++)
518 tcpVel.push_back(s.currentTwist[i]);
527 const Ice::Current& iceCurrent)
531 for (
size_t i = 0; i < 4; ++i)
533 for (
int j = 0; j < 4; ++j)
535 pair.second.desiredPose(i, j) = targetPoseMap.at(pair.first)[i][j];
538 if (targetNullspaceMap.at(pair.first).size() > 0)
540 const size_t nDoF = pair.second.desiredNullspaceJointAngles.value().size();
542 <<
"the joint numbers does not match";
543 for (
size_t i = 0; i < nDoF; ++i)
545 pair.second.desiredNullspaceJointAngles.value()(i) =
546 targetNullspaceMap.at(pair.first)[i];
549 limb.at(pair.first)->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
550 limb.at(pair.first)->bufferConfigUserToNonRt.commitWrite();
558 const auto nDoF = arm->jointNames.size();
561 const auto checkNonNegative = [](
const auto& v) {
ARMARX_CHECK((v.array() >= 0).all()); };
563 if (!configData.desiredNullspaceJointAngles.has_value())
567 ARMARX_INFO <<
"No user defined nullspace target, reset to zero with "
569 configData.desiredNullspaceJointAngles = Eigen::VectorXf::Zero(nDoF);
570 arm->reInitPreActivate.store(
true);
575 arm->bufferConfigRtToUser.getUpToDateReadBuffer().desiredNullspaceJointAngles;
577 <<
"Controller is active, but no user defined nullspace target. \n"
578 "You should first get up-to-date config of this controller and then update "
580 " auto cfg = ctrl->getConfig(); \n"
581 " cfg.desiredPose = xxx;\n"
582 " ctrl->updateConfig(cfg);\n"
583 "Now, I decide by myself to use the existing values of nullspace target\n"
584 << currentValue.value();
585 configData.desiredNullspaceJointAngles = currentValue;
589 checkSize(configData.desiredNullspaceJointAngles.value());
590 checkSize(configData.kdNullspaceTorque);
591 checkSize(configData.kpNullspaceTorque);
593 checkNonNegative(configData.kdNullspaceTorque);
594 checkNonNegative(configData.kpNullspaceTorque);
595 checkNonNegative(configData.kdImpedance);
596 checkNonNegative(configData.kpImpedance);
604 auto rtData = arm->bufferConfigRtToOnPublish.getUpToDateReadBuffer();
605 auto rtStatus = arm->bufferRtStatusToOnPublish.getUpToDateReadBuffer();
609 if (rtData.desiredNullspaceJointAngles.has_value())
612 "desiredNullspaceJointAngles",
613 rtData.desiredNullspaceJointAngles.value());
622 float positionError =
626 datafields[
"poseError_position"] =
new Variant(positionError);
627 datafields[
"poseError_angle"] =
new Variant(angleError);
628 datafields[
"poseError_threshold_position"] =
new Variant(rtData.safeDistanceMMToGoal);
629 datafields[
"poseError_threshold_angle"] =
new Variant(rtData.safeRotAngleDegreeToGoal);
658 float currentForceNorm = rtStatus.currentForceTorque.head<3>().
norm();
659 float currentTorqueNorm = rtStatus.currentForceTorque.tail<3>().
norm();
660 float safeForceGuardOffsetNorm = rtStatus.safeFTGuardOffset.head<3>().
norm();
661 float safeTorqueGuardOffsetNorm = rtStatus.safeFTGuardOffset.tail<3>().
norm();
662 datafields[
"currentForceTorqueNorm"] =
new Variant(currentForceNorm);
663 datafields[
"currentTorqueTorqueNorm"] =
new Variant(currentTorqueNorm);
664 datafields[
"safeForceGuardOffsetNorm"] =
new Variant(safeForceGuardOffsetNorm);
665 datafields[
"safeTorqueGuardOffsetNorm"] =
new Variant(safeTorqueGuardOffsetNorm);
666 datafields[
"safeForceGuardDifference"] =
667 new Variant(currentForceNorm - safeForceGuardOffsetNorm);
668 datafields[
"safeTorqueGuardDifference"] =
669 new Variant(currentTorqueNorm - safeTorqueGuardOffsetNorm);
670 datafields[
"safeForceGuardThreshold"] =
671 new Variant(rtData.ftConfig.safeGuardForceThreshold);
672 datafields[
"safeTorqueGuardThreshold"] =
673 new Variant(rtData.ftConfig.safeGuardTorqueThreshold);
696 datafields[
"safeDistanceToGoalThr"] =
new Variant(rtData.safeDistanceMMToGoal);
697 datafields[
"rtTargetSafe"] =
new Variant(rtStatus.rtTargetSafe);
699 debugObs->setDebugChannel(
getClassName() +
"_" + arm->kinematicChainName, datafields);
706 .fromTo(objCenter, objCenter + 100.0f * rtStatus.currentForceTorque.head<3>())
707 .
color(simox::Color::yellow()));
710 .fromTo(objCenter, objCenter + 100.0f * rtStatus.currentForceTorque.tail<3>())
711 .
color(simox::Color::green()));
715 layerPose.
add(
viz::Pose(
"targetPose_" + arm->kinematicChainName)
716 .
pose(rtStatus.desiredPose)
718 layerPose.
add(
viz::Pose(
"currentPose_" + arm->kinematicChainName)
719 .
pose(rtStatus.currentPose)
721 arviz.commit(layerPose);
729 for (
auto& pair :
limb)
731 if (not pair.second->rtReady.load())
737 hands->onPublish(debugObs);
751 auto& cfg =
coordinator->bufferUserCfgToPublish.getUpToDateReadBuffer();
752 auto data =
coordinator->bufferDataRtToPublish.getUpToDateReadBuffer();
763 using namespace armarx::control::common::coordination::arondto;
764 auto followerIsolation = cfg.followerConnectionMode == ConnectionMode::follower_isolated;
765 auto leftAsLeader = cfg.leadershipMode == LeadershipMode::left_as_leader;
766 auto rightAsLeader = cfg.leadershipMode == LeadershipMode::right_as_leader;
767 auto followerInLeaderLocalFrame =
768 cfg.followerFrameMode == common::arondto::PoseFrameMode::leader;
769 datafields[
"followerIsolation"] =
new Variant(followerIsolation);
770 datafields[
"leftAsLeader"] =
new Variant(leftAsLeader);
771 datafields[
"rightAsLeader"] =
new Variant(rightAsLeader);
772 datafields[
"followerInLeaderLocalFrame"] =
new Variant(followerInLeaderLocalFrame);
774 debugObs->setDebugChannel(
"SyncModeCoordinator", datafields);
787 .fromTo(objCenter, objCenter + 100.0f *
data.currentFT.head<3>())
788 .
color(simox::Color::yellow()));
790 .fromTo(objCenter, objCenter + 100.0f *
data.currentFT.tail<3>())
791 .
color(simox::Color::green()));
792 arviz.commit(layerFT);
795 viz::Layer layerVirtualStatus =
arviz.layer(
"coordinator_virtual_status");
796 layerVirtualStatus.
add(
798 .fromTo(objCenter, objCenter + 1000.0f *
data.virtualVel.head<3>())
799 .
color(simox::Color::blue()));
800 layerVirtualStatus.
add(
802 .fromTo(objCenter, objCenter + 1000.0f *
data.poseError.head<3>())
803 .
color(simox::Color::black()));
804 arviz.commit(layerVirtualStatus);
811 for (
auto& pair :
limb)
813 pair.second->rtReady.store(
false);
819 const ::armarx::FloatSeqSeq& targetPose,
820 const Ice::Current& iceCurrent)
827 Eigen::Matrix4f desiredPose;
828 desiredPose.setZero();
829 for (
size_t i = 0; i < 4; ++i)
831 for (
int j = 0; j < 4; ++j)
833 desiredPose(i, j) = targetPose[i][j];
842 const std::string& type,
843 const ::armarx::aron::data::dto::DictPtr& dto,
844 const Ice::Current& )
846 ARMARX_INFO <<
"Adding coordinator of type " << type;
852 coordinator = std::make_shared<common::coordination::SyncCoordination>(dto);
859 for (
const auto& nodeset :
coordinator->getNodesetList())
861 if (
limb.find(nodeset) ==
limb.end())
864 ARMARX_WARNING <<
"The requested nodeset by coordinator " << nodeset
865 <<
" does not exist in the current controller, disable coordinator";
870 for (
const auto& nodeset :
coordinator->getNodesetList())
894 ARMARX_WARNING <<
"Coordinator is not created yet, use `useCoordinator` to create!";
898 for (
const auto& nodeset :
coordinator->getNodesetList())
900 auto& arm =
limb.at(nodeset);
901 auto& cfgRT = arm->bufferConfigRtToUser.getUpToDateReadBuffer();
902 arm->bufferConfigUserToNonRt.getWriteBuffer().desiredPose = cfgRT.desiredPose;
903 arm->bufferConfigUserToNonRt.commitWrite();
913 VirtualRobot::RobotNodeSetPtr rns =
rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
914 Eigen::Matrix4f currentPose = rns->getTCP()->getPoseInRootFrame();
915 auto quat = VirtualRobot::MathTools::eigen4f2quat(currentPose);
917 "[ %.2f, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f ].",
926 if (arm->reInitPreActivate.load())
928 arm->rtConfig.desiredNullspaceJointAngles.value() = rns->getJointValuesEigen();
929 arm->rtConfig.desiredPose = currentPose;
931 arm->bufferConfigUserToNonRt.reinitAllBuffers(arm->rtConfig);
932 arm->reInitPreActivate.store(
false);
935 arm->nonRtConfig = arm->rtConfig;
936 arm->bufferConfigNonRtToRt.reinitAllBuffers(arm->rtConfig);
937 arm->bufferConfigRtToOnPublish.reinitAllBuffers(arm->rtConfig);
938 arm->bufferConfigRtToUser.reinitAllBuffers(arm->rtConfig);
941 arm->sensorDevices.updateJointValues(arm->rtStatus.jointPosition,
942 arm->rtStatus.jointVelocity,
943 arm->rtStatus.jointTorque);
944 arm->rtStatus.rtPreActivate(currentPose);
946 arm->rtStatusInNonRT = arm->rtStatus;
947 arm->nonRTDeltaT = 0.0;
948 arm->nonRTAccumulateTime = 0.0;
949 arm->bufferRtStatusToOnPublish.reinitAllBuffers(arm->rtStatus);
950 arm->bufferRtStatusToNonRt.reinitAllBuffers(arm->rtStatus);
951 arm->bufferRtStatusToUser.reinitAllBuffers(arm->rtStatus);
954 arm->controller.preactivateInit(rns);
960 for (
auto& pair :
limb)
964 userConfig.limbs.at(pair.first) = pair.second->rtConfig;
968 hands->rtPreActivate();
990 const std::map<std::string, ConstControlDevicePtr>& controlDevices,
991 const std::map<std::string, ConstSensorDevicePtr>&)
997 ::armarx::WidgetDescription::WidgetSeq widgets;
1000 LabelPtr label =
new Label;
1001 label->text =
"select a controller config";
1003 StringComboBoxPtr cfgBox =
new StringComboBox;
1004 cfgBox->name =
"config_box";
1005 cfgBox->defaultIndex = 0;
1006 cfgBox->multiSelect =
false;
1008 cfgBox->options = std::vector<std::string>{
1009 "default",
"default_right",
"default_a7_right",
"default_a6_right"};
1012 layout->children.emplace_back(label);
1013 layout->children.emplace_back(cfgBox);
1016 layout->children.insert(layout->children.end(), widgets.begin(), widgets.end());
1025 auto cfgName = values.at(
"config_box")->getString();
1028 "controller_config/NJointTaskspaceImpedanceController/" + cfgName +
".json");
1035 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
static ConfigPtrT GenerateConfigFromVariants(const StringVariantBaseMap &values)
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
law::TaskspaceImpedanceController::Config Config
void limbRT(ArmPtr &arm, const double deltaT)
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 ----------------------------------------—
void limbRTSetTarget(ArmPtr &arm, const Eigen::VectorXf &targetTorque)
NJointTaskspaceImpedanceController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
std::atomic_bool coordinatorEnabled
coordinator
void validateConfigData(Config &config, ArmPtr &arm)
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 updateObjectTargetPose(const FloatSeqSeq &targetPose, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
void limbPublish(ArmPtr &arm, const DebugObserverInterfacePrx &debugObs)
void handleRTNotSafeInNonRT()
armarx::control::common::arondto::PoseFrameMode PoseFrameMode
VirtualRobot::RobotPtr nonRtRobot
void rtPreActivateController() override
This function is called before the controller is activated.
void limbRTUpdateStatus(ArmPtr &arm, const double deltaT)
-----------------------------— Real time cotnrol --------------------------------------—
DerivedT & pose(Eigen::Matrix4f const &pose)
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_WARNING
The logging level for unexpected behaviour, but not a serious problem.
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)
Eigen::Block< Eigen::Matrix4f, 3, 1 > getPos(Eigen::Matrix4f &matrix)
NJointControllerRegistration< NJointTaskspaceImpedanceController > registrationControllerNJointTaskspaceImpedanceController("NJointTaskspaceImpedanceController")
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)