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>
10#include <simox/control/dynamics/RBDLModel.h>
11#include <simox/control/robot/NodeInterface.h>
29 const Eigen::VectorXf& qvelFiltered,
30 Eigen::VectorXf& jointTorque,
31 const float distanceThresholdRaw,
32 const float distanceThreshold)
const
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(
43 simox::control::robot::JacobianParams{
44 .mode = simox::control::utils::CartesianSelection::Position,
45 .localTransformation = localTransformation});
49 float distThrSquare = distanceThresholdRaw * distanceThresholdRaw;
50 float factor =
c.maxRepulsiveForce / distThrSquare;
51 float diff = collDataVec.
minDistance - distanceThreshold;
65 (collDataVec.
direction.transpose() * collDataVec.
jacobian.cast<
float>()).transpose();
85 collDataVec.
damping *=
c.recoveryDampingFactor;
96 const simox::control::robot::NodeSetInterface* nodeSet) :
98 identityMat(nodeSet ?
Eigen::MatrixXf::Identity(nodeSet->getSize(), nodeSet->getSize())
108 ARMARX_INFO <<
"Destruction of CollisionAvoidanceController";
120 const Eigen::VectorXf& qvelFiltered,
150 if (
c.enableCollisionRecoveryOnStartup and (thresholdInit <
c.recoveryDistanceElapseMeter))
152 thresholdInit =
c.selfDistanceThreshold;
155 float minDist =
static_cast<float>(collisionPair.minDistance);
156 if (minDist < thresholdInit)
158 thresholdInit = std::max(minDist, 0.0f);
162 std::min(
c.selfDistanceThreshold, thresholdInit +
c.recoveryDistanceElapseMeter);
176 if (collisionRobotIndices.count(collisionPair.node1) == 0 and
177 collisionRobotIndices.count(collisionPair.node2) == 0)
186 selfCollDataVec.minDistance =
static_cast<float>(collisionPair.minDistance);
188 bool flipped =
false;
189 if (collisionRobotIndices.count(collisionPair.node1) > 0)
193 if (collisionRobotIndices.count(collisionPair.node2) > 0)
199 selfCollDataVec.node1 = collisionPair.node1;
200 selfCollDataVec.node2 = collisionPair.node2;
201 selfCollDataVec.point1 = collisionPair.point1->cast<
float>();
202 selfCollDataVec.point2 = collisionPair.point2->cast<
float>();
209 selfCollDataVec.node1 = collisionPair.node2;
210 selfCollDataVec.node2 = collisionPair.node1;
211 selfCollDataVec.point1 = collisionPair.point2->cast<
float>();
212 selfCollDataVec.point2 = collisionPair.point1->cast<
float>();
216 selfCollDataVec.direction = selfCollDataVec.point1 - selfCollDataVec.point2;
218 if (selfCollDataVec.minDistance < 0.0f)
220 selfCollDataVec.minDistance = 0.0f;
224 if (selfCollDataVec.point1.isApprox(selfCollDataVec.point2, 1e-8) and
225 collisionPair.normalVec != std::nullopt)
238 selfCollDataVec.direction = collisionPair.normalVec->cast<
float>();
241 selfCollDataVec.direction *= -1.0f;
246 selfCollDataVec.direction *= -1.0f;
250 selfCollDataVec.direction.normalize();
255 collisionRobotIndices,
258 c.selfDistanceThreshold,
268 const Eigen::VectorXf& qpos,
269 const Eigen::VectorXf& qvelFiltered)
const
284 for (
int i = 0; i < n; ++i)
287 if (joint.isLimitless)
295 if (qpos[i] < joint.qposThresholdLow)
297 diff = joint.qposThresholdLow - qpos[i];
300 else if (qpos[i] > joint.qposThresholdHigh)
302 diff = qpos[i] - joint.qposThresholdHigh;
315 joint.repulsiveTorque =
316 std::min(joint.kRepulsive * (diff * diff),
c.maxRepulsiveTorque);
320 const float localStiffness = 2.0F * joint.kRepulsive * diff;
321 const float jointInertia =
static_cast<float>(rts.
inertia(i, i));
324 const float dampingGain =
325 2.0F * std::sqrt(jointInertia * localStiffness) *
c.dampingFactor;
327 joint.totalDamping = dampingGain * qvelFiltered[i];
389 const common::control_law::arondto::CollisionAvoidanceConfig&
c,
410 if (active.minDistance <
c.selfCollActivatorZ1)
415 else if (
c.selfCollActivatorZ1 <= active.minDistance &&
416 active.minDistance <=
c.selfCollActivatorZ2)
420 rtStatus.
selfCollK2 * std::pow(active.minDistance, 2) +
426 "desired null space value should not be higher than 1.0");
455 if (
c.onlyLimitCollDirection)
462 if ((active.projectedJacT(i) < 0.0f and
464 (active.projectedJacT(i) > 0.0f and
482 const Eigen::VectorXf& qpos)
const
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);
508 if (not joint.isLimitless)
511 if (qpos[i] < joint.qposZ1Low)
516 else if (joint.qposZ1Low <= qpos[i] && qpos[i] <= joint.qposZ2Low)
520 rts.
k2Lo * std::pow(qpos[i], 2) + rts.
k3Lo * qpos[i] +
525 "desired null space value should not be higher than 1.0, was %.2f, "
526 "approaching lower joint limit, weights: [%.2f, %.2f, %.2f, %.2f]",
532 .deactivateSpam(2.0f);
540 else if (joint.qposZ2High <= qpos[i] && qpos[i] <= joint.qposZ1High)
544 rts.
k2Hi * std::pow(qpos[i], 2) + rts.
k3Hi * qpos[i] +
549 "desired null space value should not be higher than 1.0, was %.2f, "
550 "approaching lower joint limit, weights: [%.2f, %.2f, %.2f, %.2f]",
556 .deactivateSpam(2.0f);
565 else if (joint.qposZ1High < qpos[i])
596 const Eigen::VectorXf& qpos,
597 const Eigen::VectorXf& qvelFiltered,
603 dynamicsModel.getInertiaMatrix(qpos.cast<
double>(), rtStatus.
inertia);
610 if (
c.enableSelfCollisionAvoidance)
613 const double timeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
618 collisionRobotIndices,
622 IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
624 if (
c.enableJointLimitAvoidance)
627 const double timeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
630 IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
634 if (
c.enableSelfCollisionAvoidance)
637 const double timeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
640 IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
642 if (
c.enableJointLimitAvoidance)
645 const double timeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
648 IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
654 if (
c.filterSafetyValues)
656 float coeff = rtStatus.
inRecoveryMode ? 0.8 *
c.safetyValFilter :
c.safetyValFilter;
736 else if (
c.enableSelfCollisionAvoidance and
c.enableJointLimitAvoidance)
740 if (
c.topPrioritySelfCollisionAvoidance)
766 else if (
c.topPriorityJointLimitAvoidance)
813 else if (
c.enableSelfCollisionAvoidance)
831 else if (
c.enableJointLimitAvoidance)
886 for (
size_t i = 0; i <
nDoFVel; ++i)
895 for (
size_t i = 0; i <
nDoFVel; ++i)
898 std::clamp(
qdVel(i), -jointVelLimit, jointVelLimit);
907 jointVel.setZero(
static_cast<int64_t
>(nDoFNodeSet));
920 const unsigned int nDoF,
921 const unsigned int maxCollisionPairs,
922 VirtualRobot::RobotNodeSetPtr& rns,
923 const std::vector<size_t>& velCtrlIndex)
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);
1013 CollisionAvoidanceController::RtStatusForSafetyStrategy::initJointLimtDataVec(
c, nDoF, rns);
1057 CollisionAvoidanceController::RtStatusForSafetyStrategy::initJointLimtDataVec(
1059 const unsigned int nDoF,
1060 VirtualRobot::RobotNodeSetPtr& rns)
1065 localStiffnessJointLim = 0.0;
1066 dampingJointLim = 0.0;
1077 jointLimitData.resize(nDoF);
1080 for (
size_t i = 0; i < nDoF; ++i)
1082 jointLimitData[i].jointName = rns->getNode(i)->getName();
1083 jointLimitData[i].isLimitless = rns->getNode(i)->isLimitless();
1085 if (not jointLimitData[i].isLimitless)
1087 jointLimitData[i].qLimLow = rns->getNode(i)->getJointLimitLow();
1088 jointLimitData[i].qLimHigh = rns->getNode(i)->getJointLimitHigh();
1093 for (
auto& joint : jointLimitData)
1095 if (not joint.isLimitless)
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 =
1112 joint.jointLimitNullSpaceWeightsHigh =
1188 if (cfg.topPrioritySelfCollisionAvoidance)
1192 (cfg.topPrioritySelfCollisionAvoidance == !cfg.topPriorityJointLimitAvoidance));
1194 if (cfg.topPriorityJointLimitAvoidance)
1198 (cfg.topPrioritySelfCollisionAvoidance == !cfg.topPriorityJointLimitAvoidance));
1207 if (not
c.enableCollisionRecoveryOnStartup or not rtStatus.
inRecoveryMode)
1222 std::min(
c.selfDistanceThreshold,
#define ARMARX_RT_LOGF_WARNING(...)
internal status of the controller, containing intermediate variables, mutable targets
Eigen::VectorXf objectCollisionTorqueFiltered
Eigen::MatrixXf selfCollTempNullSpaceMatrix
Eigen::MatrixXf jointLimNullSpace
AdmittanceInterface jointLimAdmInterface
std::vector< size_t > velCtrlIdx
admittance interface for velocity controlled joint
Eigen::VectorXf projCollJointTorque
double selfCollNullspaceTime
double collisionTorqueTime
Eigen::VectorXf projJointLimJointTorque
AdmittanceInterface objColAdmInterface
Eigen::VectorXf finalTorque
double jointLimitNullspaceTime
double jointLimitTorqueTime
AdmittanceInterface selfColAdmInterface
unsigned int objectCollDataIndex
Eigen::VectorXf torqueAcc
Eigen::VectorXf jointLimitJointTorque
Eigen::MatrixXf jointLimNullSpaceFiltered
Eigen::MatrixXf objectCollTempNullSpaceMatrix
Eigen::VectorXf jointLimitJointVel
Eigen::VectorXf impedanceJointTorque
intermediate torque results
float totalForceImpedance
Eigen::MatrixXf objectCollNullSpace
Eigen::MatrixXf selfCollNullSpace
intermediate null space matrices ((self-)collision and joint limit avoidance)
Eigen::MatrixXf objectCollNullSpaceFiltered
Eigen::VectorXf selfCollisionTorqueFiltered
Eigen::VectorXf projImpedanceJointTorque
intermediate projected torques via null space matrices
float objectCollK1
object collision avoidance null space intermediate results
Eigen::VectorXf objectCollNormalizedJacT
Eigen::Vector4f selfCollisionNullSpaceWeights
collision avoidance initialization parameters
unsigned int collisionPairsNum
collision pair info
float projTotalForceImpedance
Eigen::MatrixXf selfCollNullSpaceFiltered
Eigen::VectorXf desiredJointVel
double timeSinceStart
Adaptive threshold for collision recovery.
Eigen::VectorXf selfCollisionJointVel
for admittance interface
std::vector< JointRangeBufferZoneData > jointLimitData
joint limit avoidance initialization parameters
Eigen::VectorXf selfCollisionJointTorque
Eigen::VectorXf desiredJointTorques
targets
unsigned int activeCollPairsNum
Eigen::Vector3f dirErrorImp
double collisionPairTime
time status
Eigen::VectorXf selfCollNormalizedJacT
void rtPreActivate(const Config &c)
float selfCollK1
self collision avoidance null space intermediate results
std::vector< CollisionData > collDataVec
distance results
void reset(const Config &c, unsigned int nDoF, unsigned int maxCollisionPairs, VirtualRobot::RobotNodeSetPtr &rns, const std::vector< size_t > &velCtrlIndex)
Eigen::MatrixXd inertia
others
Eigen::VectorXf jointLimitTorqueFiltered
Eigen::MatrixXf inertiaInverse
Eigen::VectorXf objectCollisionJointTorque
Eigen::VectorXf objectCollisionJointVel
Eigen::MatrixXf nullSpaceAcc
for generating torques according to priority
Eigen::MatrixXf impedanceNullSpace
Eigen::VectorXf kdImpedanceTorque
Eigen::Vector6f projForceImpedance
void calculateJointLimitNullspace(const Config &c, RtStatusForSafetyStrategy &rtStatus, const Eigen::VectorXf &qpos) const
simox::control::dynamics::RBDLModel DynamicsModel
::simox::control::environment::DistanceResult DistanceResult
void calculateJointLimitTorque(const Config &c, RtStatusForSafetyStrategy &rtStatus, const Eigen::VectorXf &qpos, const Eigen::VectorXf &qvelFiltered) const
std::size_t numNodes() const
void calculateSelfCollisionNullspace(const Config &c, RtStatusForSafetyStrategy &rtStatus) const
caclulate null spaces
std::vector< DistanceResult > DistanceResults
CollisionAvoidanceController(const simox::control::robot::NodeSetInterface *nodeSet)
~CollisionAvoidanceController()
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.
void validateConfigData(const arondto::CollisionAvoidanceConfig &cfg)
Eigen::Vector4f calculateTransitionWeights(float z1, float z2)
helper functions
This file is part of ArmarX.
double norm(const Point &a)
void run(Eigen::VectorXf &jointTorque, float jointVelLimit, const TSCtrlRtStatus &rts)
void reset(size_t nDoFNodeSet, size_t nDoFVelocity)
Eigen::VectorXf projectedJacT
Eigen::Vector3f direction
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)
float collDistanceThreshold
float collDistanceThresholdInit
std::vector< size_t > jointIDVelocityMode
Eigen::VectorXf qvelFiltered
for velocity control
Eigen::MatrixXf inertiaInvVelCtrlJoints
#define ARMARX_TRACE_LITE