ObjectCollisionAvoidanceCore.cpp
Go to the documentation of this file.
2
3#include <VirtualRobot/Nodes/RobotNode.h>
4#include <VirtualRobot/RobotNodeSet.h>
5
6#include <simox/control/environment/CollisionRobot.h>
7#include <simox/control/impl/simox/robot/Robot.h>
8
11
13
16
18{
19
21 const VirtualRobot::RobotPtr& rtRobot,
22 const Config& cfg,
23 const std::map<std::string, std::vector<size_t>>& velCtrlIndices) :
24 rtRobot(rtRobot)
25 {
27
28 rtCfg = cfg;
30 userCfg = rtCfg;
31 bufferCfgUserToRT.reinitAllBuffers(rtCfg);
32 velCtrlIdx = velCtrlIndices;
33
34 // Collect tcp node names
35 std::vector<std::string> tcpNodeNames;
36 for (const auto& pair : rtCfg.ctrlCfg)
37 {
38 const auto nodeset = rtRobot->getRobotNodeSet(pair.first);
39 const std::string tcpName = nodeset->getTCP()->getName();
40 tcpNodeNames.push_back(tcpName);
41 if (pair.second.selfDistanceThreshold > preFilterDistance)
42 {
43 preFilterDistance = pair.second.selfDistanceThreshold;
44 }
45 if (pair.second.objectDistanceThreshold > preFilterDistance)
46 {
47 preFilterDistance = pair.second.objectDistanceThreshold;
48 }
49 }
50
51 /// add actuated robot joints
52 /// use a robot nodeset with all actuated joints, arms including head and torso joints, which change
53 /// the position of the robot body parts for correct collision checking
54 ARMARX_CHECK(rtRobot->hasRobotNodeSet(cfg.actuatedRobotNodeSetName));
55 rtRobotNodeSet = rtRobot->getRobotNodeSet(cfg.actuatedRobotNodeSetName);
56 actuatedJointNames = rtRobotNodeSet->getNodeNames();
57
58 /// initialize simox control robot for self-collision checking
59 scRobot = std::make_unique<simox::control::simox::robot::Robot>(
60 rtRobot, actuatedJointNames, tcpNodeNames, reduceModel);
61 scRobot->setGlobalPose(Eigen::Isometry3d::Identity());
62
63 ARMARX_CHECK(scRobot->getRobot()->hasRobotNodeSet(cfg.actuatedRobotNodeSetName));
64 scRobotNodeSet = scRobot->getRobot()->getRobotNodeSet(cfg.actuatedRobotNodeSetName);
65
66 ARMARX_DEBUG << "Creating robot model for collision computation using default primitive "
67 "models and models with id "
68 << rtCfg.primitiveModelParts;
69
71 std::make_unique<simox::control::environment::CollisionRobot<hpp::fcl::OBBRSS>>(
72 *scRobot,
73 simox::control::environment::CollisionRobotParams{.loadDefaultPrimitiveModel = true,
74 .primitiveModelIDs =
75 rtCfg.primitiveModelParts,
76 .sortNodes = true});
77
78 // initialize vector to store the current joint values of all actuated joints to update
79 // the simox robots with the most recent values, so the simox control robots display the
80 // current joint configuration of the real world model
82 qposActuatedJoints.setZero();
83
84 size_t jointIdx = 0;
85 for (const auto& nodeName : actuatedJointNames)
86 {
87 const auto node = rtRobot->getRobotNode(nodeName);
88 if (node->isTranslationalJoint())
89 {
90 // convert value from mm to m for simox control robot
91 // all translational values of the simox control robots are in meter
92 translationJointIndex.push_back(jointIdx);
93 }
94 jointIdx++;
95 }
96
97 for (const auto& pair : rtCfg.ctrlCfg)
98 {
99 collLimb.try_emplace(pair.first,
100 rtRobot,
101 pair.first,
102 *scRobot,
104 rtCfg,
105 velCtrlIdx.at(pair.first));
106 }
107
108 // Store all indices
109 ARMARX_DEBUG << "Creating index to node mapping for collision robot:";
110 std::unordered_set<unsigned int> consideredIndices;
111 for (auto& [name, data] : collLimb)
112 {
113 collisionRobot->getIndices(data.controller.getNodeSet(), data.collisionRobotIndices);
114 for (const auto& [index, node] : data.collisionRobotIndices)
115 {
116 ARMARX_DEBUG << "Mapping index " << index << " to node " << node->getName()
117 << " for limb " << name;
118 consideredIndices.insert(index);
119 }
120 }
121
122 ARMARX_DEBUG << "Initial computation of all self collision pairs";
123
124 selfColAvoidanceArgs =
125 simox::control::environment::CompDistArgs{.updatePose = false,
126 .nearestPoints = true,
127 .individualColObjects = true,
128 .allowIndices = consideredIndices};
129
130 // Compute number of collision pairs
131 // This will not change if no objects are attached and the args are not changed
132 collisionRobot->update(false); // update pose
133 const DistanceResults distanceResults =
134 collisionRobot->computeMinimumSelfCollisionDistance(selfColAvoidanceArgs);
135 const int nElements = distanceResults.size();
136
137 for (const auto& distanceResult : distanceResults)
138 {
139 ARMARX_DEBUG << "Considering distance between "
140 << collisionRobot->getNodes().at(distanceResult.node1).getName() << " and "
141 << collisionRobot->getNodes().at(distanceResult.node2).getName()
142 << ". Initial distance: " << distanceResult.minDistance << "m";
143 }
144
145 ARMARX_DEBUG << "Reserving space for " << nElements << " collision pairs";
146 ARMARX_CHECK_EXPRESSION(nElements < rtCfg.maxCollisionPairs);
147 collisionPairs.reserve(nElements);
148 }
149
151 {
152 ARMARX_IMPORTANT << "destruction of ObjectCollisionAvoidanceBase";
153 }
154
156 const VirtualRobot::RobotPtr& rtRobot,
157 const std::string& robotNodeSetName,
158 const SCRobot& scRobot,
160 const Config& c,
161 const std::vector<size_t>& velCtrlIndex) :
162 nodeSetName(robotNodeSetName),
163 rtRNS(rtRobot->getRobotNodeSet(robotNodeSetName)),
164 controller(scRobot.getSubNodeSet(robotNodeSetName)),
166 {
168 ARMARX_CHECK_GREATER(c.maxCollisionPairs, 0);
169
170 reset(c, velCtrlIndex);
171
172 dynamicsModel = scRobot.createDynamicsModel(robotNodeSetName);
173
174 bufferRTtoPublish.reinitAllBuffers(rts);
176 }
177
178 void
180 const std::vector<size_t>& velCtrlIndex)
181 {
182 rts.reset(c.ctrlCfg.at(rtRNS->getName()),
183 controller.numNodes(),
184 c.maxCollisionPairs,
185 rtRNS,
186 velCtrlIndex);
187 rts.objectCollisionNullSpaceWeights =
189 c.ctrlCfg.at(rtRNS->getName()).objectCollActivatorZ1,
190 c.ctrlCfg.at(rtRNS->getName()).objectCollActivatorZ2);
191 recoveryStateObjColl.reset();
192 recoveryStateSelfColl.reset();
193 }
194
195 void
197 {
198 for (auto& pair : collLimb)
199 {
200 pair.second.rts.rtPreActivate(userCfg.ctrlCfg.at(pair.first));
201 pair.second.recoveryStateObjColl.reset();
202 pair.second.recoveryStateSelfColl.reset();
203 }
204 }
205
206 void
208 {
209 for (auto& pair : collLimb)
210 {
211 pair.second.reset(rtCfg, velCtrlIdx.at(pair.first));
212 }
213 }
214
215 void
217 {
218 /// Running in rt thread.
219 rtCfg = bufferCfgUserToRT.getUpToDateReadBuffer();
221 }
222
223 void
225 {
226 // /// ----------------- update joint values for simox Robots ---------------------------------
227 // qposActuatedJoints = rtRobot->getRobotNodeSet(rtCfg.actuatedRobotNodeSetName)
228 // ->getJointValuesEigen()
229 // .cast<double>();
230 //
231 // // convert value from mm to m for simox control robot
232 // // all translational values of the simox control robots are in meter
233 // for (unsigned int i : translationJointIndex)
234 // {
235 // qposActuatedJoints(i) *= 0.001;
236 // }
237 //
238 // /// ----------------- update Simox robots --------------------------------------------------
239 // ///
240 // /// a VectorXd is needed with nodeSet size (size of actuated joints in order of vector,
241 // /// which has been used for initialization in init
242 // ///
243 // /// It is very important that the simox robots map the current joint configuration of the
244 // /// real-world robot
245 // scRobot->setConfig(qposActuatedJoints);
246
247 // Directly set Simox robot inside and then update the joints of simox control robot
248 scRobotNodeSet->setJointValues(rtRobotNodeSet->getJointValuesEigen());
249 scRobot->update();
250 globalPose = rtRobot->getGlobalPose().matrix().cast<double>();
251 globalPose.block<3, 1>(0, 3) /= 1000.0;
252 scRobot->setGlobalPose(simox::control::Pose(globalPose), true);
253
254 /// ----------------- calculation of robot collision pairs ---------------------------------
255 const auto time = IceUtil::Time::now();
256 // TODO update is also called in computeMinimumSelfCollisionDistance if updatePose = true in selfColAvoidanceArgs
257 collisionRobot->update(false); // update pose
258 collisionRobot->computeMinimumSelfCollisionDistance(collisionPairs, selfColAvoidanceArgs);
259 const double collisionPairTime = (IceUtil::Time::now() - time).toMicroSecondsDouble();
260
261 for (auto& pair : collLimb)
262 {
263 pair.second.rts.collisionPairTime = collisionPairTime;
264 pair.second.rts.collisionPairsNum = collisionPairs.size();
265 }
266
267 /// ----------------- calculation of collision pairs between the robot and the environment -----------------
268 collisionRobot->computeMinimumDistance(
269 rtCollisionObjects, externalCollisionPairs, compDistArgs);
270 }
271
272 void
273 ObjectCollisionAvoidanceBase::rtLimbControllerRun(const std::string& robotNodeSetName,
274 float torqueLimit,
275 float jointVelLimit,
276 law::TSCtrlRtStatus& rts)
277 {
278 auto& arm = collLimb.at(robotNodeSetName);
279
280 // arm.rts.impedanceJointTorque = rts.desiredJointTorque;
281 arm.controller.run(rtCfg.ctrlCfg.at(robotNodeSetName),
282 arm.rts,
283 arm.recoveryStateSelfColl,
284 arm.recoveryStateObjColl,
285 arm.collisionPairs,
287 arm.collisionRobotIndices,
288 *arm.dynamicsModel,
289 torqueLimit,
290 jointVelLimit,
291 rts);
292 arm.bufferRTtoPublish.getWriteBuffer() = arm.rts;
293 arm.bufferRTtoPublish.commitWrite();
294
295 arm.bufferRecoveryStateSelfColl.getWriteBuffer() = arm.recoveryStateSelfColl;
296 arm.bufferRecoveryStateSelfColl.commitWrite();
297 }
298
299 void
301 {
302 ARMARX_CHECK_NONNEGATIVE(cfg.maxCollisionPairs);
303 ARMARX_CHECK_NOT_EMPTY(cfg.primitiveModelParts);
304 ARMARX_CHECK_NOT_EMPTY(cfg.actuatedRobotNodeSetName);
305 for (auto& pair : cfg.ctrlCfg)
306 {
308 }
309 }
310
311 void
313 {
314 userCfg = cfg;
316 bufferCfgUserToRT.getWriteBuffer() = userCfg;
317 bufferCfgUserToRT.commitWrite();
318 }
319
320 void
322 {
323 /// Running in rt thread.
324 std::tie(externalCollisionPairs, rtCollisionObjects) =
325 bufferCollisionObjectsUserToRt.getUpToDateReadBuffer();
326 }
327
328 void
330 {
331 userCollisionObjects.clear();
332 auto& writeBuffer = bufferCollisionObjectsUserToRt.getWriteBuffer();
333 std::get<0>(writeBuffer).reserve(0);
334 std::get<1>(writeBuffer) = userCollisionObjects;
335 bufferCollisionObjectsUserToRt.commitWrite();
336 }
337
338 void
340 const std::vector<hpp::fcl::CollisionObject>& collisionObjects)
341 {
342 const unsigned int nElements =
343 collisionRobot->computeNElements(compDistArgs, collisionObjects);
344 ARMARX_INFO << "There are " << collisionObjects.size() << " collision objects";
345 ARMARX_INFO << "Reserving space for " << nElements << " collision pairs";
346
347 userCollisionObjects = collisionObjects;
348 auto& writeBuffer = bufferCollisionObjectsUserToRt.getWriteBuffer();
349 std::get<0>(writeBuffer).reserve(nElements);
350 std::get<1>(writeBuffer) = collisionObjects;
351 bufferCollisionObjectsUserToRt.commitWrite();
352 }
353
354
355} // namespace armarx::control::njoint_controller::core
uint8_t index
#define ARMARX_CHECK_NOT_EMPTY(c)
constexpr T c
ObjectCollisionAvoidanceBase(const VirtualRobot::RobotPtr &rtRobot, const Config &cfg, const std::map< std::string, std::vector< size_t > > &velCtrlIndices)
void updateUserCollisionObjects(const std::vector< hpp::fcl::CollisionObject > &)
armarx::TripleBuffer< std::tuple< DistanceResults, std::vector< hpp::fcl::CollisionObject > > > bufferCollisionObjectsUserToRt
void rtLimbControllerRun(const std::string &robotNodeSetName, float torqueLimit, float jointVelLimit, common::control_law::TSCtrlRtStatus &rts)
#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_NONNEGATIVE(number)
Check whether number is nonnegative (>= 0).
#define ARMARX_INFO
The normal logging level.
Definition Logging.h:181
#define ARMARX_IMPORTANT
The logging level for always important information, but expected behaviour (in contrast to ARMARX_WAR...
Definition Logging.h:190
#define ARMARX_DEBUG
The logging level for output that is only interesting while debugging.
Definition Logging.h:184
std::shared_ptr< class Robot > RobotPtr
Definition Bus.h:19
void validateConfigData(const arondto::CollisionAvoidanceConfig &cfg)
Eigen::Vector4f calculateTransitionWeights(float z1, float z2)
helper functions
Definition utils.cpp:25
VirtualRobot::RobotNodeSetPtr rtRNS
!!!!!!! Note that, all the data below should only be accessed in rt thread !!!!!!!
NodeSetData(const VirtualRobot::RobotPtr &rtRobot, const std::string &robotNodeSetName, const SCRobot &scRobot, const DistanceResults &collisionPairs, const Config &c, const std::vector< size_t > &velCtrlIndex)