CollisionCheckerComponent.cpp
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  * @package RobotComponents::ArmarXObjects::CollisionCheckerComponent
17  * @author Adrian Knobloch ( adrian dot knobloch at student dot kit dot edu )
18  * @date 2016
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
24 
25 #include <stdlib.h>
26 
27 #include <cmath>
28 #include <iterator>
29 #include <sstream>
30 
31 #include <boost/regex.hpp>
32 
33 #include <SimoxUtility/algorithm/string/string_tools.h>
34 #include <VirtualRobot/CollisionDetection/CollisionChecker.h>
35 #include <VirtualRobot/RobotNodeSet.h>
36 #include <VirtualRobot/SceneObjectSet.h>
37 
40 
42 
49 
50 using namespace armarx;
51 
53 {
54 }
55 
56 void
58 {
59  interval = getProperty<int>("interval").getValue();
60 
61  useWorkingMemory = getProperty<bool>("UseWorkingMemory").getValue();
62  if (useWorkingMemory)
63  {
64  workingMemoryName = getProperty<std::string>("WorkingMemoryName").getValue();
65  ARMARX_INFO << "Using WorkingMemory \"" << workingMemoryName << "\" to get SceneObjects."
66  << std::endl;
67  usingProxy(workingMemoryName);
68  usingTopic(getProperty<std::string>("WorkingMemoryListenerTopicName").getValue());
69  }
70  else
71  {
72  robotStateComponentName = getProperty<std::string>("RobotStateComponentName").getValue();
73  ARMARX_INFO << "Using RobotStateComponent \"" << robotStateComponentName
74  << "\" to get SceneObjects." << std::endl;
75  usingProxy(robotStateComponentName);
76  }
77 
78  std::string collisionPairsString = getProperty<std::string>("CollisionPairs").getValue();
79  boost::regex regexCollisionPair(
80  "[\\[\\{\\(](([^:,\\[\\{\\(\\]\\}\\)]+:)?([^,\\[\\{\\(\\]\\}\\)]+,|[\\[\\{\\(]([^,\\[\\{\\("
81  "\\]\\}\\)]+,)*[^,\\[\\{\\(\\]\\}\\)]+[\\]\\}\\)],)){2}[0-9]*[.]?[0-9]*[\\]\\}\\)]");
82 
83  boost::sregex_token_iterator iterCollisionPair(
84  collisionPairsString.begin(), collisionPairsString.end(), regexCollisionPair, 0);
85  boost::sregex_token_iterator end;
86 
87  for (; iterCollisionPair != end; ++iterCollisionPair)
88  {
89  std::string collisionPairString = *iterCollisionPair;
90  while ((collisionPairString[0] == '{' &&
91  collisionPairString[collisionPairString.size() - 1] == '}') ||
92  (collisionPairString[0] == '(' &&
93  collisionPairString[collisionPairString.size() - 1] == ')') ||
94  (collisionPairString[0] == '[' &&
95  collisionPairString[collisionPairString.size() - 1] == ']'))
96  {
97  collisionPairString = collisionPairString.substr(1, collisionPairString.size() - 2);
98  }
99 
100  if ((collisionPairString[0] == '{' || collisionPairString[0] == '(' ||
101  collisionPairString[0] == '[') &&
102  (collisionPairString[collisionPairString.size() - 1] == '}' ||
103  collisionPairString[collisionPairString.size() - 1] == ')' ||
104  collisionPairString[collisionPairString.size() - 1] == ']'))
105  {
106  ARMARX_ERROR << "Could not parse collision pair: " << *iterCollisionPair
107  << ". Ignoring..." << std::endl;
108  continue;
109  }
110 
111  boost::regex regex("([^:,\\[\\{\\(\\]\\}\\)]+:)?([\\{\\[\\(][^\\{\\[\\(\\]\\}\\)]+[\\]\\}"
112  "\\)]|[^\\{\\[\\(\\]\\}\\),]+)");
113 
114  boost::sregex_token_iterator iter(
115  collisionPairString.begin(), collisionPairString.end(), regex, 0);
116  boost::sregex_token_iterator end;
117 
118  ARMARX_CHECK_EXPRESSION(iter != end);
119 
120  std::string robotName1;
121  std::vector<std::string> nodeNames1;
122  bool usesNodeSet1;
123  std::string nodeSetName1;
124  parseNodeSet(*iter, robotName1, nodeNames1, usesNodeSet1, nodeSetName1);
125 
126  ++iter;
127  ARMARX_CHECK_EXPRESSION(iter != end);
128 
129  std::string robotName2;
130  std::vector<std::string> nodeNames2;
131  bool usesNodeSet2;
132  std::string nodeSetName2;
133  parseNodeSet(*iter, robotName2, nodeNames2, usesNodeSet2, nodeSetName2);
134 
135  ++iter;
136  ARMARX_CHECK_EXPRESSION(iter != end);
137 
138  addCollisionPair(robotName1,
139  nodeNames1,
140  usesNodeSet1,
141  nodeSetName1,
142  robotName2,
143  nodeNames2,
144  usesNodeSet2,
145  nodeSetName2,
146  std::atof(((std::string)*iter).c_str()));
147 
148  ARMARX_CHECK_EXPRESSION(++iter == end);
149  }
150 
151  collisionChecker = VirtualRobot::CollisionChecker::getGlobalCollisionChecker();
152 
153  offeringTopic(getProperty<std::string>("CollisionListenerTopicName").getValue());
154  offeringTopic(getProperty<std::string>("DistanceListenerTopicName").getValue());
155 
156  useDebugDrawer = getProperty<bool>("UseDebugDrawer").getValue();
157 }
158 
159 void
161 {
162  {
163  std::scoped_lock lockData(dataMutex);
164 
165  robots.clear();
166 
167  if (useWorkingMemory)
168  {
169  workingMemoryPrx = getProxy<memoryx::WorkingMemoryInterfacePrx>(workingMemoryName);
170  objectInstancesPrx = workingMemoryPrx->getObjectInstancesSegment();
171  agentInstancesPrx = workingMemoryPrx->getAgentInstancesSegment();
172  fileManager.reset(new memoryx::GridFileManager(workingMemoryPrx->getCommonStorage()));
173  for (memoryx::AgentInstanceBasePtr& agent : agentInstancesPrx->getAllAgentInstances())
174  {
175  RobotStateComponentInterfacePrx robotStateComponentPrx =
176  agent->getSharedRobot()->getRobotStateComponent();
177  VirtualRobot::RobotPtr robot =
178  armarx::RemoteRobot::createLocalCloneFromFile(robotStateComponentPrx);
179 
180  robots.push_back({robot, robotStateComponentPrx});
181  }
182  }
183  else
184  {
185  RobotStateComponentInterfacePrx robotStateComponentPrx =
186  getProxy<RobotStateComponentInterfacePrx>(robotStateComponentName);
187 
188  VirtualRobot::RobotPtr robot =
189  armarx::RemoteRobot::createLocalCloneFromFile(robotStateComponentPrx);
190 
191  RobotPair r = {robot, robotStateComponentPrx};
192  robots.push_back(r);
193  }
194 
195  {
196  std::unique_lock lock(connectedMutex);
197  connected = true;
198  }
199 
200 
201  for (SceneObjectPair& pair : sceneObjectPairs)
202  {
203  if (!resolveCollisionPair(pair))
204  {
205  std::ostringstream nodeNames1Str;
206  std::copy(pair.nodeNames1.begin(),
207  pair.nodeNames1.end() - 1,
208  std::ostream_iterator<std::string>(nodeNames1Str, ","));
209  nodeNames1Str << pair.nodeNames1.back();
210 
211  std::ostringstream nodeNames2Str;
212  std::copy(pair.nodeNames2.begin(),
213  pair.nodeNames2.end() - 1,
214  std::ostream_iterator<std::string>(nodeNames2Str, ","));
215  nodeNames2Str << pair.nodeNames2.back();
216  ARMARX_WARNING << "Could not resolve collision pair: {" << pair.robotName1
217  << (pair.robotName1 == "" ? "" : ":") << "(" << nodeNames1Str.str()
218  << ")," << pair.robotName2 << (pair.robotName2 == "" ? "" : ":")
219  << "(" << nodeNames2Str.str() << ")," << pair.warningDistance << "}"
220  << std::endl;
221  }
222  }
223  }
224 
225  collisionListenerPrx = getTopic<CollisionListenerPrx>(
226  getProperty<std::string>("CollisionListenerTopicName").getValue());
227  distanceListenerPrx = getTopic<DistanceListenerPrx>(
228  getProperty<std::string>("DistanceListenerTopicName").getValue());
229 
230  if (!reportTask)
231  {
233  this,
234  &CollisionCheckerComponent::reportDistancesAndCollisions,
235  interval,
236  false,
237  "ReportCollisionsTask");
238  }
239 
240  reportTask->start();
241 
242  if (useDebugDrawer)
243  {
244  debugDrawerTopicPrx = getTopic<DebugDrawerInterfacePrx>(
245  getProperty<std::string>("DebugDrawerTopicName").getValue());
246 
247  if (!debugDrawerTopicPrx)
248  {
249  ARMARX_ERROR << "Failed to obtain debug drawer proxy." << std::endl;
250  useDebugDrawer = false;
251  }
252  }
253 }
254 
255 void
257 {
258  {
259  std::unique_lock lock(connectedMutex);
260  connected = false;
261  }
262  reportTask->stop();
263 
264  std::scoped_lock lockData(dataMutex);
265  for (SceneObjectPair& pair : sceneObjectPairs)
266  {
267  pair.objects1 = VirtualRobot::SceneObjectSetPtr();
268  pair.objects2 = VirtualRobot::SceneObjectSetPtr();
269  }
270  robots.clear();
271 
272  if (useDebugDrawer && debugDrawerTopicPrx)
273  {
274  debugDrawerTopicPrx->clearLayer("distanceVisu");
275  debugDrawerTopicPrx->removeLayer("distanceVisu");
276  }
277 }
278 
279 void
281 {
282 }
283 
286 {
289 }
290 
291 bool
292 armarx::CollisionCheckerComponent::resolveCollisionPair(SceneObjectPair& pair)
293 {
294  std::shared_lock lockConnected(connectedMutex);
295  if (!connected)
296  {
297  return false;
298  }
299 
300  if (pair.usesNodeSet1 && pair.nodeSetName1 != "")
301  {
302  pair.nodeNames1.clear();
303  if (pair.robotName1 != "")
304  {
305  for (RobotPair& robotPair : robots)
306  {
307  if (robotPair.robot->getName() == pair.robotName1)
308  {
309  VirtualRobot::SceneObjectSetPtr set =
310  robotPair.robot->getRobotNodeSet(pair.nodeSetName1);
311  if (set)
312  {
313  for (VirtualRobot::SceneObjectPtr so : set->getSceneObjects())
314  {
315  pair.nodeNames1.push_back(so->getName());
316  }
317  }
318  else
319  {
320  ARMARX_WARNING << "Robot \"" << pair.robotName1
321  << "\" has no set with name \"" << pair.nodeSetName1 << "\""
322  << std::endl;
323  }
324  break;
325  }
326  }
327  }
328  else
329  {
330  ARMARX_WARNING << "No robot name given for RobotNodeSet \"" << pair.nodeSetName1 << "\""
331  << std::endl;
332  }
333  }
334 
335  VirtualRobot::SceneObjectSetPtr objects1(new VirtualRobot::SceneObjectSet());
336  for (std::string& nodeName : pair.nodeNames1)
337  {
338  VirtualRobot::SceneObjectPtr sc = getSceneObject(pair.robotName1, nodeName);
339  if (!sc)
340  {
341  ARMARX_DEBUG << "failed to get object: \"" << pair.robotName1 << "\" : \"" << nodeName
342  << "\"" << std::endl;
343  return false;
344  }
345  if (!sc->getCollisionModel())
346  {
347  ARMARX_WARNING << pair.robotName1 << (pair.robotName1 == "" ? "" : ".") << nodeName
348  << " does not have a collision model. Ignoring..." << std::endl;
349  continue;
350  }
351  objects1->addSceneObject(sc);
352  }
353 
354  if (pair.usesNodeSet2 && pair.nodeSetName2 != "")
355  {
356  pair.nodeNames2.clear();
357  if (pair.robotName2 != "")
358  {
359  for (RobotPair& robotPair : robots)
360  {
361  if (robotPair.robot->getName() == pair.robotName2)
362  {
363  VirtualRobot::SceneObjectSetPtr set =
364  robotPair.robot->getRobotNodeSet(pair.nodeSetName2);
365  if (set)
366  {
367  for (VirtualRobot::SceneObjectPtr so : set->getSceneObjects())
368  {
369  pair.nodeNames2.push_back(so->getName());
370  }
371  }
372  else
373  {
374  ARMARX_WARNING << "Robot \"" << pair.robotName2
375  << "\" has no set with name \"" << pair.nodeSetName2 << "\""
376  << std::endl;
377  }
378  break;
379  }
380  }
381  }
382  else
383  {
384  ARMARX_WARNING << "No robot name given for RobotNodeSet \"" << pair.nodeSetName2 << "\""
385  << std::endl;
386  }
387  }
388 
389  VirtualRobot::SceneObjectSetPtr objects2(new VirtualRobot::SceneObjectSet());
390  for (std::string& nodeName : pair.nodeNames2)
391  {
392  VirtualRobot::SceneObjectPtr sc = getSceneObject(pair.robotName2, nodeName);
393  if (!sc)
394  {
395  ARMARX_DEBUG << "failed to get object: \"" << pair.robotName2 << "\" : \"" << nodeName
396  << "\"" << std::endl;
397  return false;
398  }
399  if (!sc->getCollisionModel())
400  {
401  ARMARX_WARNING << pair.robotName2 << (pair.robotName2 == "" ? "" : ".") << nodeName
402  << " does not have a collision model. Ignoring..." << std::endl;
403  continue;
404  }
405  objects2->addSceneObject(sc);
406  }
407 
408  if (!objects1 || !objects2 || objects1->getSize() == 0 || objects2->getSize() == 0)
409  {
410  return false;
411  }
412 
413  pair.objects1 = objects1;
414  pair.objects2 = objects2;
415  return true;
416 }
417 
419 armarx::CollisionCheckerComponent::getSceneObject(const std::string& robotName,
420  const std::string& nodeName)
421 {
422  if (robotName.size() == 0 && useWorkingMemory)
423  {
424  ARMARX_DEBUG << "Get object from WorkingMemory: " << nodeName << std::endl;
425  return getSceneObjectFromWorkingMemory(nodeName);
426  }
427  else if (robotName.size() == 0) //&& !useWorkingMemory
428  {
429  //get RobotNode from first robot (should be only one)
430  ARMARX_DEBUG << "Get object from first robot: " << nodeName << std::endl;
431  return robots[0].robot->getRobotNode(nodeName);
432  }
433  else
434  {
435  ARMARX_DEBUG << "Searching for matching robot: " << robotName << std::endl;
436  for (RobotPair& r : robots)
437  {
438  if (r.robot->getName() == robotName)
439  {
440  ARMARX_DEBUG << "Get object from robot: " << nodeName << std::endl;
441  return r.robot->getRobotNode(nodeName);
442  }
443  else
444  {
445  ARMARX_DEBUG << r.robot->getName() << " != " << robotName << std::endl;
446  }
447  }
448  }
449 
451 }
452 
453 bool
454 armarx::CollisionCheckerComponent::parseNodeSet(const std::string& setAsString,
455  std::string& robotName,
456  std::vector<std::string>& nodeNames,
457  bool& usesNodeSet,
458  std::string& nodeSetName)
459 {
460  std::vector<std::string> split = simox::alg::split(setAsString, ":");
461 
462  std::string nodeNamesString;
463  switch (split.size())
464  {
465  case 1:
466  robotName = "";
467  nodeNamesString = split[0];
468  break;
469  case 2:
470  robotName = split[0];
471  nodeNamesString = split[1];
472  break;
473  default:
474  return false;
475  }
476 
477  if (nodeNamesString[0] != '{' && nodeNamesString[0] != '(' && nodeNamesString[0] != '[')
478  {
479  usesNodeSet = true;
480  nodeSetName = nodeNamesString;
481  nodeNames.clear();
482  }
483  else
484  {
485  usesNodeSet = false;
486  nodeSetName = "";
487  while ((nodeNamesString[0] == '{' && nodeNamesString[nodeNamesString.size() - 1] == '}') ||
488  (nodeNamesString[0] == '(' && nodeNamesString[nodeNamesString.size() - 1] == ')') ||
489  (nodeNamesString[0] == '[' && nodeNamesString[nodeNamesString.size() - 1] == ']'))
490  {
491  nodeNamesString = nodeNamesString.substr(1, nodeNamesString.size() - 2);
492  }
493 
494  ARMARX_CHECK_EXPRESSION(nodeNamesString.size() > 0);
495 
496  nodeNames = simox::alg::split(nodeNamesString, ",");
497  }
498  return true;
499 }
500 
502 armarx::CollisionCheckerComponent::getSceneObjectFromWorkingMemory(const std::string& name)
503 {
504  for (VirtualRobot::SceneObjectPtr& sc : workingMemorySceneObjects)
505  {
506  if (sc->getName() == name)
507  {
508  return sc;
509  }
510  }
511  const memoryx::EntityBasePtr entityBase = objectInstancesPrx->getEntityByName(name);
512  const memoryx::ObjectInstanceBasePtr object =
513  memoryx::ObjectInstancePtr::dynamicCast(entityBase);
514 
515  if (!object)
516  {
517  ARMARX_ERROR << "Could not get object with name " << name << std::endl;
519  }
520 
521  const std::string className = object->getMostProbableClass();
522 
523  memoryx::ObjectClassList classes =
524  workingMemoryPrx->getPriorKnowledge()->getObjectClassesSegment()->getClassWithSubclasses(
525  className);
526 
527  if (!classes.size())
528  {
529  ARMARX_INFO_S << "No classes for most probable class '" << className << "' of object '"
530  << object->getName() << "' with name " << name;
532  }
533 
534  memoryx::ObjectClassPtr objectClass = memoryx::ObjectClassPtr::dynamicCast(classes.at(0));
535  const PosePtr objectPose = armarx::PosePtr::dynamicCast(armarx::PoseBasePtr{
536  new armarx::Pose{object->getPositionBase(), object->getOrientationBase()}});
537 
538  if (!objectClass)
539  {
540  ARMARX_ERROR << "Can't use object class with ice id " << classes.at(0)->ice_id()
541  << std::endl;
543  }
544 
546  objectClass->addWrapper(new memoryx::EntityWrappers::SimoxObjectWrapper(fileManager));
547  VirtualRobot::ManipulationObjectPtr orgMo = sw->getManipulationObject();
549  std::string moName = orgMo->getName();
550  VirtualRobot::ManipulationObjectPtr mo = orgMo->clone(moName);
551 
552  //move the object to the given position
553  if (!objectPose)
554  {
555  ARMARX_ERROR << "Can't convert pose of " << objectClass->getName() << " to armarx::Pose."
556  << std::endl;
558  }
559  mo->setGlobalPose(objectPose->toEigen());
560  mo->setName(name); //make shure the name of the scene object is equal to the requested name
561 
562  workingMemorySceneObjects.push_back(mo);
563  return mo;
564 }
565 
566 void
567 armarx::CollisionCheckerComponent::synchronizeObjectsFromWorkingMemory()
568 {
569  std::scoped_lock lockPosition(wmPositionMutex);
570  for (VirtualRobot::SceneObjectPtr& sc : workingMemorySceneObjects)
571  {
572  auto it = currentPositions.find(sc->getName());
573  if (it != currentPositions.end())
574  {
575  sc->setGlobalPose(it->second->toEigen());
576  }
577  }
578 }
579 
580 void
581 armarx::CollisionCheckerComponent::reportDistancesAndCollisions()
582 {
583  std::scoped_lock lockData(dataMutex);
584  for (RobotPair& r : robots)
585  {
587  r.robot, r.robotStateComponentPrx->getSynchronizedRobot());
588  }
589  synchronizeObjectsFromWorkingMemory();
590 
591  for (SceneObjectPair& pair : sceneObjectPairs)
592  {
593  if (!pair.objects1 || !pair.objects2)
594  {
595  continue;
596  }
597  double distance;
598  if (useDebugDrawer && debugDrawerTopicPrx)
599  {
600  std::ostringstream nodeNames1Str;
601  std::copy(pair.nodeNames1.begin(),
602  pair.nodeNames1.end() - 1,
603  std::ostream_iterator<std::string>(nodeNames1Str, ","));
604  nodeNames1Str << pair.nodeNames1.back();
605 
606  std::ostringstream nodeNames2Str;
607  std::copy(pair.nodeNames2.begin(),
608  pair.nodeNames2.end() - 1,
609  std::ostream_iterator<std::string>(nodeNames2Str, ","));
610  nodeNames2Str << pair.nodeNames2.back();
611 
612  Eigen::Vector3f p1, p2;
613  distance = collisionChecker->calculateDistance(pair.objects1, pair.objects2, p1, p2);
614  Vector3BasePtr p1a(new Vector3(p1)), p2a(new Vector3(p2));
615  DrawColor color;
616  if (distance <= pair.warningDistance)
617  {
618  color.r = 1;
619  color.g = 1;
620  color.b = 0;
621  }
622  else
623  {
624  color.r = 0;
625  color.g = 0.9;
626  color.b = 0;
627  }
628  debugDrawerTopicPrx->setLineVisu("distanceVisu",
629  pair.robotName1 + (pair.robotName1 == "" ? "" : ": ") +
630  nodeNames1Str.str() + " - " + pair.robotName2 +
631  (pair.robotName2 == "" ? "" : ": ") +
632  nodeNames2Str.str(),
633  p1a,
634  p2a,
635  1,
636  color);
637  }
638  else
639  {
640  distance = collisionChecker->calculateDistance(pair.objects1, pair.objects2);
641  }
642 
643  distanceListenerPrx->reportDistance(
644  pair.robotName1, pair.nodeNames1, pair.robotName2, pair.nodeNames2, distance);
645 
646  if (distance <= pair.warningDistance)
647  {
648  collisionListenerPrx->reportCollisionWarning(
649  pair.robotName1, pair.nodeNames1, pair.robotName2, pair.nodeNames2, distance);
650  }
651 
652  if (collisionChecker->checkCollision(pair.objects1, pair.objects2))
653  {
654  collisionListenerPrx->reportCollision(
655  pair.robotName1, pair.nodeNames1, pair.robotName2, pair.nodeNames2, distance);
656  }
657  }
658 }
659 
660 void
661 CollisionCheckerComponent::addCollisionPair(const std::string& robotName1,
662  const std::vector<std::string>& nodeNames1,
663  const std::string& robotName2,
664  const std::vector<std::string>& nodeNames2,
665  double warningDistance,
666  const Ice::Current&)
667 {
669  robotName1, nodeNames1, false, "", robotName2, nodeNames2, false, "", warningDistance);
670 }
671 
672 void
673 CollisionCheckerComponent::addCollisionPair(const std::string& robotName1,
674  const std::vector<std::string>& nodeNames1,
675  const bool usesNodeSet1,
676  const std::string& nodeSetName1,
677  const std::string& robotName2,
678  const std::vector<std::string>& nodeNames2,
679  const bool usesNodeSet2,
680  const std::string& nodeSetName2,
681  double warningDistance)
682 {
683  if (hasCollisionPair(robotName1, nodeNames1, robotName2, nodeNames2))
684  {
685  return;
686  }
687  SceneObjectPair pair = {VirtualRobot::SceneObjectSetPtr(),
688  robotName1,
689  nodeNames1,
690  usesNodeSet1,
691  nodeSetName1,
692  VirtualRobot::SceneObjectSetPtr(),
693  robotName2,
694  nodeNames2,
695  usesNodeSet2,
696  nodeSetName2,
697  warningDistance};
698  std::scoped_lock lockData(dataMutex);
699  resolveCollisionPair(pair);
700  sceneObjectPairs.push_back(pair);
701 }
702 
703 void
705  const std::vector<std::string>& nodeNames1,
706  const std::string& robotName2,
707  const std::vector<std::string>& nodeNames2,
708  const Ice::Current&)
709 {
710  std::scoped_lock lockData(dataMutex);
711  for (auto it = sceneObjectPairs.begin(); it != sceneObjectPairs.end(); it++)
712  {
713  if ((it->robotName1 == robotName1 && it->nodeNames1 == nodeNames1 &&
714  it->robotName2 == robotName2 && it->nodeNames2 == nodeNames2) ||
715  (it->robotName1 == robotName2 && it->nodeNames1 == nodeNames2 &&
716  it->robotName2 == robotName1 && it->nodeNames2 == nodeNames1))
717  {
718  sceneObjectPairs.erase(it);
719  break;
720  }
721  }
722 }
723 
724 bool
725 CollisionCheckerComponent::hasCollisionPair(const std::string& robotName1,
726  const std::vector<std::string>& nodeNames1,
727  const std::string& robotName2,
728  const std::vector<std::string>& nodeNames2,
729  const Ice::Current&) const
730 {
731  std::scoped_lock lockData(dataMutex);
732  for (const SceneObjectPair& pair : sceneObjectPairs)
733  {
734  if ((pair.robotName1 == robotName1 && pair.nodeNames1 == nodeNames1 &&
735  pair.robotName2 == robotName2 && pair.nodeNames2 == nodeNames2) ||
736  (pair.robotName1 == robotName2 && pair.nodeNames1 == nodeNames2 &&
737  pair.robotName2 == robotName1 && pair.nodeNames2 == nodeNames1))
738  {
739  return true;
740  }
741  }
742  return false;
743 }
744 
745 void
746 CollisionCheckerComponent::setWarningDistance(const std::string& robotName1,
747  const std::vector<std::string>& nodeNames1,
748  const std::string& robotName2,
749  const std::vector<std::string>& nodeNames2,
750  double warningDistance,
751  const Ice::Current&)
752 {
753  std::scoped_lock lockData(dataMutex);
754  for (SceneObjectPair& pair : sceneObjectPairs)
755  {
756  if ((pair.robotName1 == robotName1 && pair.nodeNames1 == nodeNames1 &&
757  pair.robotName2 == robotName2 && pair.nodeNames2 == nodeNames2) ||
758  (pair.robotName1 == robotName2 && pair.nodeNames1 == nodeNames2 &&
759  pair.robotName2 == robotName1 && pair.nodeNames2 == nodeNames1))
760  {
761  pair.warningDistance = warningDistance;
762  break;
763  }
764  }
765 }
766 
767 double
768 CollisionCheckerComponent::getWarningDistance(const std::string& robotName1,
769  const std::vector<std::string>& nodeNames1,
770  const std::string& robotName2,
771  const std::vector<std::string>& nodeNames2,
772  const Ice::Current&) const
773 {
774  std::scoped_lock lockData(dataMutex);
775  for (const SceneObjectPair& pair : sceneObjectPairs)
776  {
777  if ((pair.robotName1 == robotName1 && pair.nodeNames1 == nodeNames1 &&
778  pair.robotName2 == robotName2 && pair.nodeNames2 == nodeNames2) ||
779  (pair.robotName1 == robotName2 && pair.nodeNames1 == nodeNames2 &&
780  pair.robotName2 == robotName1 && pair.nodeNames2 == nodeNames1))
781  {
782  return pair.warningDistance;
783  }
784  }
785  return INFINITY;
786 }
787 
788 CollisionPairList
790 {
791  std::scoped_lock lockData(dataMutex);
792  CollisionPairList list;
793  for (const SceneObjectPair& pair : sceneObjectPairs)
794  {
795  armarx::CollisionPair p = {pair.robotName1,
796  pair.nodeNames1,
797  pair.robotName2,
798  pair.nodeNames2,
799  pair.warningDistance};
800  list.push_back(p);
801  }
802  return list;
803 }
804 
805 int
806 CollisionCheckerComponent::getInterval(const Ice::Current&) const
807 {
808  return interval;
809 }
810 
811 void
813 {
814  std::shared_lock lockConnected(connectedMutex);
815  this->interval = interval;
816  if (connected && reportTask && reportTask->isRunning())
817  {
818  reportTask->stop();
820  this,
821  &CollisionCheckerComponent::reportDistancesAndCollisions,
822  interval,
823  false,
824  "ReportCollisionsTask");
825  reportTask->start();
826  }
827  else
828  {
830  this,
831  &CollisionCheckerComponent::reportDistancesAndCollisions,
832  interval,
833  false,
834  "ReportCollisionsTask");
835  }
836 }
837 
838 void
839 CollisionCheckerComponent::reportEntityCreated(const std::string& segmentName,
840  const memoryx::EntityBasePtr& entity,
841  const Ice::Current&)
842 {
843  if (segmentName == objectInstancesPrx->getSegmentName())
844  {
845  std::scoped_lock lockData(dataMutex);
846  for (SceneObjectPair& pair : sceneObjectPairs)
847  {
848  if ((!pair.objects1 || !pair.objects2) &&
849  ((pair.robotName1 == "" &&
850  std::find(pair.nodeNames1.begin(), pair.nodeNames1.end(), entity->getName()) !=
851  pair.nodeNames1.end()) ||
852  (pair.robotName2 == "" &&
853  std::find(pair.nodeNames2.begin(), pair.nodeNames2.end(), entity->getName()) !=
854  pair.nodeNames2.end())))
855  {
856  resolveCollisionPair(pair);
857  }
858  }
859  }
860  else if (segmentName == agentInstancesPrx->getSegmentName())
861  {
862  std::scoped_lock lockData(dataMutex);
863  memoryx::AgentInstanceBasePtr agent =
864  agentInstancesPrx->getAgentInstanceById(entity->getId());
865  RobotStateComponentInterfacePrx robotStateComponentPrx =
866  agent->getSharedRobot()->getRobotStateComponent();
867  VirtualRobot::RobotPtr robot =
868  armarx::RemoteRobot::createLocalCloneFromFile(robotStateComponentPrx);
869 
870  robots.push_back({robot, robotStateComponentPrx});
871 
872 
873  for (SceneObjectPair& pair : sceneObjectPairs)
874  {
875  if ((!pair.objects1 || !pair.objects2) &&
876  (pair.robotName1 == entity->getName() || pair.robotName2 == entity->getName()))
877  {
878  resolveCollisionPair(pair);
879  }
880  }
881  }
882 }
883 
884 void
885 CollisionCheckerComponent::reportEntityUpdated(const std::string& segmentName,
886  const memoryx::EntityBasePtr& entityOld,
887  const memoryx::EntityBasePtr& entityNew,
888  const Ice::Current&)
889 {
890  if (segmentName == objectInstancesPrx->getSegmentName())
891  {
892  std::scoped_lock lockPosition(wmPositionMutex);
893  const memoryx::ObjectInstanceBasePtr object =
894  memoryx::ObjectInstancePtr::dynamicCast(entityNew);
895  currentPositions[entityNew->getName()] = armarx::PosePtr::dynamicCast(armarx::PoseBasePtr{
896  new armarx::Pose{object->getPositionBase(), object->getOrientationBase()}});
897  }
898 }
899 
900 void
901 CollisionCheckerComponent::reportEntityRemoved(const std::string& segmentName,
902  const memoryx::EntityBasePtr& entity,
903  const Ice::Current&)
904 {
905  if (segmentName == objectInstancesPrx->getSegmentName())
906  {
907  std::scoped_lock lockData(dataMutex);
908  for (SceneObjectPair& pair : sceneObjectPairs)
909  {
910  if ((pair.robotName1 == "" &&
911  std::find(pair.nodeNames1.begin(), pair.nodeNames1.end(), entity->getName()) !=
912  pair.nodeNames1.end()) ||
913  (pair.robotName2 == "" &&
914  std::find(pair.nodeNames2.begin(), pair.nodeNames2.end(), entity->getName()) !=
915  pair.nodeNames2.end()))
916  {
917  pair.objects1.reset();
918  pair.objects2.reset();
919  }
920  }
921  for (auto it = workingMemorySceneObjects.begin(); it != workingMemorySceneObjects.end();
922  ++it)
923  {
924  if ((*it)->getName() == entity->getName())
925  {
926  workingMemorySceneObjects.erase(it);
927  break;
928  }
929  }
930  }
931  else if (segmentName == agentInstancesPrx->getSegmentName())
932  {
933  std::scoped_lock lockData(dataMutex);
934  for (auto it = robots.begin(); it != robots.end(); ++it)
935  {
936  if ((*it).robot->getName() == entity->getName())
937  {
938  robots.erase(it);
939  break;
940  }
941  }
942 
943  for (SceneObjectPair& pair : sceneObjectPairs)
944  {
945  if (pair.robotName1 == entity->getName() || pair.robotName2 == entity->getName())
946  {
947  pair.objects1.reset();
948  pair.objects2.reset();
949  }
950  }
951  }
952 }
953 
954 void
955 CollisionCheckerComponent::reportSnapshotLoaded(const std::string& segmentName, const Ice::Current&)
956 {
957  if (segmentName == objectInstancesPrx->getSegmentName())
958  {
959  std::scoped_lock lockData(dataMutex);
960  for (SceneObjectPair& pair : sceneObjectPairs)
961  {
962  if (!pair.objects1 || !pair.objects2)
963  {
964  resolveCollisionPair(pair);
965  }
966  }
967  }
968 }
969 
970 void
971 CollisionCheckerComponent::reportSnapshotCompletelyLoaded(const Ice::Current& c)
972 {
973 }
974 
975 void
976 CollisionCheckerComponent::reportMemoryCleared(const std::string& segmentName, const Ice::Current&)
977 {
978  if (segmentName == objectInstancesPrx->getSegmentName())
979  {
980  std::scoped_lock lockData(dataMutex);
981  for (SceneObjectPair& pair : sceneObjectPairs)
982  {
983  if (pair.robotName1 == "" || pair.robotName2 == "")
984  {
985  pair.objects1.reset();
986  pair.objects2.reset();
987  }
988  }
989  }
990 }
armarx::CollisionCheckerComponent::setWarningDistance
void setWarningDistance(const std::string &robotName1, const std::vector< std::string > &nodeNames1, const std::string &robotName2, const std::vector< std::string > &nodeNames2, double warningDistance, const Ice::Current &=Ice::emptyCurrent) override
Definition: CollisionCheckerComponent.cpp:746
RemoteRobot.h
armarx::CollisionCheckerComponent::onInitComponent
void onInitComponent() override
Definition: CollisionCheckerComponent.cpp:57
armarx::CollisionCheckerComponent::getWarningDistance
double getWarningDistance(const std::string &robotName1, const std::vector< std::string > &nodeNames1, const std::string &robotName2, const std::vector< std::string > &nodeNames2, const Ice::Current &=Ice::emptyCurrent) const override
Definition: CollisionCheckerComponent.cpp:768
armarx::RemoteRobot::synchronizeLocalClone
static bool synchronizeLocalClone(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx)
Definition: RemoteRobot.cpp:522
robots
std::vector< VirtualRobot::RobotPtr > robots
Definition: VisualizationRobot.cpp:88
armarx::RemoteRobot::createLocalCloneFromFile
static VirtualRobot::RobotPtr createLocalCloneFromFile(RobotStateComponentInterfacePrx robotStatePrx, VirtualRobot::RobotIO::RobotDescription loadMode=VirtualRobot::RobotIO::eFull)
This is a convenience function for createLocalClone, which automatically gets the filename from the R...
Definition: RemoteRobot.cpp:512
list
list(APPEND SOURCES ${QT_RESOURCES}) set(COMPONENT_LIBS ArmarXGui ArmarXCoreObservers ArmarXCoreEigen3Variants PlotterController $
Definition: CMakeLists.txt:49
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:46
armarx::CollisionCheckerComponent::hasCollisionPair
bool hasCollisionPair(const std::string &robotName1, const std::vector< std::string > &nodeNames1, const std::string &robotName2, const std::vector< std::string > &nodeNames2, const Ice::Current &=Ice::emptyCurrent) const override
Definition: CollisionCheckerComponent.cpp:725
so
linux gnu libIceDB so
Definition: CMakeLists.txt:7
ObjectClass.h
IceInternal::Handle< ObjectClass >
armarx::CollisionCheckerComponent::onExitComponent
void onExitComponent() override
Definition: CollisionCheckerComponent.cpp:280
armarx::CollisionCheckerComponent::CollisionCheckerComponent
CollisionCheckerComponent()
Definition: CollisionCheckerComponent.cpp:52
armarx::CollisionCheckerComponent::getInterval
int getInterval(const Ice::Current &=Ice::emptyCurrent) const override
Definition: CollisionCheckerComponent.cpp:806
copy
Use of this software is granted under one of the following two to be chosen freely by the user Boost Software License Version Marcin Kalicinski Permission is hereby free of to any person or organization obtaining a copy of the software and accompanying documentation covered by this and transmit the and to prepare derivative works of the and to permit third parties to whom the Software is furnished to do all subject to the including the above license this restriction and the following must be included in all copies of the in whole or in and all derivative works of the unless such copies or derivative works are solely in the form of machine executable object code generated by a source language processor THE SOFTWARE IS PROVIDED AS WITHOUT WARRANTY OF ANY EXPRESS OR INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF FITNESS FOR A PARTICULAR TITLE AND NON INFRINGEMENT IN NO EVENT SHALL THE COPYRIGHT HOLDERS OR ANYONE DISTRIBUTING THE SOFTWARE BE LIABLE FOR ANY DAMAGES OR OTHER WHETHER IN TORT OR ARISING OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE The MIT Marcin Kalicinski Permission is hereby free of to any person obtaining a copy of this software and associated documentation to deal in the Software without including without limitation the rights to copy
Definition: license.txt:39
armarx::interval
Interval< T > interval(T lo, T hi)
Definition: OccupancyGrid.h:33
armarx::CollisionCheckerComponent::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: CollisionCheckerComponent.cpp:285
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:184
CollisionCheckerComponent.h
MemoryXCoreObjectFactories.h
armarx::CollisionCheckerComponent::addCollisionPair
void addCollisionPair(const std::string &robotName1, const std::vector< std::string > &nodeNames1, const std::string &robotName2, const std::vector< std::string > &nodeNames2, double warningDistance, const Ice::Current &=Ice::emptyCurrent) override
Definition: CollisionCheckerComponent.cpp:661
ARMARX_ERROR
#define ARMARX_ERROR
Definition: Logging.h:196
armarx::CollisionCheckerComponent::setInterval
void setInterval(int interval, const Ice::Current &=Ice::emptyCurrent) override
Definition: CollisionCheckerComponent.cpp:812
memoryx::EntityWrappers::SimoxObjectWrapper
SimoxObjectWrapper offers a simplified access to the Simox ManipulationObject (i.e visualization,...
Definition: SimoxObjectWrapper.h:46
armarx::CollisionCheckerComponentPropertyDefinitions
Definition: CollisionCheckerComponent.h:49
armarx::CollisionCheckerComponent::getAllCollisionPairs
CollisionPairList getAllCollisionPairs(const Ice::Current &=Ice::emptyCurrent) const override
Definition: CollisionCheckerComponent.cpp:789
armarx::ManagedIceObject::usingTopic
void usingTopic(const std::string &name, bool orderedPublishing=false)
Registers a proxy for subscription after initialization.
Definition: ManagedIceObject.cpp:254
armarx::Component::getConfigIdentifier
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition: Component.cpp:79
CMakePackageFinder.h
SimoxObjectWrapper.h
armarx::Pose
The Pose class.
Definition: Pose.h:242
armarx::CollisionCheckerComponent::onDisconnectComponent
void onDisconnectComponent() override
Definition: CollisionCheckerComponent.cpp:256
ObjectInstance.h
ARMARX_CHECK_EXPRESSION
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
Definition: ExpressionException.h:73
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:181
armarx::ManagedIceObject::offeringTopic
void offeringTopic(const std::string &name)
Registers a topic for retrival after initialization.
Definition: ManagedIceObject.cpp:300
set
set(LIBS ArmarXCoreInterfaces ${CMAKE_THREAD_LIBS_INIT} ${dl_LIBRARIES} ${rt_LIBRARIES} ${QT_LIBRARIES} ${Boost_LIBRARIES} BoostAssertionHandler ArmarXCPPUtility SimoxUtility) set(LIB_FILES ArmarXManager.cpp ArmarXMultipleObjectsScheduler.cpp ArmarXObjectScheduler.cpp ManagedIceObject.cpp ManagedIceObjectPlugin.cpp Component.cpp ComponentPlugin.cpp IceGridAdmin.cpp ArmarXObjectObserver.cpp IceManager.cpp PackagePath.cpp RemoteReferenceCount.cpp logging/LoggingUtil.cpp logging/Logging.cpp logging/LogSender.cpp logging/ArmarXLogBuf.cpp system/ArmarXDataPath.cpp system/DynamicLibrary.cpp system/ProcessWatcher.cpp system/FactoryCollectionBase.cpp system/cmake/CMakePackageFinder.cpp system/cmake/CMakePackageFinderCache.cpp system/cmake/ArmarXPackageToolInterface.cpp system/RemoteObjectNode.cpp services/sharedmemory/HardwareId.cpp services/tasks/RunningTask.cpp services/tasks/ThreadList.cpp services/tasks/ThreadPool.cpp services/profiler/Profiler.cpp services/profiler/FileLoggingStrategy.cpp services/profiler/IceLoggingStrategy.cpp application/Application.cpp application/ApplicationOptions.cpp application/ApplicationProcessFacet.cpp application/ApplicationNetworkStats.cpp application/properties/PropertyUser.cpp application/properties/Property.cpp application/properties/PropertyDefinition.cpp application/properties/PropertyDefinitionContainer.cpp application/properties/PropertyDefinitionHelpFormatter.cpp application/properties/PropertyDefinitionConfigFormatter.cpp application/properties/PropertyDefinitionBriefHelpFormatter.cpp application/properties/PropertyDefinitionXmlFormatter.cpp application/properties/PropertyDefinitionDoxygenFormatter.cpp application/properties/PropertyDefinitionDoxygenComponentPagesFormatter.cpp application/properties/PropertyDefinitionContainerBriefHelpFormatter.cpp application/properties/IceProperties.cpp exceptions/Exception.cpp exceptions/local/UnexpectedEnumValueException.cpp util/FileSystemPathBuilder.cpp util/StringHelpers.cpp util/IceReportSkipper.cpp util/Throttler.cpp util/distributed/AMDCallbackCollection.cpp util/distributed/RemoteHandle/ClientSideRemoteHandleControlBlock.cpp util/distributed/RemoteHandle/RemoteHandle.cpp util/distributed/RemoteHandle/RemoteHandleControlBlock.cpp time/ice_conversions.cpp time/json_conversions.cpp time/CallbackWaitLock.cpp time/Clock.cpp time/ClockType.cpp time/ClockTypeNames.cpp time/CycleUtil.cpp time/DateTime.cpp time/Duration.cpp time/Frequency.cpp time/LocalTimeServer.cpp time/Metronome.cpp time/ScopedStopWatch.cpp time/StopWatch.cpp time/Timer.cpp time/TimeKeeper.cpp time/TimeUtil.cpp csv/CsvWriter.cpp csv/CsvReader.cpp eigen/conversions.cpp eigen/ice_conversions.cpp) set(LIB_HEADERS ArmarXManager.h ArmarXDummyManager.h ArmarXMultipleObjectsScheduler.h ArmarXObjectObserver.h ArmarXObjectScheduler.h ArmarXFwd.h Component.h ComponentPlugin.h ComponentFactories.h CoreObjectFactories.h IceGridAdmin.h IceManager.h IceManagerImpl.h json_conversions.h ManagedIceObject.h ManagedIceObjectPlugin.h ManagedIceObjectImpl.h ManagedIceObjectDependency.h ManagedIceObjectRegistryInterface.h PackagePath.h RemoteReferenceCount.h system/ImportExport.h system/ImportExportComponent.h system/AbstractFactoryMethod.h system/FactoryCollectionBase.h system/Synchronization.h system/ArmarXDataPath.h system/DynamicLibrary.h system/ProcessWatcher.h system/ConditionSynchronization.h system/cmake/CMakePackageFinder.h system/cmake/CMakePackageFinderCache.h system/cmake/FindPackageX.cmake system/cmake/ArmarXPackageToolInterface.h system/RemoteObjectNode.h logging/LoggingUtil.h logging/LogSender.h logging/Logging.h logging/ArmarXLogBuf.h logging/SpamFilterData.h services/tasks/RunningTask.h services/tasks/PeriodicTask.h services/tasks/ThreadList.h services/tasks/TaskUtil.h services/tasks/ThreadPool.h services/sharedmemory/SharedMemoryProvider.h services/sharedmemory/SharedMemoryConsumer.h services/sharedmemory/IceSharedMemoryProvider.h services/sharedmemory/IceSharedMemoryConsumer.h services/sharedmemory/HardwareIdentifierProvider.h services/sharedmemory/HardwareId.h services/sharedmemory/exceptions/SharedMemoryExceptions.h services/profiler/Profiler.h services/profiler/LoggingStrategy.h services/profiler/FileLoggingStrategy.h services/profiler/IceLoggingStrategy.h application/Application.h application/ApplicationOptions.h application/ApplicationProcessFacet.h application/ApplicationNetworkStats.h application/properties/forward_declarations.h application/properties/Properties.h application/properties/Property.h application/properties/PluginEigen.h application/properties/PluginEnumNames.h application/properties/PluginCfgStruct.h application/properties/PluginAll.h application/properties/PropertyUser.h application/properties/PropertyDefinition.h application/properties/PropertyDefinition.hpp application/properties/PropertyDefinitionInterface.h application/properties/PropertyDefinitionContainer.h application/properties/PropertyDefinitionFormatter.h application/properties/PropertyDefinitionContainerFormatter.h application/properties/PropertyDefinitionConfigFormatter.h application/properties/PropertyDefinitionHelpFormatter.h application/properties/PropertyDefinitionBriefHelpFormatter.h application/properties/PropertyDefinitionXmlFormatter.h application/properties/PropertyDefinitionDoxygenFormatter.h application/properties/PropertyDefinitionDoxygenComponentPagesFormatter.h application/properties/PropertyDefinitionContainerBriefHelpFormatter.h application/properties/ProxyPropertyDefinition.h application/properties/IceProperties.h exceptions/Exception.h exceptions/LocalException.h exceptions/local/DynamicLibraryException.h exceptions/local/ExpressionException.h exceptions/local/FileIOException.h exceptions/local/InvalidPropertyValueException.h exceptions/local/MissingRequiredPropertyException.h exceptions/local/PropertyInheritanceCycleException.h exceptions/local/ProxyNotInitializedException.h exceptions/local/UnexpectedEnumValueException.h exceptions/local/UnmappedValueException.h exceptions/local/ValueRangeExceededException.h exceptions/user/NotImplementedYetException.h rapidxml/rapidxml.hpp rapidxml/rapidxml_print.hpp rapidxml/rapidxml_iterators.hpp rapidxml/rapidxml_utils.hpp rapidxml/wrapper/RapidXmlReader.h rapidxml/wrapper/RapidXmlWriter.h rapidxml/wrapper/DefaultRapidXmlReader.h rapidxml/wrapper/MultiNodeRapidXMLReader.h util/IceBlobToObject.h util/ObjectToIceBlob.h util/FileSystemPathBuilder.h util/FiniteStateMachine.h util/StringHelpers.h util/StringHelperTemplates.h util/algorithm.h util/OnScopeExit.h util/Predicates.h util/Preprocessor.h util/PropagateConst.h util/Registrar.h util/TemplateMetaProgramming.h util/TripleBuffer.h util/IceReportSkipper.h util/Throttler.h util/distributed/AMDCallbackCollection.h util/distributed/RemoteHandle/ClientSideRemoteHandleControlBlock.h util/distributed/RemoteHandle/RemoteHandle.h util/distributed/RemoteHandle/RemoteHandleControlBlock.h util/SimpleStatemachine.h time.h time_minimal.h time/forward_declarations.h time/ice_conversions.h time/json_conversions.h time/CallbackWaitLock.h time/Clock.h time/ClockType.h time/ClockTypeNames.h time/CycleUtil.h time/DateTime.h time/Duration.h time/Frequency.h time/LocalTimeServer.h time/Metronome.h time/ScopedStopWatch.h time/StopWatch.h time/Timer.h time/TimeUtil.h time/TimeKeeper.h csv/CsvWriter.h csv/CsvReader.h eigen/conversions.h eigen/ice_conversions.h ice_conversions.h ice_conversions/ice_conversions_boost_templates.h ice_conversions/ice_conversions_templates.h ice_conversions/ice_conversions_templates.tpp $
Definition: CMakeLists.txt:12
IceUtil::Handle< class PropertyDefinitionContainer >
armarx::CollisionCheckerComponent::removeCollisionPair
void removeCollisionPair(const std::string &robotName1, const std::vector< std::string > &nodeNames1, const std::string &robotName2, const std::vector< std::string > &nodeNames2, const Ice::Current &=Ice::emptyCurrent) override
Definition: CollisionCheckerComponent.cpp:704
memoryx::KBM::Vector3
Eigen::Vector3d Vector3
Definition: kbm.h:43
IceInternal::ProxyHandle<::IceProxy::armarx::RobotStateComponentInterface >
scene3D::SceneObjectPtr
boost::intrusive_ptr< SceneObject > SceneObjectPtr
Definition: PointerDefinitions.h:40
memoryx::GridFileManager
GridFileManager provides utility functions for working with files in Mongo GridFS and links to them s...
Definition: GridFileManager.h:41
MemoryXTypesObjectFactories.h
AgentInstance.h
distance
double distance(const Point &a, const Point &b)
Definition: point.hpp:95
ARMARX_INFO_S
#define ARMARX_INFO_S
Definition: Logging.h:202
armarx::PeriodicTask
Definition: ArmarXManager.h:70
armarx::CollisionCheckerComponent::onConnectComponent
void onConnectComponent() override
Definition: CollisionCheckerComponent.cpp:160
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:193
armarx::PropertyDefinitionsPtr
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
Definition: forward_declarations.h:35
ArmarXDataPath.h
armarx::ManagedIceObject::usingProxy
bool usingProxy(const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list.
Definition: ManagedIceObject.cpp:154
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:27
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:19
armarx::split
std::vector< std::string > split(const std::string &source, const std::string &splitBy, bool trimElements=false, bool removeEmptyElements=false)
Definition: StringHelpers.cpp:38