RobotUnitModuleSelfCollisionChecker.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 RobotAPI::ArmarXObjects::RobotUnit
17  * @author Raphael Grimm ( raphael dot grimm at kit dot edu )
18  * @date 2018
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
24 #include <algorithm>
25 #include <cstddef>
26 #include <string>
27 
28 #include <SimoxUtility/algorithm/string/string_tools.h>
29 #include <VirtualRobot/CollisionDetection/CollisionChecker.h>
30 #include <VirtualRobot/Obstacle.h>
31 #include <VirtualRobot/RobotNodeSet.h>
32 
36 
41 
43 
44 #define FLOOR_OBJ_STR "FLOOR"
45 
47 {
48  void
49  SelfCollisionChecker::_preOnInitRobotUnit()
50  {
51  throwIfInControlThread(BOOST_CURRENT_FUNCTION);
52  //get the robot
53  selfCollisionAvoidanceRobot = _module<RobotData>().cloneRobot(true);
54  //get pairs to check
55  {
56  const std::string colModelsString =
57  getProperty<std::string>("SelfCollisionCheck_ModelGroupsToCheck").getValue();
58  std::vector<std::string> groups;
59  if (!colModelsString.empty())
60  {
61  groups = armarx::Split(colModelsString, ";", true, true);
62  }
63  ARMARX_DEBUG << "Processing groups for self collision checking:";
64  for (std::string& group : groups)
65  {
66  ARMARX_DEBUG << "---- group: " << group;
67  // Removing parentheses
68  simox::alg::trim_if(group, " \t{}");
69  std::set<std::set<std::string>> setsOfNode;
70  {
71  auto splittedRaw = armarx::Split(group, ",", true, true);
72  if (splittedRaw.size() < 2)
73  {
74  continue;
75  }
76  for (auto& subentry : splittedRaw)
77  {
78  simox::alg::trim_if(subentry, " \t{}");
79  if (selfCollisionAvoidanceRobot->hasRobotNodeSet(subentry))
80  {
81  std::set<std::string> nodes;
82  //the entry is a set
83  for (const auto& node :
84  selfCollisionAvoidanceRobot->getRobotNodeSet(subentry)
85  ->getAllRobotNodes())
86  {
87  if (!node->getCollisionModel())
88  {
89 
90  ARMARX_WARNING << "Self Collision Avoidance: No collision "
91  "model found for '"
92  << node->getName() << "'";
93  continue;
94  }
95  nodes.emplace(node->getName());
96  ARMARX_DEBUG << "-------- from set: " << subentry
97  << ", node: " << node->getName();
98  }
99  setsOfNode.emplace(std::move(nodes));
100  }
101  else if (selfCollisionAvoidanceRobot->hasRobotNode(subentry))
102  {
103  //the entry is a node
104  if (!selfCollisionAvoidanceRobot->getRobotNode(subentry)
105  ->getCollisionModel())
106  {
107 
109  << "Self Collision Avoidance: No collision model found for '"
110  << selfCollisionAvoidanceRobot->getRobotNode(subentry)
111  ->getName()
112  << "'";
113  continue;
114  }
115  setsOfNode.emplace(std::set<std::string>{subentry});
116  ARMARX_DEBUG << "-------- node: " << subentry;
117  }
118  else if (subentry == FLOOR_OBJ_STR)
119  {
120  //the entry is the floor
121  setsOfNode.emplace(std::set<std::string>{subentry});
122  ARMARX_DEBUG << "-------- floor: " << subentry;
123  }
124  else
125  {
126  ARMARX_ERROR << "No RobotNodeSet or RobotNode with name '" << subentry
127  << "' defined in "
128  << _module<RobotData>().getRobotFileName()
129  << ". Skipping.";
130  continue;
131  }
132  }
133  }
134 
135  auto addCombinationOfSetsToCollisionCheck =
136  [this](const std::set<std::string>& a, const std::set<std::string>& b)
137  {
138  for (const auto& nodeA : a)
139  {
140  for (const auto& nodeB : b)
141  {
142  if (nodeA == nodeB)
143  {
144  continue;
145  }
146  if (nodeA < nodeB)
147  {
148  ARMARX_DEBUG << "------------ " << nodeA << " " << nodeB;
149  namePairsToCheck.emplace(nodeA, nodeB);
150  }
151  else
152  {
153  ARMARX_DEBUG << "------------ " << nodeB << " " << nodeA;
154  namePairsToCheck.emplace(nodeB, nodeA);
155  }
156  }
157  }
158  };
159 
160  ARMARX_DEBUG << "-------- adding pairs to check:";
161  for (auto setAIt = setsOfNode.begin(); setAIt != setsOfNode.end(); ++setAIt)
162  {
163  auto setBIt = setAIt;
164  ++setBIt;
165  for (; setBIt != setsOfNode.end(); ++setBIt)
166  {
167  addCombinationOfSetsToCollisionCheck(*setAIt, *setBIt);
168  }
169  }
170 
171 
172  ARMARX_DEBUG << "-------- group: " << group << "...DONE!\n";
173  }
174  ARMARX_DEBUG << "Processing groups for self collision checking...DONE!";
175  }
177  getProperty<float>("SelfCollisionCheck_Frequency").getValue());
179  getProperty<float>("SelfCollisionCheck_MinSelfDistance").getValue());
180  }
181 
182  void
184  const Ice::Current&)
185  {
186  throwIfInControlThread(BOOST_CURRENT_FUNCTION);
187  std::lock_guard<std::mutex> guard{selfCollisionDataMutex};
188  if (distance < 0)
189  {
190  throw InvalidArgumentException{std::string{__FILE__} + ": " + BOOST_CURRENT_FUNCTION +
191  ": illegal distance:" + std::to_string(distance)};
192  }
193  if (distance == minSelfDistance && !nodePairsToCheck.empty())
194  {
195  return;
196  }
197  //reset data
199  minSelfDistance = distance;
200  selfCollisionAvoidanceRobot = _module<RobotData>().cloneRobot(true);
201  selfCollisionAvoidanceRobotNodes = selfCollisionAvoidanceRobot->getRobotNodes();
202  nodePairsToCheck.clear();
203  //set floor
204  {
205  floor.reset(new VirtualRobot::SceneObjectSet(
206  "FLOORSET", selfCollisionAvoidanceRobot->getCollisionChecker()));
207  static constexpr float floorSize = 1e16f;
208  VirtualRobot::ObstaclePtr boxOb = VirtualRobot::Obstacle::createBox(
209  floorSize,
210  floorSize,
211  std::min(0.001f, minSelfDistance / 2),
212  VirtualRobot::VisualizationFactory::Color::Red(),
213  "",
214  selfCollisionAvoidanceRobot->getCollisionChecker());
215  boxOb->setGlobalPose(Eigen::Matrix4f::Identity());
216  boxOb->setName(FLOOR_OBJ_STR);
217  floor->addSceneObject(boxOb);
218  }
219  //inflate robot
220  for (const auto& node : selfCollisionAvoidanceRobotNodes)
221  {
222  if (node->getCollisionModel())
223  {
224  node->getCollisionModel()->inflateModel(minSelfDistance / 2.f);
225  }
226  }
227 
228  // Remove / filter collision pairs according to robot model (XML: Physics/IgnoreCollision)
229  {
230  ARMARX_VERBOSE << "Removing ignored collision pairs";
231  // introduce vector to remove elements "in-place" via remove-erase-if idiom (not possible for sets)
232  std::vector<std::pair<std::string, std::string>> validNamePairsToCheck(namePairsToCheck.begin(), namePairsToCheck.end());
233 
234  const auto isCollisionIgnored = [this](const std::string& a, const std::string& b) -> bool {
235 
236  if(a == FLOOR_OBJ_STR or b == FLOOR_OBJ_STR)
237  {
238  return false;
239  }
240 
241  const auto nodeA = selfCollisionAvoidanceRobot->getRobotNode(a);
242  const auto nodeB = selfCollisionAvoidanceRobot->getRobotNode(b);
243 
244  if(nodeA == nullptr or nodeB == nullptr)
245  {
246  return false;
247  }
248 
249  const std::vector<std::string> nodesIgnoredByA = nodeA->getIgnoredCollisionModels();
250  const std::vector<std::string> nodesIgnoredByB = nodeB->getIgnoredCollisionModels();
251 
252  if(std::find(nodesIgnoredByA.begin(), nodesIgnoredByA.end(), b) != nodesIgnoredByA.end())
253  {
254  ARMARX_VERBOSE << "Ignoring collision between nodes: " << a << " -- " << b;
255  return true;
256  }
257 
258  if(std::find(nodesIgnoredByB.begin(), nodesIgnoredByB.end(), a) != nodesIgnoredByB.end())
259  {
260  ARMARX_VERBOSE << "Ignoring collision between nodes: " << b << " -- " << a;
261  return true;
262  }
263 
264  return false;
265 
266  };
267 
268  validNamePairsToCheck.erase(std::remove_if(validNamePairsToCheck.begin(), validNamePairsToCheck.end(), [&isCollisionIgnored](const auto& p) -> bool {
269  const auto& [a, b] = p;
270  return isCollisionIgnored(a, b);
271  }), validNamePairsToCheck.end());
272 
273  ARMARX_VERBOSE << "Removed " << (namePairsToCheck.size() - validNamePairsToCheck.size()) << " collision pairs.";
274 
275  // copy over name pairs which should not be ignored
276  namePairsToCheck = std::set(validNamePairsToCheck.begin(), validNamePairsToCheck.end());
277  }
278 
279  //collect pairs
280  for (const auto& pair : namePairsToCheck)
281  {
283  (pair.first == FLOOR_OBJ_STR)
284  ? floor->getSceneObject(0)
285  : selfCollisionAvoidanceRobot->getRobotNode(pair.first);
286 
287  ARMARX_CHECK_NOT_NULL(first) << pair.first;
288 
290  (pair.second == FLOOR_OBJ_STR)
291  ? floor->getSceneObject(0)
292  : selfCollisionAvoidanceRobot->getRobotNode(pair.second);
293 
294  ARMARX_CHECK_NOT_NULL(second) << pair.second;
295 
296  nodePairsToCheck.emplace_back(first, second);
297  }
298  ARMARX_CHECK_EQUAL(nodePairsToCheck.size(), namePairsToCheck.size());
299  }
300 
301  void
303  {
304  throwIfInControlThread(BOOST_CURRENT_FUNCTION);
305  if (freq < 0)
306  {
307  throw InvalidArgumentException{std::string{__FILE__} + ": " + BOOST_CURRENT_FUNCTION +
308  ": illegal frequency:" + std::to_string(freq)};
309  }
310  checkFrequency = freq;
311  }
312 
313  bool
315  {
316  throwIfInControlThread(BOOST_CURRENT_FUNCTION);
317  return checkFrequency != 0;
318  }
319 
320  float
322  {
323  throwIfInControlThread(BOOST_CURRENT_FUNCTION);
324  return checkFrequency;
325  }
326 
327  float
329  {
330  throwIfInControlThread(BOOST_CURRENT_FUNCTION);
331  return minSelfDistance;
332  }
333 
334  void
335  SelfCollisionChecker::_componentPropertiesUpdated(const std::set<std::string>& changed)
336  {
337  throwIfInControlThread(BOOST_CURRENT_FUNCTION);
338  if (changed.count("SelfCollisionCheck_Frequency"))
339  {
341  getProperty<float>("SelfCollisionCheck_Frequency").getValue());
342  }
343  if (changed.count("SelfCollisionCheck_MinSelfDistance"))
344  {
346  getProperty<float>("SelfCollisionCheck_MinSelfDistance").getValue());
347  }
348  }
349 
350  void
351  SelfCollisionChecker::_postFinishControlThreadInitialization()
352  {
353  selfCollisionAvoidanceThread = std::thread{[&] { selfCollisionAvoidanceTask(); }};
354  }
355 
356  void
357  SelfCollisionChecker::selfCollisionAvoidanceTask()
358  {
359  throwIfInControlThread(BOOST_CURRENT_FUNCTION);
360  ARMARX_INFO << "Self collision checker: entered selfCollisionAvoidanceTask";
362  {
363  ARMARX_INFO << "Self collision checker: leaving selfCollisionAvoidanceTask";
364  };
365  while (true)
366  {
367  const auto freq = checkFrequency.load();
368 
369  core::time::Metronome metronome(Frequency::Hertz(freq));
370 
371  //done
372  if (isShuttingDown())
373  {
374  return;
375  }
376  const bool inEmergencyStop =
377  _module<ControlThread>().getEmergencyStopState() == eEmergencyStopActive;
378  if (inEmergencyStop || freq == 0)
379  {
380  ARMARX_VERBOSE << deactivateSpam() << "Self collision checker: skipping check "
381  << VAROUT(freq) << " " << VAROUT(inEmergencyStop);
382  //currently wait
383  std::this_thread::sleep_for(std::chrono::microseconds{1'000});
384  continue;
385  }
386  //update robot + check
387  {
388  std::lock_guard<std::mutex> guard{selfCollisionDataMutex};
389  //update robot
390  _module<ControlThreadDataBuffer>().updateVirtualRobot(
391  selfCollisionAvoidanceRobot, selfCollisionAvoidanceRobotNodes);
392 
393  //check for all nodes 0
394  {
395  bool allJoints0 = true;
396  for (const auto& node : selfCollisionAvoidanceRobotNodes)
397  {
398  ARMARX_CHECK_NOT_NULL(node);
399  if (0 != node->getJointValue())
400  {
401  allJoints0 = false;
402  break;
403  }
404  }
405  if (allJoints0)
406  {
407  continue;
408  }
409  }
410 
411  bool collision = false;
412  for (std::size_t idx = 0; idx < nodePairsToCheck.size(); ++idx)
413  {
414  const auto& pair = nodePairsToCheck.at(idx);
415 
416  ARMARX_CHECK_NOT_NULL(pair.first);
417  ARMARX_CHECK_NOT_NULL(pair.second);
418 
419  if (selfCollisionAvoidanceRobot->getCollisionChecker()->checkCollision(
420  pair.first, pair.second))
421  {
422  collision = true;
423  lastCollisionPairIndex = idx;
424  ARMARX_WARNING << "Self collision checker: COLLISION: '"
425  << pair.first->getName() << "' and '"
426  << pair.second->getName() << "'";
427  _module<Units>().getEmergencyStopMaster()->setEmergencyStopState(
428  EmergencyStopState::eEmergencyStopActive);
429  // since at least one of the NJoint-Controllers is going to cause a collision, we just kick them all.
430  _module<ControlThreadDataBuffer>().setActivateControllersRequest({});
431  break;
432  }
433  }
434  if (!collision)
435  {
436  ARMARX_VERBOSE << deactivateSpam()
437  << "Self collision checker: no collision found between the "
438  << nodePairsToCheck.size() << " pairs";
439  }
440  }
441 
442  //sleep remaining
443  const auto duration = metronome.waitForNextTick();
444 
445  if(not duration.isPositive())
446  {
447  ARMARX_WARNING << deactivateSpam(10) <<
448  "Self collision checking took too long. "
449  "Exceeding time budget by " << duration.toMilliSecondsDouble() << "ms.";
450  }
451  }
452  }
453 
454  void
455  SelfCollisionChecker::_preFinishRunning()
456  {
457  throwIfInControlThread(BOOST_CURRENT_FUNCTION);
458  ARMARX_INFO << "Stopping Self Collision Avoidance.";
459  if (selfCollisionAvoidanceThread.joinable())
460  {
461  selfCollisionAvoidanceThread.join();
462  }
463  }
464 } // namespace armarx::RobotUnitModule
armarx::RobotUnitModule::ModuleBase::isShuttingDown
bool isShuttingDown() const
Returns whether the RobotUnit is shutting down.
Definition: RobotUnitModuleBase.h:647
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:180
RobotUnitModuleUnits.h
armarx::VariantType::Float
const VariantTypeId Float
Definition: Variant.h:918
armarx::RobotUnitModule::SelfCollisionChecker::setSelfCollisionAvoidanceDistance
void setSelfCollisionAvoidanceDistance(Ice::Float distance, const Ice::Current &=Ice::emptyCurrent) override
Sets the minimal distance (mm) between a configured pair of bodies to 'distance'.
Definition: RobotUnitModuleSelfCollisionChecker.cpp:183
NJointControllerBase.h
OnScopeExit.h
ARMARX_CHECK_NOT_NULL
#define ARMARX_CHECK_NOT_NULL(ptr)
This macro evaluates whether ptr is not null and if it turns out to be false it will throw an Express...
Definition: ExpressionException.h:206
armarx::Split
std::vector< std::string > Split(const std::string &source, const std::string &splitBy, bool trimElements=false, bool removeEmptyElements=false)
Definition: StringHelperTemplates.h:35
ARMARX_CHECK_GREATER
#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...
Definition: ExpressionException.h:116
ARMARX_ON_SCOPE_EXIT
#define ARMARX_ON_SCOPE_EXIT
Executes given code when the enclosing scope is left.
Definition: OnScopeExit.h:112
armarx::RobotUnitModule::SelfCollisionChecker::isSelfCollisionCheckEnabled
bool isSelfCollisionCheckEnabled(const Ice::Current &=Ice::emptyCurrent) const override
Returns whether the frequency of self collision checks is above 0.
Definition: RobotUnitModuleSelfCollisionChecker.cpp:314
RobotUnitModuleSelfCollisionChecker.h
FLOOR_OBJ_STR
#define FLOOR_OBJ_STR
Definition: RobotUnitModuleSelfCollisionChecker.cpp:44
RobotUnitModuleRobotData.h
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:523
armarx::ctrlutil::a
double a(double t, double a0, double j)
Definition: CtrlUtil.h:45
RobotUnitModuleControlThread.h
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:177
RobotUnitModuleControlThreadDataBuffer.h
Metronome.h
armarx::RobotUnitModule::SelfCollisionChecker::getSelfCollisionAvoidanceDistance
float getSelfCollisionAvoidanceDistance(const Ice::Current &=Ice::emptyCurrent) const override
Returns the minimal distance (mm) between a pair of bodies.
Definition: RobotUnitModuleSelfCollisionChecker.cpp:328
ARMARX_ERROR
#define ARMARX_ERROR
Definition: Logging.h:189
armarx::to_string
const std::string & to_string(const std::string &s)
Definition: StringHelpers.h:40
armarx::RobotUnitModule::SelfCollisionChecker::getSelfCollisionAvoidanceFrequency
float getSelfCollisionAvoidanceFrequency(const Ice::Current &=Ice::emptyCurrent) const override
Returns the frequency of self collision checks.
Definition: RobotUnitModuleSelfCollisionChecker.cpp:321
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
VAROUT
#define VAROUT(x)
Definition: StringHelpers.h:182
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
armarx::RobotUnitModule::ModuleBase::throwIfInControlThread
void throwIfInControlThread(const std::string &fnc) const
Throws if the current thread is the ControlThread.
Definition: RobotUnitModuleBase.cpp:416
scene3D::SceneObjectPtr
boost::intrusive_ptr< SceneObject > SceneObjectPtr
Definition: PointerDefinitions.h:40
armarx::Logging::deactivateSpam
SpamFilterDataPtr deactivateSpam(float deactivationDurationSec=10.0f, const std::string &identifier="", bool deactivate=true) const
disables the logging for the current line for the given amount of seconds.
Definition: Logging.cpp:92
distance
double distance(const Point &a, const Point &b)
Definition: point.hpp:88
armarx::core::time::Frequency::Hertz
static Frequency Hertz(std::int64_t hertz)
Definition: Frequency.cpp:23
armarx::RobotUnitModule
Definition: ControlDevice.h:34
Logging.h
min
T min(T t1, T t2)
Definition: gdiam.h:42
ARMARX_CHECK_EQUAL
#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...
Definition: ExpressionException.h:130
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
armarx::RobotUnitModule::SelfCollisionChecker::setSelfCollisionAvoidanceFrequency
void setSelfCollisionAvoidanceFrequency(Ice::Float freq, const Ice::Current &=Ice::emptyCurrent) override
Sets the frequency of self collision checks.
Definition: RobotUnitModuleSelfCollisionChecker.cpp:302