CollisionAvoidance.cpp
Go to the documentation of this file.
2
3#include <algorithm>
4
5#include <SimoxUtility/math/convert/mat4f_to_quat.h>
6#include <VirtualRobot/MathTools.h>
7#include <VirtualRobot/Nodes/RobotNode.h>
8#include <VirtualRobot/RobotNodeSet.h>
9
10#include <simox/control/dynamics/RBDLModel.h>
11#include <simox/control/robot/NodeInterface.h>
12
14
18
20
22{
23 void
25 CollisionData& collDataVec,
26 const Config& c,
28 const CollisionRobotIndices& collisionRobotIndices,
29 const Eigen::VectorXf& qvelFiltered,
30 Eigen::VectorXf& jointTorque,
31 const float distanceThresholdRaw,
32 const float distanceThreshold) const
33 {
34 // calculate jacobian
35 {
36 const auto* node = collisionRobotIndices.at(collDataVec.node1);
37 auto localTransformation = Eigen::Isometry3d::Identity();
38 localTransformation.translation() =
39 node->getGlobalPose().inverse() * collDataVec.point1.cast<double>();
40 const bool result = nodeSet_->computeJacobian(
41 collDataVec.jacobian,
42 *node,
43 simox::control::robot::JacobianParams{
44 .mode = simox::control::utils::CartesianSelection::Position,
45 .localTransformation = localTransformation});
47 }
48
49 float distThrSquare = distanceThresholdRaw * distanceThresholdRaw;
50 float factor = c.maxRepulsiveForce / distThrSquare;
51 float diff = collDataVec.minDistance - distanceThreshold;
52 /// calculate common collision pair values
53 collDataVec.repulsiveForce = factor * diff * diff;
54 collDataVec.localStiffness = -2.0 * factor * diff;
55 // minimum distance is always lower than the threshold distance
56 // (local stiffness is always positive)
57 collDataVec.repulsiveForce =
58 std::clamp(collDataVec.repulsiveForce, 0.0f, c.maxRepulsiveForce);
61
62 ARMARX_CHECK_EQUAL(3, collDataVec.direction.rows());
63 // projected in direction of collision (1xn), is saved transposed (nx1)
64 collDataVec.projectedJacT =
65 (collDataVec.direction.transpose() * collDataVec.jacobian.cast<float>()).transpose();
66 ARMARX_CHECK_EQUAL(1, collDataVec.projectedJacT.cols());
67 ARMARX_CHECK_EQUAL(numNodes(), collDataVec.projectedJacT.rows());
68 ARMARX_CHECK_EQUAL(numNodes(), qvelFiltered.rows());
69
70 collDataVec.distanceVelocity = collDataVec.projectedJacT.transpose() * qvelFiltered;
71
74
75 collDataVec.projectedMass = 1 / (collDataVec.projectedJacT.transpose() *
76 rts.inertiaInverse * collDataVec.projectedJacT);
77
79
80 collDataVec.damping = 2 * std::sqrt(collDataVec.localStiffness) *
81 std::sqrt(collDataVec.projectedMass) * c.dampingFactor;
82
83 if (rts.inRecoveryMode)
84 {
85 collDataVec.damping *= c.recoveryDampingFactor;
86 }
87
89
90 jointTorque +=
91 collDataVec.projectedJacT *
92 (collDataVec.repulsiveForce - collDataVec.damping * collDataVec.distanceVelocity);
93 }
94
96 const simox::control::robot::NodeSetInterface* nodeSet) :
97 nodeSet_(nodeSet),
98 identityMat(nodeSet ? Eigen::MatrixXf::Identity(nodeSet->getSize(), nodeSet->getSize())
99 : Eigen::MatrixXf())
100 {
103 }
104
106 {
107
108 ARMARX_INFO << "Destruction of CollisionAvoidanceController";
109 }
110
111 /// methods for self-collision and joint limit avoidance
112 /// avoidance torque methods
113 void
115 const Config& c,
117 RecoveryState& rState,
118 const DistanceResults& collisionPairs,
119 const CollisionRobotIndices& collisionRobotIndices,
120 const Eigen::VectorXf& qvelFiltered,
121 double deltaT) const
122 {
123 /// self-collision avoidance algorithm following the methods in Dietrich et al. (2012):
124 ///
125 /// A. Dietrich, T. Wimbock, A. Albu-Schaffer and G. Hirzinger, "Integration of Reactive,
126 /// Torque-Based Self-Collision Avoidance Into a Task Hierarchy," in IEEE Transactions on
127 /// Robotics, vol. 28, no. 6, pp. 1278-1293, Dec. 2012, doi: 10.1109/TRO.2012.2208667.
128 ///
129 /// see: https://ieeexplore.ieee.org/document/6255795
130 ///
131 /// method:
132 ///
133 /// computes the joint torques to avoid self-collisions -> collisionJointTorque
134
135 ARMARX_CHECK_GREATER(collisionPairs.size(), 0);
136
137 /// clear values before new cycle
138 rts.selfCollisionJointTorque.setZero();
139 rts.activeCollPairsNum = 0;
140
141 for (auto& data : rts.collDataVec)
142 {
143 data.clearValues();
144 }
145
146 /// when collDistanceThresholdInit is smaller than recoveryDistanceElapseMeter
147 /// (usually means it is zero), we need to initilize it to the smallest collision distance
148 /// plus a recoveryDistanceElapseMeter.
149 float& thresholdInit = rState.collDistanceThresholdInit;
150 if (c.enableCollisionRecoveryOnStartup and (thresholdInit < c.recoveryDistanceElapseMeter))
151 {
152 thresholdInit = c.selfDistanceThreshold;
153 for (const DistanceResult& collisionPair : collisionPairs)
154 {
155 float minDist = static_cast<float>(collisionPair.minDistance);
156 if (minDist < thresholdInit)
157 {
158 thresholdInit = std::max(minDist, 0.0f);
159 }
160 }
161 thresholdInit =
162 std::min(c.selfDistanceThreshold, thresholdInit + c.recoveryDistanceElapseMeter);
163 }
164
165 rState.update(c, rts, deltaT);
166
167 /// check collision pairs, which have are below the prefilter distance
168 for (const DistanceResult& collisionPair : collisionPairs)
169 {
170 // if (static_cast<float>(collisionPair.minDistance) >= c.selfDistanceThreshold)
171 if (static_cast<float>(collisionPair.minDistance) >= rState.collDistanceThreshold)
172 {
173 continue;
174 }
175
176 if (collisionRobotIndices.count(collisionPair.node1) == 0 and
177 collisionRobotIndices.count(collisionPair.node2) == 0)
178 {
179 continue;
180 }
181
182 ARMARX_CHECK(collisionPair.hasPoints());
183
184 auto& selfCollDataVec = rts.collDataVec[rts.activeCollPairsNum++];
185
186 selfCollDataVec.minDistance = static_cast<float>(collisionPair.minDistance);
187
188 bool flipped = false;
189 if (collisionRobotIndices.count(collisionPair.node1) > 0)
190 {
191 // First node on nodeset
192
193 if (collisionRobotIndices.count(collisionPair.node2) > 0)
194 {
195 // Check that second node comes later (equals larger index)
196 ARMARX_CHECK_GREATER(collisionPair.node2, collisionPair.node1);
197 }
198
199 selfCollDataVec.node1 = collisionPair.node1;
200 selfCollDataVec.node2 = collisionPair.node2;
201 selfCollDataVec.point1 = collisionPair.point1->cast<float>();
202 selfCollDataVec.point2 = collisionPair.point2->cast<float>();
203 }
204 else
205 {
206 // Second node on nodeset -> flip collision pair
207
208 flipped = true;
209 selfCollDataVec.node1 = collisionPair.node2;
210 selfCollDataVec.node2 = collisionPair.node1;
211 selfCollDataVec.point1 = collisionPair.point2->cast<float>();
212 selfCollDataVec.point2 = collisionPair.point1->cast<float>();
213 }
214
215 // direction is pointing away from collision
216 selfCollDataVec.direction = selfCollDataVec.point1 - selfCollDataVec.point2;
217
218 if (selfCollDataVec.minDistance < 0.0f)
219 {
220 selfCollDataVec.minDistance = 0.0f;
221
222 // check for overlapping spheres or capsules overlapping spheres
223 // (returned points are exactly the same)
224 if (selfCollDataVec.point1.isApprox(selfCollDataVec.point2, 1e-8) and
225 collisionPair.normalVec != std::nullopt)
226 {
227 /// if the points are the same, normalVec comes with a value
228
229 // todo: how to make sure the normalVec is always pointing away from the
230 // collision, in normally the vector points out from the contact point within
231 // the sphere
232 // issue: if the arm is modeled with a sphere, it will point towards the collision
233 // No faulty behavior has been detected so far, however there is the possibility
234 // to get a direction vector pointing towards the collision
235
236 // solution: check if the node is a sphere, if the repulsive force is
237 // suppose to apply on the sphere, use the negative normal direction
238 selfCollDataVec.direction = collisionPair.normalVec->cast<float>();
239 if (flipped)
240 {
241 selfCollDataVec.direction *= -1.0f;
242 }
243 }
244 else
245 {
246 selfCollDataVec.direction *= -1.0f;
247 }
248 }
249
250 selfCollDataVec.direction.normalize();
251
252 calculateCollisionTorque(selfCollDataVec,
253 c,
254 rts,
255 collisionRobotIndices,
256 qvelFiltered,
258 c.selfDistanceThreshold,
259 rState.collDistanceThreshold);
260 }
262 }
263
264 void
266 const Config& c,
268 const Eigen::VectorXf& qpos,
269 const Eigen::VectorXf& qvelFiltered) const
270 {
271 /// method:
272 ///
273 /// computes the joint torques to avoid joint limits -> jointLimitJointTorque
274
275 rts.jointLimitJointTorque.setZero();
276 const size_t n = rts.jointLimitData.size();
278
280 ARMARX_CHECK_EQUAL(numNodes(), rts.inertia.cols());
281 ARMARX_CHECK_EQUAL(numNodes(), rts.inertia.rows());
282
283 /// iterate over all joints and check the joint positions for not limiteless joints
284 for (int i = 0; i < n; ++i)
285 {
286 auto& joint = rts.jointLimitData[i];
287 if (joint.isLimitless)
288 {
289 continue;
290 }
291
292 float diff = 0.0F;
293 float sign = 1.0F;
294 // 1. Determine penetration depth and direction
295 if (qpos[i] < joint.qposThresholdLow)
296 {
297 diff = joint.qposThresholdLow - qpos[i];
298 sign = 1.0F;
299 }
300 else if (qpos[i] > joint.qposThresholdHigh)
301 {
302 diff = qpos[i] - joint.qposThresholdHigh;
303 sign = -1.0F;
304 }
305 else
306 {
307 continue; // Within safe limits
308 }
309
310 // 2. Pre-calculate common factors, done in the init process
311 // maxRepulsiveJointVel = 1 / (thresholdRange * thresholdRange)
312 // kRepulsive = c.maxRepulsiveJointVel * joint.invThresholdSq;
313
314 // 3. Compute Repulsive Velocity (Quadratic)
315 joint.repulsiveTorque =
316 std::min(joint.kRepulsive * (diff * diff), c.maxRepulsiveTorque);
317
318 // 4. Compute Damping
319 // Stiffness is the derivative of the velocity profile
320 const float localStiffness = 2.0F * joint.kRepulsive * diff;
321 const float jointInertia = static_cast<float>(rts.inertia(i, i));
322
323 // Critical Damping: 2 * sqrt(K * M) * zeta
324 const float dampingGain =
325 2.0F * std::sqrt(jointInertia * localStiffness) * c.dampingFactor;
326
327 joint.totalDamping = dampingGain * qvelFiltered[i];
328
329 // 5. Apply result
330 // For Low limit: pos_vel - damping
331 // For High limit: -(pos_vel + damping) => -pos_vel - damping
332 rts.jointLimitJointTorque(i) = (sign * joint.repulsiveTorque) - joint.totalDamping;
333
334
335 // rts.jointInertia = rts.inertia(i, i);
336 // if (qpos[i] < rts.jointLimitData[i].qposThresholdLow)
337 // {
338 // joint.repulsiveTorque =
339 // c.maxRepulsiveTorque / std::pow(rts.jointLimitData[i].thresholdRange, 2) *
340 // std::pow(rts.jointLimitData[i].qposThresholdLow - qpos[i], 2);
341 // ARMARX_CHECK_NONNEGATIVE(joint.repulsiveTorque);
342 // joint.repulsiveTorque =
343 // std::clamp(joint.repulsiveTorque, 0.0f, c.maxRepulsiveTorque);
344 //
345 // rts.localStiffnessJointLim = 2 * c.maxRepulsiveTorque /
346 // std::pow(rts.jointLimitData[i].thresholdRange, 2) *
347 // (rts.jointLimitData[i].qposThresholdLow - qpos[i]);
348 //
349 // ARMARX_CHECK_NONNEGATIVE(rts.localStiffnessJointLim);
350 // rts.dampingJointLim = 2 * std::sqrt(rts.jointInertia) *
351 // std::sqrt(rts.localStiffnessJointLim) * c.dampingFactor;
352 //
353 // ARMARX_CHECK_NONNEGATIVE(rts.dampingJointLim);
354 // joint.totalDamping = rts.dampingJointLim * qvelFiltered[i];
355 // rts.jointLimitJointTorque(i) =
356 // joint.repulsiveTorque - rts.dampingJointLim * qvelFiltered[i];
357 //
358 // ARMARX_TRACE_LITE;
359 // }
360 // else if (qpos[i] > rts.jointLimitData[i].qposThresholdHigh)
361 // {
362 // joint.repulsiveTorque =
363 // c.maxRepulsiveTorque / std::pow(rts.jointLimitData[i].thresholdRange, 2) *
364 // std::pow(qpos[i] - rts.jointLimitData[i].qposThresholdHigh, 2);
365 //
366 // ARMARX_CHECK_NONNEGATIVE(joint.repulsiveTorque);
367 // joint.repulsiveTorque =
368 // std::clamp(joint.repulsiveTorque, 0.0f, c.maxRepulsiveTorque);
369 //
370 // rts.localStiffnessJointLim = 2 * c.maxRepulsiveTorque /
371 //
372 // std::pow(rts.jointLimitData[i].thresholdRange, 2) *
373 // (qpos[i] - rts.jointLimitData[i].qposThresholdHigh);
374 // ARMARX_TRACE_LITE;
375 // ARMARX_CHECK_NONNEGATIVE(rts.localStiffnessJointLim);
376 // rts.dampingJointLim = 2 * std::sqrt(rts.jointInertia) *
377 // std::sqrt(rts.localStiffnessJointLim) * c.dampingFactor;
378 // ARMARX_CHECK_NONNEGATIVE(rts.dampingJointLim);
379 // joint.totalDamping = rts.dampingJointLim * qvelFiltered[i];
380 // rts.jointLimitJointTorque(i) =
381 // -(joint.repulsiveTorque + rts.dampingJointLim * qvelFiltered[i]);
382 // }
383 }
384 }
385
386 /// caclulate null spaces
387 void
389 const common::control_law::arondto::CollisionAvoidanceConfig& c,
390 RtStatusForSafetyStrategy& rtStatus) const
391 {
392 rtStatus.selfCollNullSpace.setIdentity();
393
396
398 rtStatus.selfCollK1 = rtStatus.selfCollisionNullSpaceWeights(0);
399 rtStatus.selfCollK2 = rtStatus.selfCollisionNullSpaceWeights(1);
400 rtStatus.selfCollK3 = rtStatus.selfCollisionNullSpaceWeights(2);
401 rtStatus.selfCollK4 = rtStatus.selfCollisionNullSpaceWeights(3);
402
404
405 for (unsigned int i = 0; i < rtStatus.objectCollDataIndex; i++)
406 {
407 auto& active = rtStatus.collDataVec[i];
408
409 /// get desired null space value based on proximity to collision
410 if (active.minDistance < c.selfCollActivatorZ1)
411 {
412 /// full locking in direction of collision
413 rtStatus.desiredNullSpace = 0.0f;
414 }
415 else if (c.selfCollActivatorZ1 <= active.minDistance &&
416 active.minDistance <= c.selfCollActivatorZ2)
417 {
418 /// in transition state
419 rtStatus.desiredNullSpace = rtStatus.selfCollK1 * std::pow(active.minDistance, 3) +
420 rtStatus.selfCollK2 * std::pow(active.minDistance, 2) +
421 rtStatus.selfCollK3 * active.minDistance +
422 rtStatus.selfCollK4;
423 if (rtStatus.desiredNullSpace > 1.0f)
424 {
426 "desired null space value should not be higher than 1.0");
427 // ARMARX_WARNING
428 // << "desired null space value should not be higher than 1.0, was "
429 // << rtStatus.desiredNullSpace
430 // << ", in collision null space calulation, weights: " << rtStatus.selfCollK1
431 // << ", " << rtStatus.selfCollK2 << ", " << rtStatus.selfCollK3 << ", "
432 // << rtStatus.selfCollK4;
433 }
434 }
435 else
436 {
437 /// unrestricted movement in direction of collision
438 rtStatus.desiredNullSpace = 1.0f;
439 }
440
441
442 active.desiredNSColl = rtStatus.desiredNullSpace;
443 rtStatus.desiredNullSpace = std::clamp(rtStatus.desiredNullSpace, 0.0f, 1.0f);
445 /// normalize projected Jacobian
446 rtStatus.selfCollNormalizedJacT = active.projectedJacT.normalized();
447
449
451 identityMat -
452 (rtStatus.selfCollNormalizedJacT * (1.0f - rtStatus.desiredNullSpace) *
453 rtStatus.selfCollNormalizedJacT.transpose());
454
455 if (c.onlyLimitCollDirection)
456 {
457 /// check, whether impedance joint torque acts against the collision direction
458 ARMARX_CHECK_EQUAL(active.projectedJacT.rows(),
459 rtStatus.impedanceJointTorque.rows());
460 for (int i = 0; i < rtStatus.impedanceJointTorque.rows(); ++i)
461 {
462 if ((active.projectedJacT(i) < 0.0f and
463 rtStatus.impedanceJointTorque(i) < 0.0f) ||
464 (active.projectedJacT(i) > 0.0f and
465 rtStatus.impedanceJointTorque(i) > 0.0f))
466 {
467 // if both have the same sign (both negative or both positive), do not limit DoF
468 rtStatus.selfCollTempNullSpaceMatrix(i, i) = 1.0f;
469 }
470 }
471 }
472
473 /// project desired null space in corresponding direction via the Norm-Jacobian
475 // todo: clamp the diagonal values between 0 and 1
476 }
477 }
478
479 void
482 const Eigen::VectorXf& qpos) const
483 {
484 /// check fundamentals thesis BA Jan Fenker
485 rts.jointLimNullSpace.setIdentity();
486
489
491
492 for (size_t i = 0; i < rts.jointLimitData.size(); ++i)
493 {
494 auto& joint = rts.jointLimitData[i];
495 ARMARX_CHECK_EQUAL(4, joint.jointLimitNullSpaceWeightsLow.rows());
496 ARMARX_CHECK_EQUAL(4, joint.jointLimitNullSpaceWeightsHigh.rows());
497 rts.k1Lo = joint.jointLimitNullSpaceWeightsLow(0);
498 rts.k2Lo = joint.jointLimitNullSpaceWeightsLow(1);
499 rts.k3Lo = joint.jointLimitNullSpaceWeightsLow(2);
500 rts.k4Lo = joint.jointLimitNullSpaceWeightsLow(3);
501 rts.k1Hi = joint.jointLimitNullSpaceWeightsHigh(0);
502 rts.k2Hi = joint.jointLimitNullSpaceWeightsHigh(1);
503 rts.k3Hi = joint.jointLimitNullSpaceWeightsHigh(2);
504 rts.k4Hi = joint.jointLimitNullSpaceWeightsHigh(3);
505
507
508 if (not joint.isLimitless)
509 {
510 /// get desired null space value based on proximity to joint boundaries
511 if (qpos[i] < joint.qposZ1Low)
512 {
513 /// full locking
514 rts.desiredNullSpace = 0.0f;
515 }
516 else if (joint.qposZ1Low <= qpos[i] && qpos[i] <= joint.qposZ2Low)
517 {
518 /// in transition state
519 rts.desiredNullSpace = rts.k1Lo * std::pow(qpos[i], 3) +
520 rts.k2Lo * std::pow(qpos[i], 2) + rts.k3Lo * qpos[i] +
521 rts.k4Lo;
522 if (rts.desiredNullSpace > 1.0f)
523 {
525 "desired null space value should not be higher than 1.0, was %.2f, "
526 "approaching lower joint limit, weights: [%.2f, %.2f, %.2f, %.2f]",
528 rts.k1Lo,
529 rts.k2Lo,
530 rts.k3Lo,
531 rts.k4Lo)
532 .deactivateSpam(2.0f);
533 // ARMARX_WARNING
534 // << "desired null space value should not be higher than 1.0, was "
535 // << rts.desiredNullSpace
536 // << ", approaching lower joint limit, weights: " << rts.k1Lo << ", "
537 // << rts.k2Lo << ", " << rts.k3Lo << ", " << rts.k4Lo;
538 }
539 }
540 else if (joint.qposZ2High <= qpos[i] && qpos[i] <= joint.qposZ1High)
541 {
542 /// in transition state
543 rts.desiredNullSpace = rts.k1Hi * std::pow(qpos[i], 3) +
544 rts.k2Hi * std::pow(qpos[i], 2) + rts.k3Hi * qpos[i] +
545 rts.k4Hi;
546 if (rts.desiredNullSpace > 1.0f)
547 {
549 "desired null space value should not be higher than 1.0, was %.2f, "
550 "approaching lower joint limit, weights: [%.2f, %.2f, %.2f, %.2f]",
552 rts.k1Hi,
553 rts.k2Hi,
554 rts.k3Hi,
555 rts.k4Hi)
556 .deactivateSpam(2.0f);
557
558 // ARMARX_WARNING
559 // << "desired null space value should not be higher than 1.0, was "
560 // << rts.desiredNullSpace
561 // << ", approaching upper joint limit, weights: " << rts.k1Hi << ", "
562 // << rts.k2Hi << ", " << rts.k3Hi << ", " << rts.k4Hi;
563 }
564 }
565 else if (joint.qposZ1High < qpos[i])
566 {
567 /// full locking
568 rts.desiredNullSpace = 0.0f;
569 }
570 else
571 {
572 /// unrestricted movement
573 rts.desiredNullSpace = 1.0f;
574 }
575
576
577 joint.desiredNSjointLim = rts.desiredNullSpace;
578 rts.desiredNullSpace = std::clamp(rts.desiredNullSpace, 0.0f, 1.0f);
580
581 /// set desired null space value in null space matrix
582 rts.jointLimNullSpace(i, i) = 1.0f - (1.0f - rts.desiredNullSpace);
583 }
584 }
585 }
586
587 /// --------------------------------- main rt-loop ------------------------------------------
588
589 void
592 RecoveryState& rStateSelfColl,
593 const DistanceResults& collisionPairs,
594 const CollisionRobotIndices& collisionRobotIndices,
595 DynamicsModel& dynamicsModel,
596 const Eigen::VectorXf& qpos,
597 const Eigen::VectorXf& qvelFiltered,
598 float torqueLimit,
599 double deltaT)
600 {
601 /// run in rt thread
602 /// ----------------------------- inertia calculations --------------------------------------------------
603 dynamicsModel.getInertiaMatrix(qpos.cast<double>(), rtStatus.inertia);
604
605 // rtStatus.inertiaInverse = rtStatus.inertia.cast<float>().inverse();
606 // inertia is positive definite matrix
607 rtStatus.inertiaInverse = rtStatus.inertia.cast<float>().llt().solve(identityMat);
608
609 /// ----------------------------- safety constraints --------------------------------------------------
610 if (c.enableSelfCollisionAvoidance)
611 {
612 // calculation of self-collision avoidance torque
613 const double timeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
615 rtStatus,
616 rStateSelfColl,
617 collisionPairs,
618 collisionRobotIndices,
619 qvelFiltered,
620 deltaT);
621 rtStatus.collisionTorqueTime =
622 IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
623 }
624 if (c.enableJointLimitAvoidance)
625 {
626 // calculation of joint limit avoidance torque
627 const double timeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
628 calculateJointLimitTorque(c, rtStatus, qpos, qvelFiltered);
629 rtStatus.jointLimitTorqueTime =
630 IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
631 }
632 if (!c.samePriority)
633 {
634 if (c.enableSelfCollisionAvoidance)
635 {
636 // calculation of null space matrix for self-collision avoidance
637 const double timeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
639 rtStatus.selfCollNullspaceTime =
640 IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
641 }
642 if (c.enableJointLimitAvoidance)
643 {
644 // calculation of null space matrix for joint limit avoidance
645 const double timeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
646 calculateJointLimitNullspace(c, rtStatus, qpos);
647 rtStatus.jointLimitNullspaceTime =
648 IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
649 }
650 }
652
653 /// --------------------------- apply EMA low pass filter -----------------------------------------------
654 if (c.filterSafetyValues)
655 {
656 float coeff = rtStatus.inRecoveryMode ? 0.8 * c.safetyValFilter : c.safetyValFilter;
657 /// filter safety constraint values using EMA low pass filter
658 for (int i = 0; i < rtStatus.selfCollisionJointTorque.size(); ++i)
659 {
660 rtStatus.selfCollisionTorqueFiltered(i) =
661 (1 - coeff) * rtStatus.selfCollisionTorqueFiltered(i) +
662 coeff * rtStatus.selfCollisionJointTorque(i);
663 }
664 for (int i = 0; i < rtStatus.jointLimitJointTorque.size(); ++i)
665 {
666 rtStatus.jointLimitTorqueFiltered(i) =
667 (1 - coeff) * rtStatus.jointLimitTorqueFiltered(i) +
668 coeff * rtStatus.jointLimitJointTorque(i);
669 }
670
671 for (int i = 0; i < rtStatus.selfCollNullSpace.diagonalSize(); ++i)
672 {
673 // the computed values are only on the diagonal, so only these need to be filtered
674 rtStatus.selfCollNullSpaceFiltered(i, i) =
675 (1 - coeff) * rtStatus.selfCollNullSpaceFiltered(i, i) +
676 coeff * rtStatus.selfCollNullSpace(i, i);
677 }
678 for (int i = 0; i < rtStatus.jointLimNullSpace.diagonalSize(); ++i)
679 {
680 // the computed values are only on the diagonal, so only these need to be filtered
681 rtStatus.jointLimNullSpaceFiltered(i, i) =
682 (1 - coeff) * rtStatus.jointLimNullSpaceFiltered(i, i) +
683 coeff * rtStatus.jointLimNullSpace(i, i);
684 }
685 /// assign filtered values
690 }
691
693 /// ----------------------------- hierarchical control --------------------------------------------------
694 /// The following control hierarchies are considered:
695 ///
696 /// three tasks in hierarchy: "enableSelfCollisionAvoidance": true, "enableJointLimitAvoidance": true
697 ///
698 /// flag: "samePriority": true
699 /// same priority: torque_coll + torque_jl + torque_imp
700 ///
701 /// flag: "topPrioritySelfCollisionAvoidance": true, "samePriority": false
702 /// self-coll avoidance on top: torque_coll -> torque_jl -> torque_imp
703 ///
704 /// flag: "topPriorityJointLimitAvoidance": true, "samePriority": false
705 /// joint limit avoidance on top: torque_jl -> torque_coll -> torque_imp
706 ///
707 /// flag: "topPrioritySelfCollisionAvoidance": false, "topPriorityJointLimitAvoidance": false,
708 /// "samePriority": false
709 /// (torque_coll + torque_jl) -> torque_imp
710 /// self-coll and joint limit avoidance on same priority level:
711 ///
712 /// two tasks in hierarchy:
713 ///
714 /// "enableSelfCollisionAvoidance": true, "enableJointLimitAvoidance": false
715 /// self-coll avoidance on top: torque_coll -> torque_imp
716 ///
717 /// "enableSelfCollisionAvoidance": false, "enableJointLimitAvoidance": true
718 /// joint limit avoidance on top: torque_jl -> torque_imp
719 ///
720 /// one task in hierarchy (impedance control):
721 ///
722 /// "enableSelfCollisionAvoidance": false, "enableJointLimitAvoidance": false
723 /// only impedance control: torque_imp
724
725 // ARMARX_INFO << VAROUT(c.samePriority);
726 if (c.samePriority)
727 {
731 rtStatus.desiredJointTorques =
733 rtStatus.impedanceJointTorque + rtStatus.kdImpedanceTorque;
735 }
736 else if (c.enableSelfCollisionAvoidance and c.enableJointLimitAvoidance)
737 {
738 /// three tasks in hierarchy considered
739
740 if (c.topPrioritySelfCollisionAvoidance)
741 {
742
746 rtStatus.selfCollNullSpace.cols());
750 rtStatus.selfCollNullSpace.cols());
751
752 rtStatus.desiredJointTorques =
753 rtStatus.selfCollisionJointTorque +
754 rtStatus.selfCollNullSpace *
755 (rtStatus.jointLimitJointTorque +
756 rtStatus.jointLimNullSpace * rtStatus.impedanceJointTorque) +
757 rtStatus.kdImpedanceTorque;
758
759 // debug values
760 rtStatus.projJointLimJointTorque =
761 rtStatus.selfCollNullSpace * rtStatus.jointLimitJointTorque;
762 rtStatus.projImpedanceJointTorque =
763 rtStatus.selfCollNullSpace *
764 (rtStatus.jointLimNullSpace * rtStatus.impedanceJointTorque);
765 }
766 else if (c.topPriorityJointLimitAvoidance)
767 {
771 rtStatus.selfCollNullSpace.cols());
775 rtStatus.jointLimNullSpace.cols());
776
777 rtStatus.desiredJointTorques =
778 rtStatus.jointLimitJointTorque +
779 rtStatus.jointLimNullSpace *
780 (rtStatus.selfCollisionJointTorque +
781 rtStatus.selfCollNullSpace * rtStatus.impedanceJointTorque) +
782 rtStatus.kdImpedanceTorque;
783
784 // debug values
785 rtStatus.projCollJointTorque =
787 rtStatus.projImpedanceJointTorque =
788 rtStatus.jointLimNullSpace *
789 (rtStatus.selfCollNullSpace * rtStatus.impedanceJointTorque);
790 }
791 else
792 {
796 rtStatus.selfCollNullSpace.cols());
800 rtStatus.jointLimNullSpace.cols());
801 rtStatus.desiredJointTorques =
803 (rtStatus.jointLimNullSpace * rtStatus.selfCollNullSpace) *
804 rtStatus.impedanceJointTorque +
805 rtStatus.kdImpedanceTorque;
806
807 // debug values
808 rtStatus.projImpedanceJointTorque =
809 (rtStatus.jointLimNullSpace * rtStatus.selfCollNullSpace) *
810 rtStatus.impedanceJointTorque;
811 }
812 }
813 else if (c.enableSelfCollisionAvoidance)
814 {
815 /// impedance control and self-collision avoidance
816
820 rtStatus.selfCollNullSpace.cols());
821
822 rtStatus.desiredJointTorques =
823 rtStatus.selfCollisionJointTorque +
824 rtStatus.selfCollNullSpace * rtStatus.impedanceJointTorque +
825 rtStatus.kdImpedanceTorque;
826
827 // debugging
828 rtStatus.projImpedanceJointTorque =
829 rtStatus.selfCollNullSpace * rtStatus.impedanceJointTorque;
830 }
831 else if (c.enableJointLimitAvoidance)
832 {
833 /// impedance control and joint limit avoidance
834
838 rtStatus.jointLimNullSpace.cols());
839
840 rtStatus.desiredJointTorques =
841 rtStatus.jointLimitJointTorque +
842 rtStatus.jointLimNullSpace * rtStatus.impedanceJointTorque +
843 rtStatus.kdImpedanceTorque;
844
845 // debugging
846 rtStatus.projImpedanceJointTorque =
847 rtStatus.jointLimNullSpace * rtStatus.impedanceJointTorque;
848 }
849 else
850 {
851 /// plain impedance control
852 rtStatus.desiredJointTorques =
853 rtStatus.impedanceJointTorque + rtStatus.kdImpedanceTorque;
854 }
855
856 // rtStatus.desiredJointTorques += rtStatus.jointDampingTorque;
857
859
860 /// ------------------------- write impedance forces to buffer -----------------------------------------
861 // this section is purely for visualization purposes in the viewer
862 // rtStatus.dirErrorImp = rtStatus.poseErrorImp.head<3>().normalized();
863 // rtStatus.totalForceImpedance = rtStatus.forceImpedance.head<3>().norm();
864 // rtStatus.projForceImpedance = rtStatus.jtpinv * rtStatus.projImpedanceJointTorque;
865 // rtStatus.projTotalForceImpedance = rtStatus.projForceImpedance.head<3>().norm();
866 // rtStatus.impForceRatio = rtStatus.projTotalForceImpedance / rtStatus.totalForceImpedance;
867 // rtStatus.impTorqueRatio =
868 // rtStatus.projImpedanceJointTorque.norm() / rtStatus.impedanceJointTorque.norm();
869
870
871 /// ----------------------------- write torque target --------------------------------------------------
872 for (int i = 0; i < rtStatus.desiredJointTorques.rows(); ++i)
873 {
874 rtStatus.desiredJointTorques(i) =
875 std::clamp(rtStatus.desiredJointTorques(i), -torqueLimit, torqueLimit);
876 }
877 }
878
879 void
881 float jointVelLimit,
882 const TSCtrlRtStatus& rts)
883 {
884 float k_d = 0.5F;
886 for (size_t i = 0; i < nDoFVel; ++i)
887 {
888 size_t idx = rts.jointIDVelocityMode[i];
889 qTemp(i) = jointTorque(idx) - k_d * (qdVel(i) - rts.qvelFiltered(idx));
890 /* - k_p * (rtStatus.qdPos(i) - rtStatus.jointPosition(idx))*/
891 }
893 qdVel = 0.5 * (rts.deltaT * qdAcc + qdVel);
894 jointVel.setZero();
895 for (size_t i = 0; i < nDoFVel; ++i)
896 {
898 std::clamp(qdVel(i), -jointVelLimit, jointVelLimit);
899 }
900 }
901
902 void
904 size_t nDoFVelocity)
905 {
906 nDoFVel = nDoFVelocity;
907 jointVel.setZero(static_cast<int64_t>(nDoFNodeSet));
908 qdVel.setZero(static_cast<int64_t>(nDoFVel));
909 qdAcc.setZero(static_cast<int64_t>(nDoFVel));
910 qTemp.setZero(static_cast<int64_t>(nDoFVel));
911 // TODO: the interface should be activated when at least one joint is velocity controlled
912 // However, due to incomplete hierarchy design, the activation is only used for full velocity control mode
913 // active = nDoFVel > 0;
914 active = nDoFVel == nDoFNodeSet;
915 }
916
917 void
919 const Config& c,
920 const unsigned int nDoF,
921 const unsigned int maxCollisionPairs,
922 VirtualRobot::RobotNodeSetPtr& rns,
923 const std::vector<size_t>& velCtrlIndex)
924 {
925 /// targets
926 desiredJointTorques.setZero(nDoF);
927 desiredJointVel.setZero(nDoF);
928
929 ///
930 trackingError = 0.0;
931 dirErrorImp.setZero();
933 projForceImpedance.setZero();
935
936 /// intermediate torque results
937 impedanceJointTorque.setZero(nDoF);
938 kdImpedanceTorque.setZero(nDoF); // TODO remove this
939 selfCollisionJointTorque.setZero(nDoF);
940 objectCollisionJointTorque.setZero(nDoF);
941 jointLimitJointTorque.setZero(nDoF);
942
943 selfCollisionTorqueFiltered.setZero(nDoF);
944 objectCollisionTorqueFiltered.setZero(nDoF);
945 jointLimitTorqueFiltered.setZero(nDoF);
946
947 /// for admittance interface
948 selfCollisionJointVel.setZero(nDoF);
949 objectCollisionJointVel.setZero(nDoF);
950 jointLimitJointVel.setZero(nDoF);
951
952 /// intermediate projected torques via null space matrices
953 projImpedanceJointTorque.setZero(nDoF);
954 projCollJointTorque.setZero(nDoF);
955 projJointLimJointTorque.setZero(nDoF);
956
957 impForceRatio = 0.0f;
958 impTorqueRatio = 0.0f;
959
960 /// intermediate null space matrices (collision and joint limit avoidance)
961 selfCollNullSpace.resize(nDoF, nDoF);
962 selfCollNullSpace.setZero();
963 jointLimNullSpace.resize(nDoF, nDoF);
964 jointLimNullSpace.setZero();
965 objectCollNullSpace.resize(nDoF, nDoF);
966 objectCollNullSpace.setZero();
967 impedanceNullSpace.resize(nDoF, nDoF);
968 impedanceNullSpace.setIdentity();
969 desiredNullSpace = 0.0;
970
971 selfCollNullSpaceFiltered.resize(nDoF, nDoF);
973 objectCollNullSpaceFiltered.resize(nDoF, nDoF);
975 jointLimNullSpaceFiltered.resize(nDoF, nDoF);
977
978 /// self-collision avoidance initialization parameters
979 /// calculate weights for self-collision nullspace transition function
980 /// range between z1 and z2
981 /// z1: below this distance [m] the collision direction is fully locked
982 /// z2: above this distance collision direction is unrestricted
983 // collisionNullSpaceWeights.setZero();
985 helper::calculateTransitionWeights(c.selfCollActivatorZ1, c.selfCollActivatorZ2);
986
987 /// distance results
988 Eigen::Vector3d point1(0.0, 0.0, 0.0);
989 Eigen::Vector3d point2(0.0, 0.0, 0.0);
990 Eigen::Vector3d norm(0.0, 0.0, 0.0);
991
992 collDataVec.resize(maxCollisionPairs, CollisionAvoidanceController::CollisionData(nDoF));
993
994 /// self-collision avoidance null space intermediate results
995 selfCollK1 = 0.0;
996 selfCollK2 = 0.0;
997 selfCollK3 = 0.0;
998 selfCollK4 = 0.0;
999 selfCollNormalizedJacT.setZero(nDoF);
1000 selfCollTempNullSpaceMatrix.resize(nDoF, nDoF);
1002
1003 /// object-collision avoidance null space intermediate results
1004 objectCollK1 = 0.0;
1005 objectCollK2 = 0.0;
1006 objectCollK3 = 0.0;
1007 objectCollK4 = 0.0;
1008 objectCollNormalizedJacT.setZero(nDoF);
1009 objectCollTempNullSpaceMatrix.resize(nDoF, nDoF);
1011
1012 /// joint limit avoidance initialization parameters
1013 CollisionAvoidanceController::RtStatusForSafetyStrategy::initJointLimtDataVec(c, nDoF, rns);
1014
1015 /// others
1016 inertia.resize(nDoF, nDoF);
1017 inertia.setZero();
1018 inertiaInverse.resize(nDoF, nDoF);
1019 inertiaInverse.setZero();
1020
1021 /// time status
1022 collisionPairTime = 0.0;
1023 preFilterTime = 0.0;
1024 collisionTorqueTime = 0.0;
1028
1029 /// collision pair info
1032
1033 /// priority accumulators
1034 nullSpaceAcc.resize(nDoF, nDoF);
1035 nullSpaceAcc.setIdentity();
1036 torqueAcc.resize(nDoF);
1037 torqueAcc.setZero();
1038 finalTorque.resize(nDoF);
1039 finalTorque.setZero();
1040
1041 /// admittance interface for vel controlled joints
1042 velCtrlIdx = velCtrlIndex;
1043 size_t nDoFVel = velCtrlIdx.size();
1044 selfColAdmInterface.reset(nDoF, nDoFVel);
1045 objColAdmInterface.reset(nDoF, nDoFVel);
1046 jointLimAdmInterface.reset(nDoF, nDoFVel);
1047 }
1048
1049 void
1051 {
1052 timeSinceStart = 0.0;
1053 inRecoveryMode = c.enableCollisionRecoveryOnStartup;
1054 }
1055
1056 void
1057 CollisionAvoidanceController::RtStatusForSafetyStrategy::initJointLimtDataVec(
1058 const Config& c,
1059 const unsigned int nDoF,
1060 VirtualRobot::RobotNodeSetPtr& rns)
1061 {
1062 jointVel = 0.0;
1063 jointInertia = 0.0;
1064
1065 localStiffnessJointLim = 0.0;
1066 dampingJointLim = 0.0;
1067
1068 k1Lo = 0.0;
1069 k2Lo = 0.0;
1070 k3Lo = 0.0;
1071 k4Lo = 0.0;
1072 k1Hi = 0.0;
1073 k2Hi = 0.0;
1074 k3Hi = 0.0;
1075 k4Hi = 0.0;
1076
1077 jointLimitData.resize(nDoF);
1078
1079 /// obtain joint information (limits, limitless) from VirtualRobot
1080 for (size_t i = 0; i < nDoF; ++i)
1081 {
1082 jointLimitData[i].jointName = rns->getNode(i)->getName();
1083 jointLimitData[i].isLimitless = rns->getNode(i)->isLimitless();
1084
1085 if (not jointLimitData[i].isLimitless)
1086 {
1087 jointLimitData[i].qLimLow = rns->getNode(i)->getJointLimitLow();
1088 jointLimitData[i].qLimHigh = rns->getNode(i)->getJointLimitHigh();
1089 }
1090 }
1091
1092 // std::vector<std::string> jointInfo;
1093 for (auto& joint : jointLimitData)
1094 {
1095 if (not joint.isLimitless)
1096 {
1097 /// set joint limit avoidance threshold parameters for not limiteless joints
1098 float qRange = joint.qLimHigh - joint.qLimLow;
1099 joint.thresholdRange = c.jointRangeBufferZone * qRange;
1100 joint.invThresholdSq = 1.0F / (joint.thresholdRange * joint.thresholdRange);
1101 joint.kRepulsive = c.maxRepulsiveTorque * joint.invThresholdSq;
1102 joint.qposThresholdLow = joint.qLimLow + joint.thresholdRange;
1103 joint.qposThresholdHigh = joint.qLimHigh - joint.thresholdRange;
1104 float qposZ1 = c.jointRangeBufferZoneZ1 * qRange;
1105 float qposZ2 = c.jointRangeBufferZoneZ2 * qRange;
1106 joint.qposZ1Low = joint.qLimLow + qposZ1;
1107 joint.qposZ2Low = joint.qLimLow + qposZ2;
1108 joint.qposZ1High = joint.qLimHigh - qposZ1;
1109 joint.qposZ2High = joint.qLimHigh - qposZ2;
1110 joint.jointLimitNullSpaceWeightsLow =
1111 helper::calculateTransitionWeights(joint.qposZ1Low, joint.qposZ2Low);
1112 joint.jointLimitNullSpaceWeightsHigh =
1113 helper::calculateTransitionWeights(joint.qposZ1High, joint.qposZ2High);
1114
1115 /// from here: only the parameter output information is prepared
1116 // std::vector<float> params = {joint.qLimLow,
1117 // joint.qLimHigh,
1118 // joint.qposThresholdLow,
1119 // joint.qposThresholdHigh,
1120 // joint.qposZ1Low,
1121 // joint.qposZ2Low,
1122 // joint.qposZ1High,
1123 // joint.qposZ2High,
1124 // joint.jointLimitNullSpaceWeightsLow(0),
1125 // joint.jointLimitNullSpaceWeightsLow(1),
1126 // joint.jointLimitNullSpaceWeightsLow(2),
1127 // joint.jointLimitNullSpaceWeightsLow(3),
1128 // joint.jointLimitNullSpaceWeightsHigh(0),
1129 // joint.jointLimitNullSpaceWeightsHigh(1),
1130 // joint.jointLimitNullSpaceWeightsHigh(2),
1131 // joint.jointLimitNullSpaceWeightsHigh(3)};
1132 // std::vector<std::string> stringParams;
1133 // // convert float values to string rounded to two digits
1134 // for (auto& param : params)
1135 // {
1136 // std::stringstream ss;
1137 // ss << std::fixed << std::setprecision(2) << param;
1138 // stringParams.push_back(ss.str());
1139 // }
1140 // std::string info = joint.jointName + ": LimLo: " + stringParams[0] +
1141 // " - LimHi: " + stringParams[1] + " - q0L: " + stringParams[2] +
1142 // " - q0H: " + stringParams[3] + " - z1L: " + stringParams[4] +
1143 // " z2L: " + stringParams[5] + " z1H: " + stringParams[6] +
1144 // " z2H: " + stringParams[7] + " k1L: " + stringParams[8] +
1145 // " k2L: " + stringParams[9] + " k3L: " + stringParams[10] +
1146 // " k4L: " + stringParams[11] + " k1H: " + stringParams[12] +
1147 // " k2H: " + stringParams[13] + " k3H: " + stringParams[14] +
1148 // " k4H: " + stringParams[15];
1149 // jointInfo.push_back(info);
1150 }
1151 }
1152
1153 // std::ostringstream oss;
1154 // for (const auto& str : jointInfo)
1155 // {
1156 // oss << str << "\n";
1157 // }
1158 // std::string initMessage = oss.str();
1159 // ARMARX_INFO << "joint limit avoidance parameters initialized for: \n" << initMessage;
1160 }
1161
1162 void
1163 collision::validateConfigData(const arondto::CollisionAvoidanceConfig& cfg)
1164 {
1165 /// collision config parameters
1166 ARMARX_CHECK_GREATER(cfg.dampingFactor, 0.0); // damping can't be exactly zero
1167 ARMARX_CHECK_LESS_EQUAL(cfg.dampingFactor, 1.0); // for scaling of the damping
1168 ARMARX_CHECK_GREATER(cfg.maxRepulsiveForce, 0.0);
1169 ARMARX_CHECK_NONNEGATIVE(cfg.maxRepulsiveForce);
1170 ARMARX_CHECK_NONNEGATIVE(cfg.selfDistanceThreshold);
1171 ARMARX_CHECK_NONNEGATIVE(cfg.selfCollActivatorZ1);
1172 ARMARX_CHECK_NONNEGATIVE(cfg.selfCollActivatorZ2);
1173 ARMARX_CHECK_GREATER(cfg.selfCollActivatorZ2, cfg.selfCollActivatorZ1);
1174
1175 /// joint limit avoidance config parameters
1176 ARMARX_CHECK_NONNEGATIVE(cfg.maxRepulsiveTorque);
1177 ARMARX_CHECK_NONNEGATIVE(cfg.jointRangeBufferZone);
1178 ARMARX_CHECK_LESS_EQUAL(cfg.jointRangeBufferZone, 1.0); // percentage value
1179 ARMARX_CHECK_NONNEGATIVE(cfg.jointRangeBufferZoneZ1);
1180 ARMARX_CHECK_LESS_EQUAL(cfg.jointRangeBufferZoneZ1, 1.0); // percentage value
1181 ARMARX_CHECK_NONNEGATIVE(cfg.jointRangeBufferZoneZ2);
1182 ARMARX_CHECK_GREATER(cfg.jointRangeBufferZoneZ2, cfg.jointRangeBufferZoneZ1);
1183 ARMARX_CHECK_LESS_EQUAL(cfg.jointRangeBufferZoneZ2, 1.0); // percentage value
1184 ARMARX_CHECK_NONNEGATIVE(cfg.safetyValFilter);
1185 ARMARX_CHECK_LESS_EQUAL(cfg.safetyValFilter, 1.0);
1186
1187 /// check hierarchy flags for valid config
1188 if (cfg.topPrioritySelfCollisionAvoidance)
1189 {
1190 ARMARX_CHECK_EXPRESSION(cfg.enableSelfCollisionAvoidance);
1192 (cfg.topPrioritySelfCollisionAvoidance == !cfg.topPriorityJointLimitAvoidance));
1193 }
1194 if (cfg.topPriorityJointLimitAvoidance)
1195 {
1196 ARMARX_CHECK_EXPRESSION(cfg.enableJointLimitAvoidance);
1198 (cfg.topPrioritySelfCollisionAvoidance == !cfg.topPriorityJointLimitAvoidance));
1199 }
1200 }
1201
1202 void
1204 RtStatusForSafetyStrategy& rtStatus,
1205 double deltaT)
1206 {
1207 if (not c.enableCollisionRecoveryOnStartup or not rtStatus.inRecoveryMode)
1208 {
1209 collDistanceThreshold = c.selfDistanceThreshold;
1210 return;
1211 }
1212
1213 /// 1. determine current time since start
1214 rtStatus.timeSinceStart += deltaT;
1215 if (rtStatus.timeSinceStart > c.recoveryDurationSec)
1216 {
1217 rtStatus.inRecoveryMode = false;
1218 }
1219
1220 /// 2. update threshold
1222 std::min(c.selfDistanceThreshold,
1224 (c.selfDistanceThreshold - collDistanceThresholdInit) *
1225 static_cast<float>(rtStatus.timeSinceStart) / c.recoveryDurationSec);
1226 }
1227
1228 void
1234
1235} // namespace armarx::control::common::control_law
#define ARMARX_RT_LOGF_WARNING(...)
constexpr T c
internal status of the controller, containing intermediate variables, mutable targets
std::vector< size_t > velCtrlIdx
admittance interface for velocity controlled joint
Eigen::MatrixXf selfCollNullSpace
intermediate null space matrices ((self-)collision and joint limit avoidance)
Eigen::VectorXf projImpedanceJointTorque
intermediate projected torques via null space matrices
Eigen::Vector4f selfCollisionNullSpaceWeights
collision avoidance initialization parameters
std::vector< JointRangeBufferZoneData > jointLimitData
joint limit avoidance initialization parameters
void reset(const Config &c, unsigned int nDoF, unsigned int maxCollisionPairs, VirtualRobot::RobotNodeSetPtr &rns, const std::vector< size_t > &velCtrlIndex)
void calculateJointLimitNullspace(const Config &c, RtStatusForSafetyStrategy &rtStatus, const Eigen::VectorXf &qpos) const
::simox::control::environment::DistanceResult DistanceResult
void calculateJointLimitTorque(const Config &c, RtStatusForSafetyStrategy &rtStatus, const Eigen::VectorXf &qpos, const Eigen::VectorXf &qvelFiltered) const
void calculateSelfCollisionNullspace(const Config &c, RtStatusForSafetyStrategy &rtStatus) const
caclulate null spaces
CollisionAvoidanceController(const simox::control::robot::NodeSetInterface *nodeSet)
std::unordered_map< unsigned int, const simox::control::robot::NodeInterface * > CollisionRobotIndices
void calculateCollisionTorque(CollisionData &collDataVec, const Config &c, RtStatusForSafetyStrategy &rts, const CollisionRobotIndices &collisionRobotIndices, const Eigen::VectorXf &qvelFiltered, Eigen::VectorXf &jointTorque, float distanceThresholdRaw, float distanceThreshold) const
void calculateSelfCollisionTorque(const Config &c, RtStatusForSafetyStrategy &rtStatus, RecoveryState &rState, const DistanceResults &collisionPairs, const CollisionRobotIndices &collisionRobotIndices, const Eigen::VectorXf &qvelFiltered, double deltaT) const
avoidance torque methods
common::control_law::arondto::CollisionAvoidanceConfig Config
void run(const Config &c, RtStatusForSafetyStrategy &robotStatus, RecoveryState &rStateSelfColl, const DistanceResults &collisionPairs, const CollisionRobotIndices &collisionRobotIndices, DynamicsModel &dynamicsModel, const Eigen::VectorXf &qpos, const Eigen::VectorXf &qvelFiltered, float torqueLimit, double deltaT)
------------------------------— main rt-loop ---------------------------------------—
#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_LESS_EQUAL(lhs, rhs)
This macro evaluates whether lhs is less or equal (<=) rhs and if it turns out to be false it will th...
#define ARMARX_CHECK_NONNEGATIVE(number)
Check whether number is nonnegative (>= 0).
#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.
Definition Logging.h:181
void validateConfigData(const arondto::CollisionAvoidanceConfig &cfg)
Eigen::Vector4f calculateTransitionWeights(float z1, float z2)
helper functions
Definition utils.cpp:25
T sign(T t)
Definition algorithm.h:214
double norm(const Point &a)
Definition point.hpp:102
void run(Eigen::VectorXf &jointTorque, float jointVelLimit, const TSCtrlRtStatus &rts)
unsigned int node1
the distances and projected jacobians from the generateSelfCollisionTorque() method are needed for th...
void update(const Config &c, RtStatusForSafetyStrategy &rtStatus, double deltaT)
Eigen::VectorXf qvelFiltered
for velocity control
Definition common.h:78
#define ARMARX_TRACE_LITE
Definition trace.h:98