25#include <VirtualRobot/MathTools.h>
26#include <VirtualRobot/Nodes/RobotNode.h>
27#include <VirtualRobot/RobotNodeSet.h>
44 NJointControllerRegistration<NJointTaskspaceZeroTorqueOrVelocityController>
46 "NJointTaskspaceZeroTorqueOrVelocityController");
54 arm->kinematicChainName = nodeSetName;
55 VirtualRobot::RobotNodeSetPtr rtRns =
56 rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
57 VirtualRobot::RobotNodeSetPtr nonRtRns =
58 nonRtRobotPtr->getRobotNodeSet(arm->kinematicChainName);
62 <<
"Creating Taskspace Zero Torque or Velocity Controller with kinematic chain: "
63 << arm->kinematicChainName <<
" with num of joints: (RT robot) " << rtRns->getSize()
64 <<
", and (non-RT robot) " << nonRtRns->getSize();
66 std::vector<size_t> jointIDTorqueMode;
67 std::vector<size_t> jointIDVelocityMode;
68 arm->jointNames.clear();
69 for (
size_t i = 0; i < rtRns->getSize(); ++i)
72 std::string jointName = rtRns->getNode(i)->getName();
73 arm->jointNames.push_back(jointName);
75 bool foundControlDevice =
false;
77 cfg.jointNameListTorque.begin(), cfg.jointNameListTorque.end(), jointName);
78 if (it != cfg.jointNameListTorque.end())
82 auto* casted_ct = ct->
asA<ControlTarget1DoFActuatorZeroTorque>();
84 arm->targetsTorque.push_back(casted_ct);
85 jointIDTorqueMode.push_back(i);
86 foundControlDevice =
true;
90 cfg.jointNameListVelocity.begin(), cfg.jointNameListVelocity.end(), jointName);
91 if (it != cfg.jointNameListVelocity.end())
95 auto* casted_ct = ct->
asA<ControlTarget1DoFActuatorZeroVelocity>();
97 arm->targetsVel.push_back(casted_ct);
98 jointIDVelocityMode.push_back(i);
99 foundControlDevice =
true;
101 if (not foundControlDevice)
103 ARMARX_INFO << jointName <<
" is not selected for " << arm->kinematicChainName;
107 ARMARX_INFO <<
"Robot node set '" << arm->kinematicChainName
108 <<
"' has torque controlled joints [" << namesTorque
109 <<
"] and velocity controlled joints [" << namesVelocity <<
"].";
113 const auto* torqueSensor = sv->
asA<SensorValue1DoFActuatorTorque>();
114 const auto* velocitySensor = sv->
asA<SensorValue1DoFActuatorVelocity>();
115 const auto* positionSensor = sv->
asA<SensorValue1DoFActuatorPosition>();
117 if (torqueSensor ==
nullptr)
121 if (velocitySensor ==
nullptr)
123 ARMARX_WARNING <<
"No velocity sensor available for " << jointName;
125 if (positionSensor ==
nullptr)
127 ARMARX_WARNING <<
"No position sensor available for " << jointName;
131 arm->sensorDevices.torqueSensors.push_back(torqueSensor);
132 arm->sensorDevices.velocitySensors.push_back(velocitySensor);
133 arm->sensorDevices.positionSensors.push_back(positionSensor);
135 ARMARX_DEBUG <<
"Number of torque controlled joints " << jointIDTorqueMode.size();
136 ARMARX_DEBUG <<
"Number of velocity controlled joints " << jointIDVelocityMode.size();
140 arm->controller.initialize(nonRtRns, rtRns, jointIDTorqueMode, jointIDVelocityMode);
141 arm->controller.ftsensor.initialize(rtRns,
robotUnit, cfg.ftConfig);
145 arm->nonRtConfig = cfg;
150 const NJointControllerConfigPtr& config,
156 ConfigPtrT cfg = ConfigPtrT::dynamicCast(config);
166 limb.emplace(pair.first, std::make_unique<ArmData>());
174 return "NJointTaskspaceZeroTorqueOrVelocityController";
185 double timeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
186 arm->rtConfig = arm->bufferNonRtToRt.getUpToDateReadBuffer();
187 double time_update_non_rt_buffer =
188 IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
190 if (arm->rtFirstRun.load())
192 arm->rtFirstRun.store(
false);
193 arm->rtReady.store(
true);
195 arm->controller.ftsensor.updateStatus(arm->rtConfig.ftConfig,
196 arm->rtStatus.currentForceTorque,
197 arm->rtStatus.deltaT,
198 arm->rtFirstRun.load());
200 double time_update_ft = IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
203 double time_update_size = IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
204 arm->sensorDevices.updateJointValues(
205 arm->rtStatus.jointPosition, arm->rtStatus.jointVelocity, arm->rtStatus.jointTorque);
207 double time_update_js = IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
208 arm->rtStatus.deltaT = deltaT;
209 double time_update_rt_status = IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
211 arm->bufferRtToNonRt.getWriteBuffer() = arm->rtStatus;
212 arm->bufferRtToNonRt.commitWrite();
213 arm->bufferRtStatusToUser.getWriteBuffer() = arm->rtStatus;
214 arm->bufferRtStatusToUser.commitWrite();
215 double time_write_rt_buffer = IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
217 arm->controller.run(arm->rtConfig, arm->rtStatus);
218 double time_run_rt = IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
220 for (
unsigned int i = 0; i < arm->rtStatus.nDoFTorque; i++)
222 auto jointIdx = arm->controller.jointIDTorqueMode[i];
223 arm->targetsTorque.at(i)->torque = arm->rtStatus.desiredJointTorque(jointIdx);
224 if (!arm->targetsTorque.at(i)->isValid())
226 arm->targetsTorque.at(i)->torque = 0;
229 for (
unsigned int i = 0; i < arm->rtStatus.nDoFVelocity; i++)
231 auto jointIdx = arm->controller.jointIDVelocityMode[i];
232 arm->targetsVel.at(i)->velocity = arm->rtStatus.desiredJointVelocity(jointIdx);
234 if (!arm->targetsVel.at(i)->isValid())
236 arm->targetsVel.at(i)->velocity = 0;
239 arm->bufferRtStatusToOnPublish.getWriteBuffer() = arm->rtStatus;
240 arm->bufferRtStatusToOnPublish.commitWrite();
242 arm->bufferRtConfigToOnPublish.getWriteBuffer() = arm->rtConfig;
243 arm->bufferRtConfigToOnPublish.commitWrite();
245 arm->bufferRtConfigToUser.getWriteBuffer() = arm->rtConfig;
246 arm->bufferRtConfigToUser.commitWrite();
247 double time_rt_status_buffer = IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
248 timeMeasure = IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
250 if (timeMeasure > 100)
253 "update_non_rt_buffer: %.2f\n"
255 "update_size: %.2f\n"
257 "update_rt_status: %.2f\n"
258 "write_rt_buffer: %.2f\n"
260 "rt_status_buffer: %.2f\n"
262 time_update_non_rt_buffer,
263 time_update_ft - time_update_non_rt_buffer,
264 time_update_size - time_update_ft,
265 time_update_js - time_update_size,
266 time_update_rt_status - time_update_non_rt_buffer,
267 time_write_rt_buffer - time_update_rt_status,
268 time_run_rt - time_write_rt_buffer,
269 time_rt_status_buffer - time_run_rt,
276 const IceUtil::Time& ,
277 const IceUtil::Time& timeSinceLastIteration)
279 double deltaT = timeSinceLastIteration.toSecondsDouble();
280 for (
auto& pair :
limb)
282 limbRT(pair.second, deltaT);
288 const ::armarx::aron::data::dto::DictPtr& dto,
289 const Ice::Current& iceCurrent)
297 limb.at(pair.first)->bufferUserToNonRt.getWriteBuffer() = pair.second;
298 limb.at(pair.first)->bufferUserToNonRt.commitWrite();
305 for (
auto& pair :
limb)
308 pair.second->bufferRtConfigToUser.getUpToDateReadBuffer();
317 const auto checkNonNegative = [](
const auto& v) {
ARMARX_CHECK(v >= 0); };
318 const auto checkVecNonNegative = [](
const auto& v)
321 checkVecNonNegative(configData.kpCartesianVel);
322 checkVecNonNegative(configData.kdCartesianVel);
324 checkNonNegative(configData.torqueLimit);
325 checkNonNegative(configData.velocityLimit);
326 checkNonNegative(configData.qvelFilter);
327 checkNonNegative(configData.cartesianLinearVelLimit);
328 checkNonNegative(configData.cartesianAngularVelLimit);
337 auto rtConfig = arm->bufferRtConfigToOnPublish.getUpToDateReadBuffer();
338 auto rtStatus = arm->bufferRtStatusToOnPublish.getUpToDateReadBuffer();
343 datafields[
"velocityLimit"] =
new Variant(rtConfig.velocityLimit);
346 debugObs->setDebugChannel(
"ZT-ZV_" + arm->kinematicChainName, datafields);
355 for (
auto& pair :
limb)
364 for (
auto& pair :
limb)
366 pair.second->rtReady.store(
false);
373 VirtualRobot::RobotNodeSetPtr rns =
rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
375 arm->bufferUserToNonRt.reinitAllBuffers(arm->rtConfig);
377 arm->nonRtConfig = arm->rtConfig;
378 arm->bufferNonRtToRt.reinitAllBuffers(arm->rtConfig);
379 arm->bufferRtConfigToOnPublish.reinitAllBuffers(arm->rtConfig);
380 arm->bufferRtConfigToUser.reinitAllBuffers(arm->rtConfig);
383 const auto nDoF = rns->getSize();
389 nDoF, arm->controller.jointIDTorqueMode, arm->controller.jointIDVelocityMode);
390 arm->sensorDevices.updateJointValues(arm->rtStatus.jointPosition,
391 arm->rtStatus.jointVelocity,
392 arm->rtStatus.jointTorque);
394 arm->rtStatusInNonRT = arm->rtStatus;
395 arm->bufferRtStatusToOnPublish.reinitAllBuffers(arm->rtStatus);
396 arm->bufferRtToNonRt.reinitAllBuffers(arm->rtStatus);
397 arm->bufferRtStatusToUser.reinitAllBuffers(arm->rtStatus);
400 arm->controller.preactivateInit(rns);
406 for (
auto& pair :
limb)
408 ARMARX_INFO <<
"rtPreActivateController for " << pair.first;
410 userConfig.limbs.at(pair.first) = pair.second->rtConfig;
426 const std::map<std::string, ConstControlDevicePtr>& controlDevices,
427 const std::map<std::string, ConstSensorDevicePtr>&)
433 ::armarx::WidgetDescription::WidgetSeq widgets;
434 auto addSlider = [&](
const std::string& label,
float min,
float max,
float defaultValue)
436 widgets.emplace_back(
new Label(
false, label));
441 c_x->defaultValue = defaultValue;
443 widgets.emplace_back(c_x);
448 LabelPtr label =
new Label;
449 label->text =
"ZeroTorque (L/R)";
451 StringComboBoxPtr boxZeroTorqueLeft =
new StringComboBox;
452 boxZeroTorqueLeft->name =
"ZeroTorqueLeft";
453 boxZeroTorqueLeft->defaultIndex = 0;
454 boxZeroTorqueLeft->multiSelect =
true;
456 StringComboBoxPtr boxZeroTorqueRight =
new StringComboBox;
457 boxZeroTorqueRight->name =
"ZeroTorqueRight";
458 boxZeroTorqueRight->defaultIndex = 0;
459 boxZeroTorqueRight->multiSelect =
true;
462 LabelPtr labelZVMode =
new Label;
463 labelZVMode->text =
"ZeroVelocity (L/R)";
465 StringComboBoxPtr boxZeroVelocityLeft =
new StringComboBox;
466 boxZeroVelocityLeft->name =
"ZeroVelocityLeft";
467 boxZeroVelocityLeft->defaultIndex = 0;
468 boxZeroVelocityLeft->multiSelect =
true;
470 StringComboBoxPtr boxZeroVelocityRight =
new StringComboBox;
471 boxZeroVelocityRight->name =
"ZeroVelocityRight";
472 boxZeroVelocityRight->defaultIndex = 0;
473 boxZeroVelocityRight->multiSelect =
true;
477 std::map<std::string, StringComboBoxPtr> boxes;
478 boxes.insert({
"zv_left", boxZeroVelocityLeft});
479 boxes.insert({
"zv_right", boxZeroVelocityRight});
480 boxes.insert({
"zt_left", boxZeroTorqueLeft});
481 boxes.insert({
"zt_right", boxZeroTorqueRight});
484 for (
auto&
c : controlDevices)
487 if (
c.first.find(
"ArmL") != std::string::npos)
491 else if (
c.first.find(
"ArmR") != std::string::npos)
500 if (
c.second->hasJointController(ControlModes::ZeroTorque1DoF))
502 boxes.at(
"zt_" + mode)->options.push_back(
c.first);
504 else if (
c.second->hasJointController(ControlModes::ZeroVelocity1DoF))
506 boxes.at(
"zv_" + mode)->options.push_back(
c.first);
511 layout->children.emplace_back(label);
512 layout->children.emplace_back(boxZeroTorqueLeft);
513 layout->children.emplace_back(boxZeroTorqueRight);
514 layout->children.emplace_back(labelZVMode);
515 layout->children.emplace_back(boxZeroVelocityLeft);
516 layout->children.emplace_back(boxZeroVelocityRight);
518 addSlider(
"maxTorque", 0, 100, 10);
519 addSlider(
"maxVeloicty", 0, 3.14, 2.0);
522 layout->children.insert(layout->children.end(), widgets.begin(), widgets.end());
533 "controller_config/NJointTaskspaceZeroTorqueOrVelocityController/default.json");
537 ARMARX_WARNING_S <<
"Left arm of armar7 is not yet calibrated, the default is set to "
538 "RightArm for safety reason!";
540 auto varZTLeft = VariantPtr::dynamicCast(values.at(
"ZeroTorqueLeft"));
541 auto varZTRight = VariantPtr::dynamicCast(values.at(
"ZeroTorqueRight"));
542 auto varZVLeft = VariantPtr::dynamicCast(values.at(
"ZeroVelocityLeft"));
543 auto varZVRight = VariantPtr::dynamicCast(values.at(
"ZeroVelocityRight"));
549 cfgDTO.limbs.at(
"RightArm").jointNameListTorque =
551 cfgDTO.limbs.at(
"RightArm").jointNameListVelocity =
553 cfgDTO.limbs.at(
"RightArm").torqueLimit = values.at(
"maxTorque")->getFloat();
554 cfgDTO.limbs.at(
"RightArm").velocityLimit = values.at(
"maxVeloicty")->getFloat();
559 cfgDTO.limbs.at(
"RightArm").jointNameListVelocity);
560 if (cfgDTO.limbs.at(
"RightArm").jointNameListTorque.size() > 0)
562 ARMARX_INFO_S <<
"'RightArm' has torque controlled joints [" << namesTorque <<
"].";
564 if (cfgDTO.limbs.at(
"RightArm").jointNameListVelocity.size() > 0)
566 ARMARX_INFO_S <<
"'RightArm' has velocity controlled joints [" << namesVelocity <<
"].";
569 ARMARX_INFO_S <<
"torque limit: " << cfgDTO.limbs.at(
"RightArm").torqueLimit
570 <<
"velocity limit: " << cfgDTO.limbs.at(
"RightArm").velocityLimit;
573 return new ConfigurableNJointControllerConfig{cfgDTO.toAronDTO()};
int Label(int n[], int size, int *curLabel, MiscLib::Vector< std::pair< int, size_t > > *labels)
#define ARMARX_RT_LOGF_WARN(...)
Brief description of class JointControlTargetBase.
const SensorValueBase * useSensorValue(const std::string &sensorDeviceName) const
Get a const ptr to the given SensorDevice's SensorValue.
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 SingleTypeVariantList class is a subclass of VariantContainer and is comparable to a std::vector<...
The Variant class is described here: Variants.
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 > &)
void onInitNJointController() override
NJointControllerBase interface.
ConfigurableNJointControllerConfigPtr ConfigPtrT
void limbRT(ArmPtr &arm, const double deltaT)
NJointTaskspaceZeroTorqueOrVelocityController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
::armarx::aron::data::dto::DictPtr getConfig(const Ice::Current &iceCurrent=Ice::emptyCurrent) override
void limbInit(const std::string nodeSetName, ArmPtr &arm, Config cfg, VirtualRobot::RobotPtr &nonRtRobotPtr)
void limbReInit(ArmPtr &arm)
std::map< std::string, ArmPtr > limb
common::control_law::arondto::ZeroTorqueOrVelocityControllerConfig Config
void validateConfigData(Config &config, ArmPtr &arm)
static ConfigPtrT GenerateConfigFromVariants(const StringVariantBaseMap &values)
void rtPostDeactivateController() override
This function is called after the controller is deactivated.
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration) override
TODO make protected and use attorneys.
std::unique_ptr< ArmData > ArmPtr
void updateConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
NJointController interface.
void limbPublish(ArmPtr &arm, const DebugObserverInterfacePrx &debugObs)
VirtualRobot::RobotPtr nonRtRobot
std::string getClassName(const Ice::Current &) const override
void rtPreActivateController() override
This function is called before the controller is activated.
#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_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_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_WARNING_S
The logging level for unexpected behaviour, but not a serious problem.
std::shared_ptr< class Robot > RobotPtr
::IceInternal::Handle< Dict > DictPtr
void debugEigenVec(StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
std::string sVecToString(const std::vector< std::string > &vec, const std::string &delimiter)
NJointControllerRegistration< NJointTaskspaceZeroTorqueOrVelocityController > registrationControllerNJointTaskspaceZeroTorqueOrVelocityController("NJointTaskspaceZeroTorqueOrVelocityController")
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface > DebugObserverInterfacePrx
std::map< std::string, VariantBasePtr > StringVariantBaseMap
AronDTO readFromJson(const std::filesystem::path &filename)
std::vector< T > max(const std::vector< T > &v1, const std::vector< T > &v2)
T fromAronDict(const ::armarx::aron::data::dto::DictPtr &dto)
IceUtil::Handle< class RobotUnit > RobotUnitPtr
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface > DebugDrawerInterfacePrx
detail::ControlThreadOutputBufferEntry SensorAndControl
std::vector< T > min(const std::vector< T > &v1, const std::vector< T > &v2)