CollisionAvoidance.h
Go to the documentation of this file.
1/**
2 * This file is part of ArmarX.
3 *
4 * ArmarX is free software; you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License version 2 as
6 * published by the Free Software Foundation.
7 *
8 * ArmarX is distributed in the hope that it will be useful, but
9 * WITHOUT ANY WARRANTY; without even the implied warranty of
10 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 * GNU General Public License for more details.
12 *
13 * You should have received a copy of the GNU General Public License
14 * along with this program. If not, see <http://www.gnu.org/licenses/>.
15 *
16 * @author Jianfeng Gao ( jianfeng dot gao at kit dot edu )
17 * @date 2021
18 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
19 * GNU General Public License
20 */
21
22#pragma once
23
24#include <VirtualRobot/VirtualRobot.h>
25
26#include <simox/control/environment/DistanceResult.h>
27#include <simox/control/impl/simox/robot/Robot.h>
28#include <simox/control/robot/RobotInterface.h>
29
31
32#include <armarx/control/common/control_law/aron/CollisionAvoidanceConfig.aron.generated.h>
35#include <armarx/control/common/ft/aron/FTConfig.aron.generated.h>
36
38{
39 namespace collision
40 {
41 void validateConfigData(const arondto::CollisionAvoidanceConfig& cfg);
42 }
43
44 /*
45 * This class should be used for one kinematric chain / robot node set
46 */
48 {
49 public:
50 using SCRobot = simox::control::simox::robot::Robot;
51 using DistanceResult = ::simox::control::environment::DistanceResult;
52 using DistanceResults = std::vector<DistanceResult>;
53 using DynamicsModel = simox::control::dynamics::RBDLModel;
54 using FTConfig = common::ft::arondto::FTConfig;
55 using Config = common::control_law::arondto::CollisionAvoidanceConfig;
57 std::unordered_map<unsigned int, const simox::control::robot::NodeInterface*>;
58
60 {
61 /// the distances and projected jacobians from the generateSelfCollisionTorque() method
62 /// are needed for the null space calculation
63 unsigned int node1 = 0;
64 unsigned int node2 = 0;
65 Eigen::MatrixXd jacobian;
66 float minDistance = -1.0F;
67
68 // Debugging values
69 float repulsiveForce = -1.0F;
70 float localStiffness = -1.0F;
71 Eigen::VectorXf projectedJacT;
72 float distanceVelocity = -1.0F;
73 Eigen::Vector3f direction = Eigen::Vector3f::Zero();
74 Eigen::Vector3f point1 = Eigen::Vector3f::Zero();
75 Eigen::Vector3f point2 = Eigen::Vector3f::Zero();
76 float damping = -1.0F;
77 float projectedMass = -1.0F;
78 float desiredNSColl = -1.0F;
79
80 // mapped back from joint space with projectedJac pinv
82
83 CollisionData(unsigned int size) :
84 jacobian(Eigen::MatrixXd::Zero(3, size)), projectedJacT(Eigen::VectorXf::Zero(size))
85 {
86 }
87
88 inline void
90 {
91 node1 = 0;
92 node2 = 0;
93 jacobian.setZero();
94 projectedJacT.setZero();
95 direction.setZero();
96 point1.setZero();
97 point2.setZero();
98 minDistance = -1.0F;
99 repulsiveForce = -1.0F;
100 localStiffness = -1.0F;
101 distanceVelocity = -1.0F;
102 damping = -1.0F;
103 projectedMass = -1.0F;
104 desiredNSColl = -1.0F;
106 }
107 };
108
110 {
111 /// for each joint, that has a limit, based on the config parameters:
112 /// jointRangeBufferZone
113 /// jointRangeBufferZone_z1
114 /// jointRangeBufferZone_z2
115 ///
116 /// the specific values depending on the joint range of each joint have to
117 /// be calculated (and stored, so the calculation is only done in the init)
118 std::string jointName = "";
119 bool isLimitless = false;
120 float qLimLow = 0.0F;
121 float qLimHigh = 0.0F;
122 float thresholdRange = 0.0F;
123 float invThresholdSq = 0.0F;
124 float kRepulsive = 0.0F;
125 float qposThresholdLow = 0.0F; // unique for each joint in rep. torque function
126 float qposThresholdHigh = 0.0F;
127 /// null space parameters
128 float qposZ1Low = 0.0F;
129 float qposZ2Low = 0.0F;
130 float qposZ1High = 0.0F;
131 float qposZ2High = 0.0F;
132 Eigen::Vector4f jointLimitNullSpaceWeightsLow = Eigen::Vector4f::Zero();
133 Eigen::Vector4f jointLimitNullSpaceWeightsHigh = Eigen::Vector4f::Zero();
134 float desiredNSjointLim = 0.0F;
135 float repulsiveTorque = 0.0F;
136 float totalDamping = 0.0F;
137 };
138
140 {
141 Eigen::VectorXf qdVel;
142 Eigen::VectorXf qdAcc;
143 Eigen::VectorXf qTemp;
144 Eigen::VectorXf jointVel; // for the whole nodeset
145 bool active = false;
146 size_t nDoFVel = 0;
147
148 void run(Eigen::VectorXf& jointTorque, float jointVelLimit, const TSCtrlRtStatus& rts);
149 void reset(size_t nDoFNodeSet, size_t nDoFVelocity);
150 };
151
152 /// internal status of the controller, containing intermediate variables, mutable targets
154 {
155 public:
156 /// global pose
157 Eigen::Matrix4f globalPose = Eigen::Matrix4f::Identity();
158 /// targets
159 Eigen::VectorXf desiredJointTorques;
160 Eigen::VectorXf
161 desiredJointVel; // TODO, remove, directly change the rts of the TS controller
162
163 /// Adaptive threshold for collision recovery
164 double timeSinceStart = 0.0;
165 bool inRecoveryMode = false;
166
168
169 Eigen::Vector3f dirErrorImp;
173
174 /// intermediate torque results
175 Eigen::VectorXf impedanceJointTorque;
176 Eigen::VectorXf kdImpedanceTorque;
179 Eigen::VectorXf jointLimitJointTorque;
180
184
185 /// for admittance interface
186 Eigen::VectorXf selfCollisionJointVel;
187 Eigen::VectorXf objectCollisionJointVel;
188 Eigen::VectorXf jointLimitJointVel;
189
190 /// intermediate projected torques via null space matrices
192 Eigen::VectorXf projCollJointTorque;
193 Eigen::VectorXf projJointLimJointTorque;
194
197
198 /// intermediate null space matrices ((self-)collision and joint limit avoidance)
199 Eigen::MatrixXf selfCollNullSpace;
200 Eigen::MatrixXf objectCollNullSpace;
201 Eigen::MatrixXf jointLimNullSpace;
202 Eigen::MatrixXf impedanceNullSpace;
204
208
209 /// collision avoidance initialization parameters
212
213 /// distance results
214 std::vector<CollisionData> collDataVec;
215 unsigned int
216 objectCollDataIndex; // from this index, the object collision avoidance data starts
217
218 /// self collision avoidance null space intermediate results
220 Eigen::VectorXf selfCollNormalizedJacT;
222
223 /// object collision avoidance null space intermediate results
227
228 /// joint limit avoidance initialization parameters
229
230 // TODO rename to jointLimitDataVec
231 std::vector<JointRangeBufferZoneData> jointLimitData;
232
233 /// joint limit avoidance intermediate results
234 float jointVel;
236
239
240 float k1Lo, k2Lo, k3Lo, k4Lo;
241 float k1Hi, k2Hi, k3Hi, k4Hi;
242
243 /// others
244 Eigen::MatrixXd inertia;
245 Eigen::MatrixXf inertiaInverse;
246
247 /// time status
255
256 /// collision pair info
257 unsigned int collisionPairsNum;
258 unsigned int activeCollPairsNum;
259
260 /// for generating torques according to priority
261 Eigen::MatrixXf nullSpaceAcc;
262 Eigen::VectorXf torqueAcc;
263 Eigen::VectorXf finalTorque;
264
265 /// admittance interface for velocity controlled joint
266 std::vector<size_t> velCtrlIdx;
270
271 void reset(const Config& c,
272 unsigned int nDoF,
273 unsigned int maxCollisionPairs,
274 VirtualRobot::RobotNodeSetPtr& rns,
275 const std::vector<size_t>& velCtrlIndex);
276 void rtPreActivate(const Config& c);
277
278 private:
279 void initJointLimtDataVec(const Config& c,
280 unsigned int nDoF,
281 VirtualRobot::RobotNodeSetPtr& rns);
282 };
283
285 {
288 void update(const Config& c, RtStatusForSafetyStrategy& rtStatus, double deltaT);
289 void reset();
290 };
291
292 CollisionAvoidanceController(const simox::control::robot::NodeSetInterface* nodeSet);
293
295
296 void run(const Config& c,
297 RtStatusForSafetyStrategy& robotStatus,
298 RecoveryState& rStateSelfColl,
299 const DistanceResults& collisionPairs,
300 const CollisionRobotIndices& collisionRobotIndices,
301 DynamicsModel& dynamicsModel,
302 const Eigen::VectorXf& qpos,
303 const Eigen::VectorXf& qvelFiltered,
304 float torqueLimit,
305 double deltaT);
306
307 inline std::size_t
308 numNodes() const
309 {
310 return nodeSet_->getSize();
311 }
312
313 inline const simox::control::robot::NodeSetInterface&
315 {
316 return *nodeSet_;
317 }
318
319 private:
320 const simox::control::robot::NodeSetInterface* nodeSet_;
321 const Eigen::MatrixXf identityMat;
322
323 protected:
324 const Eigen::MatrixXf&
326 {
327 return identityMat;
328 }
329
330 /// avoidance torque methods
332 RtStatusForSafetyStrategy& rtStatus,
333 RecoveryState& rState,
334 const DistanceResults& collisionPairs,
335 const CollisionRobotIndices& collisionRobotIndices,
336 const Eigen::VectorXf& qvelFiltered,
337 double deltaT) const;
338
340 RtStatusForSafetyStrategy& rtStatus,
341 const Eigen::VectorXf& qpos,
342 const Eigen::VectorXf& qvelFiltered) const;
343
344 void calculateCollisionTorque(CollisionData& collDataVec,
345 const Config& c,
346 RtStatusForSafetyStrategy& rts,
347 const CollisionRobotIndices& collisionRobotIndices,
348 const Eigen::VectorXf& qvelFiltered,
349 Eigen::VectorXf& jointTorque,
350 float distanceThresholdRaw,
351 float distanceThreshold) const;
352
353 /// caclulate null spaces
355 RtStatusForSafetyStrategy& rtStatus) const;
357 RtStatusForSafetyStrategy& rtStatus,
358 const Eigen::VectorXf& qpos) const;
359 };
360} // namespace armarx::control::common::control_law
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 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
const simox::control::robot::NodeSetInterface & getNodeSet() const
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 ---------------------------------------—
Matrix< float, 6, 1 > Vector6f
void validateConfigData(const arondto::CollisionAvoidanceConfig &cfg)
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...
std::string jointName
for each joint, that has a limit, based on the config parameters: jointRangeBufferZone jointRangeBuff...
void update(const Config &c, RtStatusForSafetyStrategy &rtStatus, double deltaT)