25#include <VirtualRobot/MathTools.h>
26#include <VirtualRobot/RobotNodeSet.h>
44 NJointControllerRegistration<NJointTaskspaceVelocityController>
46 "NJointTaskspaceVelocityController");
54 arm->kinematicChainName = nodeSetName;
55 VirtualRobot::RobotNodeSetPtr rtRns =
56 rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
57 VirtualRobot::RobotNodeSetPtr nonRtRns =
58 nonRtRobotPtr->getRobotNodeSet(arm->kinematicChainName);
61 ARMARX_IMPORTANT <<
"Creating Taskspace Impedance controller with kinematic chain: "
62 << arm->kinematicChainName <<
" with num of joints: (RT robot) "
63 << rtRns->getSize() <<
", and (non-RT robot) " << nonRtRns->getSize();
65 arm->controller.initialize(nonRtRns, rtRns);
66 arm->controller.ftsensor.initialize(rtRns,
robotUnit, cfg.ftConfig);
67 arm->jointNames.clear();
68 std::vector<size_t> jointIDTorqueMode;
69 std::vector<size_t> jointIDVelocityMode;
70 for (
size_t i = 0; i < rtRns->getSize(); ++i)
72 std::string jointName = rtRns->getNode(i)->getName();
73 arm->jointNames.push_back(jointName);
77 auto* casted_ct = ct->
asA<ControlTarget1DoFActuatorVelocity>();
79 arm->targetsVel.push_back(casted_ct);
83 arm->sensorDevices.append(sv, jointName);
84 jointIDVelocityMode.push_back(i);
89 arm->nonRtConfig = cfg;
91 auto nDoF = rtRns->getSize();
92 arm->rtStatus.reset(nDoF, jointIDTorqueMode, jointIDVelocityMode);
97 const NJointControllerConfigPtr& config,
103 ConfigPtrT cfg = ConfigPtrT::dynamicCast(config);
113 limb.emplace(pair.first, std::make_unique<ArmData>());
125 <<
hands->hands.at(pair.first)->kinematicChainName;
134 return "NJointTaskspaceVelocityController";
140 std::string taskName =
getClassName() +
"AdditionalTask";
152 while (
getState() == eManagedIceObjectStarted)
158 c.waitForCycleDuration();
166 arm->bufferConfigNonRtToRt.getWriteBuffer() = arm->nonRtConfig;
167 arm->bufferConfigNonRtToRt.commitWrite();
175 if (not rtTargetSafe)
181 std::tuple<bool, bool>
186 bool rtTargetSafe =
true;
187 bool forceTorqueSafe =
true;
188 for (
auto& pair :
limb)
190 auto& arm = pair.second;
191 arm->nonRtConfig = arm->bufferConfigUserToNonRt.getUpToDateReadBuffer();
192 arm->rtStatusInNonRT = arm->bufferRtStatusToNonRt.getUpToDateReadBuffer();
193 rtSafe = rtSafe and pair.second->rtStatusInNonRT.rtSafe;
194 rtTargetSafe = rtTargetSafe and pair.second->rtStatusInNonRT.rtTargetSafe;
195 forceTorqueSafe = forceTorqueSafe and pair.second->rtStatusInNonRT.forceTorqueSafe;
199 hands->nonRTUpdateStatus();
201 return std::make_tuple(rtTargetSafe, forceTorqueSafe);
207 for (
auto& pair :
limb)
213 hands->nonRTSetTarget();
220 for (
auto& pair :
limb)
222 if (not pair.second->rtReady)
225 if (not pair.second->rtStatusInNonRT.rtTargetSafe)
228 pair.second->rtStatusInNonRT.currentPose,
229 pair.second->rtStatusInNonRT.desiredPoseUnsafe,
240 arm->rtConfig = arm->bufferConfigNonRtToRt.getUpToDateReadBuffer();
241 arm->rtStatus.deltaT = deltaT;
242 arm->rtStatus.accumulateTime += deltaT;
244 arm->controller.ftsensor.updateStatus(arm->rtConfig.ftConfig,
245 arm->rtStatus.currentForceTorque,
246 arm->rtStatus.deltaT,
247 arm->rtFirstRun.load());
248 arm->rtStatus.safeFTGuardOffset.head<3>() =
249 arm->controller.ftsensor.getSafeGuardForceOffset();
251 arm->sensorDevices.updateJointValues(
252 arm->rtStatus.jointPosition, arm->rtStatus.jointVelocity, arm->rtStatus.jointTorque);
255 arm->bufferRtStatusToNonRt.getWriteBuffer() = arm->rtStatus;
256 arm->bufferRtStatusToNonRt.commitWrite();
257 arm->bufferRtStatusToUser.getWriteBuffer() = arm->rtStatus;
258 arm->bufferRtStatusToUser.commitWrite();
263 const Eigen::VectorXf& targetVelocity)
265 for (
unsigned int i = 0; i < targetVelocity.size(); i++)
267 arm->targetsVel.at(i)->velocity = targetVelocity(i);
268 if (!arm->targetsVel.at(i)->isValid())
270 arm->targetsVel.at(i)->velocity = 0;
273 arm->bufferRtStatusToOnPublish.getWriteBuffer() = arm->rtStatus;
274 arm->bufferRtStatusToOnPublish.commitWrite();
276 arm->bufferConfigRtToOnPublish.getWriteBuffer() = arm->rtConfig;
277 arm->bufferConfigRtToOnPublish.commitWrite();
279 arm->bufferConfigRtToUser.getWriteBuffer() = arm->rtConfig;
280 arm->bufferConfigRtToUser.commitWrite();
282 if (arm->rtFirstRun.load())
284 arm->rtFirstRun.store(
false);
285 arm->rtReady.store(
true);
292 double time_measure = IceUtil::Time::now().toMicroSecondsDouble();
296 arm->controller.run(arm->rtConfig, arm->rtStatus);
297 double time_run_rt = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
301 double time_set_target = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
302 time_measure = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
304 if (time_measure > 200)
307 "run_rt_limb: %.2f\n"
308 "set_target_limb: %.2f\n"
310 time_run_rt - time_measure,
311 time_set_target - time_run_rt,
313 .deactivateSpam(1.0f);
319 const IceUtil::Time& timeSinceLastIteration)
321 double deltaT = timeSinceLastIteration.toSecondsDouble();
322 for (
auto& pair :
limb)
329 for (
auto& pair :
limb)
331 limbRT(pair.second, deltaT);
335 hands->updateRTStatus(deltaT);
342 const Ice::Current& iceCurrent)
350 bool desiredPoseFrameModeSame = prevCfg.limbs.at(pair.first).desiredPoseFrameMode ==
351 pair.second.desiredPoseFrameMode;
353 pair.second.desiredPose,
354 prevCfg.limbs.at(pair.first).desiredPose,
356 "previous desired pose",
357 pair.second.safeDistanceMMToGoal,
358 pair.second.safeRotAngleDegreeToGoal,
359 "updateConfig_" + pair.first))
362 pair.second.desiredPose = prevCfg.limbs.at(pair.first).desiredPose;
364 limb.at(pair.first)->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
365 limb.at(pair.first)->bufferConfigUserToNonRt.commitWrite();
376 for (
auto& pair :
limb)
379 pair.second->bufferConfigRtToUser.getUpToDateReadBuffer();
390 const bool forceGuard,
391 const bool torqueGuard,
392 const Ice::Current& iceCurrent)
397 it->second.ftConfig.enableSafeGuardForce = forceGuard;
398 it->second.ftConfig.enableSafeGuardTorque = torqueGuard;
399 limb.at(nodeSetName)->controller.ftsensor.enableSafeGuard(forceGuard, torqueGuard);
401 <<
"reset safe guard with force torque sensors: safe? "
402 <<
limb.at(nodeSetName)->controller.ftsensor.isSafe(it->second.ftConfig);
403 limb.at(nodeSetName)->bufferConfigUserToNonRt.getWriteBuffer() = it->second;
404 limb.at(nodeSetName)->bufferConfigUserToNonRt.commitWrite();
409 <<
" found in the controllers.";
416 const Ice::Current& iceCurrent)
421 return limb.at(nodeSetName)->controller.ftsensor.ftSafe.load();
425 <<
" found in the controllers.";
431 const Ice::Current& iceCurrent)
433 std::vector<float> tcpVel;
434 auto& arm =
limb.at(rns);
435 auto s = arm->bufferRtStatusToUser.getUpToDateReadBuffer();
436 for (
int i = 0; i < s.currentTwist.size(); i++)
438 tcpVel.push_back(s.currentTwist[i]);
447 const Ice::Current& iceCurrent)
451 for (
size_t i = 0; i < 4; ++i)
453 for (
int j = 0; j < 4; ++j)
455 pair.second.desiredPose(i, j) = targetPoseMap.at(pair.first)[i][j];
458 if (targetNullspaceMap.at(pair.first).size() > 0)
460 const size_t nDoF = pair.second.desiredNullspaceJointAngles.value().size();
462 <<
"the joint numbers does not match";
463 for (
size_t i = 0; i < nDoF; ++i)
465 pair.second.desiredNullspaceJointAngles.value()(i) =
466 targetNullspaceMap.at(pair.first)[i];
469 limb.at(pair.first)->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
470 limb.at(pair.first)->bufferConfigUserToNonRt.commitWrite();
478 const auto nDoF = arm->jointNames.size();
481 const auto checkNonNegative = [](
const auto& v) {
ARMARX_CHECK((v.array() >= 0).all()); };
483 if (!configData.desiredNullspaceJointAngles.has_value())
487 ARMARX_INFO <<
"No user defined nullspace target, reset to zero with "
489 configData.desiredNullspaceJointAngles = Eigen::VectorXf::Zero(nDoF);
490 arm->reInitPreActivate.store(
true);
495 arm->bufferConfigRtToUser.getUpToDateReadBuffer().desiredNullspaceJointAngles;
497 <<
"Controller is active, but no user defined nullspace target. \n"
498 "You should first get up-to-date config of this controller and then update "
500 " auto cfg = ctrl->getConfig(); \n"
501 " cfg.desiredPose = xxx;\n"
502 " ctrl->updateConfig(cfg);\n"
503 "Now, I decide by myself to use the existing values of nullspace target\n"
504 << currentValue.value();
505 configData.desiredNullspaceJointAngles = currentValue;
509 checkSize(configData.desiredNullspaceJointAngles.value());
510 checkSize(configData.kdNullspaceVel);
511 checkSize(configData.kpNullspaceVel);
513 checkNonNegative(configData.kdNullspaceVel);
514 checkNonNegative(configData.kpNullspaceVel);
515 checkNonNegative(configData.kpNullspaceVel);
516 checkNonNegative(configData.kdNullspaceVel);
524 auto rtData = arm->bufferConfigRtToOnPublish.getUpToDateReadBuffer();
525 auto rtStatus = arm->bufferRtStatusToOnPublish.getUpToDateReadBuffer();
536 float currentForceNorm = rtStatus.currentForceTorque.head<3>().
norm();
537 float currentTorqueNorm = rtStatus.currentForceTorque.tail<3>().
norm();
538 float safeForceGuardOffsetNorm = rtStatus.safeFTGuardOffset.head<3>().
norm();
539 float safeTorqueGuardOffsetNorm = rtStatus.safeFTGuardOffset.tail<3>().
norm();
540 datafields[
"currentForceTorqueNorm"] =
new Variant(currentForceNorm);
541 datafields[
"currentTorqueTorqueNorm"] =
new Variant(currentTorqueNorm);
542 datafields[
"safeForceGuardOffsetNorm"] =
new Variant(safeForceGuardOffsetNorm);
543 datafields[
"safeTorqueGuardOffsetNorm"] =
new Variant(safeTorqueGuardOffsetNorm);
544 datafields[
"safeForceGuardDifference"] =
545 new Variant(currentForceNorm - safeForceGuardOffsetNorm);
546 datafields[
"safeTorqueGuardDifference"] =
547 new Variant(currentTorqueNorm - safeTorqueGuardOffsetNorm);
548 datafields[
"safeForceGuardThreshold"] =
549 new Variant(rtData.ftConfig.safeGuardForceThreshold);
550 datafields[
"safeTorqueGuardThreshold"] =
551 new Variant(rtData.ftConfig.safeGuardTorqueThreshold);
556 datafields,
"nullspaceTarget", rtData.desiredNullspaceJointAngles.value());
558 debugObs->setDebugChannel(
getClassName() +
"_" + arm->kinematicChainName, datafields);
566 for (
auto& pair :
limb)
568 if (not pair.second->rtReady.load())
574 hands->onPublish(debugObs);
581 for (
auto& pair :
limb)
583 pair.second->rtReady.store(
false);
590 VirtualRobot::RobotNodeSetPtr rns =
rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
591 Eigen::Matrix4f currentPose = rns->getTCP()->getPoseInRootFrame();
592 auto quat = VirtualRobot::MathTools::eigen4f2quat(currentPose);
594 "[ %.2f, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f ].",
603 if (arm->reInitPreActivate.load())
605 arm->rtConfig.desiredNullspaceJointAngles.value() = rns->getJointValuesEigen();
606 arm->rtConfig.desiredPose = currentPose;
608 arm->bufferConfigUserToNonRt.reinitAllBuffers(arm->rtConfig);
609 arm->reInitPreActivate.store(
false);
612 arm->nonRtConfig = arm->rtConfig;
613 arm->bufferConfigNonRtToRt.reinitAllBuffers(arm->rtConfig);
614 arm->bufferConfigRtToOnPublish.reinitAllBuffers(arm->rtConfig);
615 arm->bufferConfigRtToUser.reinitAllBuffers(arm->rtConfig);
618 arm->sensorDevices.updateJointValues(arm->rtStatus.jointPosition,
619 arm->rtStatus.jointVelocity,
620 arm->rtStatus.jointTorque);
621 arm->rtStatus.rtPreActivate(currentPose);
623 arm->rtStatusInNonRT = arm->rtStatus;
624 arm->nonRTDeltaT = 0.0;
625 arm->nonRTAccumulateTime = 0.0;
626 arm->bufferRtStatusToOnPublish.reinitAllBuffers(arm->rtStatus);
627 arm->bufferRtStatusToNonRt.reinitAllBuffers(arm->rtStatus);
628 arm->bufferRtStatusToUser.reinitAllBuffers(arm->rtStatus);
631 arm->controller.preactivateInit(rns);
637 for (
auto& pair :
limb)
641 userConfig.limbs.at(pair.first) = pair.second->rtConfig;
645 hands->rtPreActivate();
666 const std::map<std::string, ConstControlDevicePtr>& controlDevices,
667 const std::map<std::string, ConstSensorDevicePtr>&)
673 ::armarx::WidgetDescription::WidgetSeq widgets;
676 LabelPtr label =
new Label;
677 label->text =
"select a controller config";
679 StringComboBoxPtr cfgBox =
new StringComboBox;
680 cfgBox->name =
"config_box";
681 cfgBox->defaultIndex = 0;
682 cfgBox->multiSelect =
false;
684 cfgBox->options = std::vector<std::string>{
685 "default",
"default_right",
"default_a7_right",
"default_a6_right"};
688 layout->children.emplace_back(label);
689 layout->children.emplace_back(cfgBox);
692 layout->children.insert(layout->children.end(), widgets.begin(), widgets.end());
701 auto cfgName = values.at(
"config_box")->getString();
704 "controller_config/NJointTaskspaceVelocityController/" + cfgName +
".json");
711 return new ConfigurableNJointControllerConfig{cfgDTO.toAronDTO()};
#define ARMARX_RT_LOGF_WARN(...)
#define ARMARX_RT_LOGF_INFO(...)
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)
void limbNonRT(ArmPtr &arm)
law::TaskspaceVelocityController::Config Config
::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)
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 &targetVelocity)
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
static ConfigPtrT GenerateConfigFromVariants(const StringVariantBaseMap &values)
std::tuple< bool, bool > additionalTaskUpdateStatus()
void rtPostDeactivateController() override
This function is called after the controller is deactivated.
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()
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
NJointTaskspaceVelocityController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
void limbPublish(ArmPtr &arm, const DebugObserverInterfacePrx &debugObs)
void handleRTNotSafeInNonRT()
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 --------------------------------------—
#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 calibrateFTSensor()
ft sensor
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)
void debugEigenPose(StringVariantBaseMap &datafields, const std::string &name, Eigen::Matrix4f pose)
NJointControllerRegistration< NJointTaskspaceVelocityController > registrationControllerNJointTaskspaceVelocityController("NJointTaskspaceVelocityController")
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)