SelectArm.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2014-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5  *
6  * ArmarX is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License version 2 as
8  * published by the Free Software Foundation.
9  *
10  * ArmarX is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  *
18  * @package RobotSkillTemplates::BringObjectGroup
19  * @author Mirko Waechter ( mirko dot waechter at kit dot edu )
20  * @date 2015
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 
25 #include "SelectArm.h"
26 
28 #include <VirtualRobot/Robot.h>
29 #include <VirtualRobot/RobotNodeSet.h>
30 #include <VirtualRobot/Grasping/GraspSet.h>
31 #include <RobotAPI/interface/core/FramedPoseBase.h>
38 
39 #include <cmath>
40 
41 using namespace armarx;
42 using namespace BringObjectGroup;
43 
44 // DO NOT EDIT NEXT LINE
45 SelectArm::SubClassRegistry SelectArm::Registry(SelectArm::GetName(), &SelectArm::CreateInstance);
46 
47 
48 
50  XMLStateTemplate<SelectArm>(stateData), SelectArmGeneratedBase<SelectArm>(stateData)
51 {
52 }
53 
54 bool SelectArm::checkForCollision(Vector3Ptr targetPlatformPose)
55 {
56  // use simox for collision check
57  // BringObjectGroupStatechartContext* c = getContext<BringObjectGroupStatechartContext>();
58  // c->getPathPlanner()->
59  return true;
60 }
61 
62 int getClosestTCP(FramedPosePtr localObjectPose, BringObjectGroupStatechartContext* c, const std::vector<std::string>& memoryNames, const std::vector<std::string>& chains)
63 {
64  int closestChainId = -1;
65  float minDistance = std::numeric_limits<float>::max();
66  ARMARX_CHECK_EXPRESSION(chains.size() == memoryNames.size());
67 
68  for (size_t i = 0; i < chains.size(); i++)
69  {
70  std::string chain = chains[i];
71  auto set = c->getRobot()->getRobotNodeSet(chain);
72  auto distance = (set->getTCP()->getPositionInRootFrame() - localObjectPose->toEigen().block<3, 1>(0, 3)).norm();
73  ARMARX_VERBOSE_S << VAROUT(distance) << VAROUT(minDistance) << VAROUT(i);
74 
75  if (distance < minDistance)
76  {
77  minDistance = distance;
78  closestChainId = i;
79  }
80  }
81 
82  return closestChainId;
83 }
84 
86 {
87 
88  // put your user code for the enter-point here
89  // execution time should be short (<100ms)
90  BringObjectGroupStatechartContext* c = getContext<BringObjectGroupStatechartContext>();
91 
92  auto instance = in.getObjectInstanceToGraspChannel();
93  FramedPositionPtr position = instance->get<FramedPosition>("position");
94  FramedOrientationPtr orientation = instance->get<FramedOrientation>("orientation");
95  FramedPosePtr globalObjectPose = new FramedPose(orientation->toEigen(), position->toEigen(), position->getFrame(), position->agent);
96 
97  FramedPosePtr objectPoseRootFrame;
98 
99  objectPoseRootFrame = FramedPosePtr::dynamicCast(globalObjectPose->clone());
100  objectPoseRootFrame->changeFrame(c->getRobot(), c->getRobot()->getRootNode()->getName());
101 
102  // memoryx::ChannelRefBaseSequence instances = c->getObjectMemoryObserverProxy()->getObjectInstances(in.getObjectToGraspChannel());
103  if (in.isPreselectedKinematicChainSet() && in.isPreselectedMemoryHandNameSet())
104  {
105  out.setSelectedKinematicChain(in.getPreselectedKinematicChain());
106  out.setSelectedMemoryHandName(in.getPreselectedMemoryHandName());
107  }
108  else if (in.isKinematicChainsSet() && in.isMemoryHandNamesSet())
109  {
110 
111 
112  ARMARX_IMPORTANT << VAROUT(*objectPoseRootFrame);
113  auto chains = in.getKinematicChains();
114  auto memoryNames = in.getMemoryHandNames();
115  int closestChainId = getClosestTCP(objectPoseRootFrame, c, memoryNames, chains);
116 
117  out.setSelectedKinematicChain(chains.at(closestChainId));
118  out.setSelectedMemoryHandName(memoryNames.at(closestChainId));
119  }
120  else
121  {
122  ARMARX_ERROR << "Either PreselectedKinematicChainSet and PreselectedMemoryHandNameSet or KinematicChainsSet and MemoryHandNamesSet parameter must be set.";
123  emitFailure();
124  return;
125  }
126 
127  ARMARX_IMPORTANT << "Selected Memory Name is: " << out.getSelectedMemoryHandName();
128  out.setSelectedTCP(c->getRobot()->getRobotNodeSet(out.getSelectedKinematicChain())->getTCP()->getName());
129  ARMARX_IMPORTANT << "Selected TCP is: " << out.getSelectedTCP();
130  // get grasp definition
131  std::string objectName = in.getObjectInstanceToGraspChannel()->getDataField("className")->getString();
132 
133  memoryx::PersistentObjectClassSegmentBasePrx classesSegmentPrx = c->getPriorKnowledgeProxy()->getObjectClassesSegment();
134  memoryx::CommonStorageInterfacePrx databasePrx = c->getPriorKnowledgeProxy()->getCommonStorage();
135  memoryx::GridFileManagerPtr fileManager(new memoryx::GridFileManager(databasePrx));
136  memoryx::EntityBasePtr entity = classesSegmentPrx->getEntityByName(objectName);
137  memoryx::ObjectClassPtr objectClass = memoryx::ObjectClassPtr::dynamicCast(entity);
138  memoryx::EntityWrappers::SimoxObjectWrapperPtr simoxWrapper = objectClass->addWrapper(new memoryx::EntityWrappers::SimoxObjectWrapper(fileManager));
139  VirtualRobot::ManipulationObjectPtr mo = simoxWrapper->getManipulationObject();
140 
141  VirtualRobot::GraspSetPtr graspSet = mo->getGraspSet(out.getSelectedTCP());
142 
143  auto findGrasp = [](VirtualRobot::GraspSetPtr graspSet, const Ice::StringSeq & requiredInfixes, const Ice::StringSeq & exludedInfixes)
144  {
145  if (graspSet)
146  {
147  auto grasps = graspSet->getGrasps();
148 
149  for (VirtualRobot::GraspPtr grasp : grasps)
150  {
151  std::string graspName = grasp->getName();
152  bool found = true;
153  for (const auto& infix : requiredInfixes)
154  {
155  found &= Contains(graspName, infix, true);
156  }
157  for (const auto& infix : exludedInfixes)
158  {
159  found &= !Contains(graspName, infix, true);
160  }
161  if (found)
162  {
163  return graspName;
164  }
165  }
166  }
167  return std::string("");
168  };
169 
170  if (graspSet)
171  {
172 
173  std::string preposeName;
174  Ice::StringSeq infixes;
175  if (in.isGraspNameInfixSet())
176  {
177  infixes.push_back(in.getGraspNameInfix());
178  }
179  infixes.push_back({"pre"});
180 
181  preposeName = findGrasp(graspSet, infixes, Ice::StringSeq());
182  if (!preposeName.empty())
183  {
184  out.setGraspPreposeName(preposeName);
185  }
186  else
187  {
188  infixes.clear();
189  infixes.push_back({"pre"}); // now without infix..
190  preposeName = findGrasp(graspSet, infixes, Ice::StringSeq());
191  if (!preposeName.empty())
192  {
193  out.setGraspPreposeName(preposeName);
194  }
195  }
196 
197  infixes.clear();
198  if (in.isGraspNameInfixSet())
199  {
200  infixes.push_back(in.getGraspNameInfix());
201  }
202  infixes.push_back({"grasp"});
203  std::string graspName = findGrasp(graspSet, infixes, {"pre"});
204  if (!graspName.empty())
205  {
206  out.setGraspName(graspName);
207  }
208  else
209  {
210  infixes.clear();
211  infixes.push_back({"grasp"});// now without infix..
212  graspName = findGrasp(graspSet, infixes, {"pre"});
213  if (!graspName.empty())
214  {
215  out.setGraspName(graspName);
216  }
217  }
218 
219 
220  auto getGraspNames = [](VirtualRobot::GraspSetPtr graspSet)
221  {
222  Ice::StringSeq graspNames;
223  for (VirtualRobot::GraspPtr& g : graspSet->getGrasps())
224  {
225  graspNames.push_back(g->getName());
226  };
227  return graspNames;
228  };
229 
230  if (!out.isGraspPreposeNameSet())
231  {
232 
233  ARMARX_ERROR << "could not find any matching pre pose for " << out.getSelectedTCP() << " for object " << objectName << " - Found Grasps are: " << getGraspNames(graspSet);
234  out.setGraspPreposeName("");
235  out.setGraspName("");
236  emitFailure();
237  return;
238 
239  }
240 
241  if (!out.isGraspNameSet())
242  {
243  ARMARX_ERROR << "could not find any matching grasp pose for " << out.getSelectedTCP() << " for object " << objectName << " - Found Grasps are: " << getGraspNames(graspSet);
244  out.setGraspPreposeName("");
245  out.setGraspName("");
246  emitFailure();
247  return;
248 
249  }
250 
251  }
252  else
253  {
254  ARMARX_ERROR << "graspSet Ptr NULL - Could not find grasp set for tcp " << out.getSelectedTCP() << " for object " << objectName;
255  emitFailure();
256  return;
257  }
258 
259 
260  Eigen::Vector3f tcpPosition = c->getRobot()->getRobotNodeSet(out.getSelectedKinematicChain())->getTCP()->getPositionInRootFrame();
261  if (tcpPosition[0] < 0) // Left Hand
262  {
263  out.setPregraspArmConfig(in.getPregraspArmConfigLeft());
264  }
265  else
266  {
267  out.setPregraspArmConfig(in.getPregraspArmConfigRight());
268  }
269 
270 
271  if (in.getUsePlatform())
272  {
273 
274  Eigen::Vector3f objPosRootFrame = Vector3Ptr::dynamicCast(objectPoseRootFrame->position)->toEigen();
275 
276  ARMARX_INFO << VAROUT(*objectPoseRootFrame);
277  Eigen::Vector3f newPlatformPos = objPosRootFrame;
278  Vector3Ptr offset;
279 
280  if (tcpPosition[0] < 0) // Left Hand
281  {
282  offset = in.getPlatformToObjectOffsetLeft();
283  }
284  else
285  {
286  offset = in.getPlatformToObjectOffsetRight();
287  }
288 
289  newPlatformPos[0] += offset->x;
290  newPlatformPos[1] += offset->y;
291 
292  if (fabs(newPlatformPos[1]) > 500)
293  {
294  ARMARX_ERROR << "Target platform pose is too far away: " << newPlatformPos;
295  }
296 
297  ARMARX_INFO << VAROUT(newPlatformPos);
298  ARMARX_INFO << "rootnode pose: " << c->getRobot()->getRootNode()->getGlobalPose();
299  Eigen::Vector3f newGlobalPlatformPos = c->getRobot()->getRootNode()->toGlobalCoordinateSystemVec(newPlatformPos);
300  Eigen::Matrix3f rotMat = c->getRobot()->getRootNode()->getGlobalPose().block<3, 3>(0, 0);
301 
302  ARMARX_INFO << "Root Node: " << c->getRobot()->getRootNode()->getName();
303  ARMARX_INFO << c->getRobot()->getRootNode()->getGlobalPose().block<3, 3>(0, 0);
304 
305  Eigen::Vector3f x = rotMat * Eigen::Vector3f::UnitX();
306  newGlobalPlatformPos[2] = atan2(x[1], x[0]);
307  std::vector<Vector3Ptr> pose;
308 
309  // If necessary, clamp the platform motion to the defined constraints
310  Eigen::Vector3f platformPos = c->getRobot()->getRootNode()->getGlobalPose().block<3, 1>(0, 3);
311 
312  if (in.isMaxPlatformMotionXSet() && fabs(newGlobalPlatformPos[0] - platformPos[0]) > in.getMaxPlatformMotionX())
313  {
314  newGlobalPlatformPos[0] = platformPos[0] + std::copysign(in.getMaxPlatformMotionX(), newGlobalPlatformPos[0] - platformPos[0]);
315  ARMARX_WARNING << "Platform motion clamped to maximum in X direction: " << newGlobalPlatformPos[0];
316  }
317 
318  if (in.isMaxPlatformMotionYSet() && fabs(newGlobalPlatformPos[1] - platformPos[1]) > in.getMaxPlatformMotionY())
319  {
320  newGlobalPlatformPos[1] = platformPos[1] + std::copysign(in.getMaxPlatformMotionY(), newGlobalPlatformPos[1] - platformPos[1]);
321  ARMARX_WARNING << "Platform motion clamped to maximum in Y direction: " << newGlobalPlatformPos[1];
322  }
323 
324  Vector3Ptr newPlatformVec = new Vector3(newGlobalPlatformPos);
325 
326  if (!checkForCollision(newPlatformVec))
327  {
328  ARMARX_ERROR << "Collision detected";
329  emitFailure();
330  return;
331  }
332  else
333  {
334  pose.push_back(newPlatformVec);
335  ARMARX_INFO << VAROUT(*newPlatformVec);
336  out.setPlatformTargetPose(pose);
337  emitArmSelectedMovePlatform();
338  }
339  }
340  else
341  {
342  emitArmSelected();
343  }
344 }
345 
346 
348 {
349  // put your user code for the exit point here
350  // execution time should be short (<100ms)
351 
352 }
353 
354 
355 // DO NOT EDIT NEXT FUNCTION
357 {
358  return XMLStateFactoryBasePtr(new SelectArm(stateData));
359 }
360 
ARMARX_IMPORTANT
#define ARMARX_IMPORTANT
Definition: Logging.h:183
armarx::VariantType::FramedPose
const VariantTypeId FramedPose
Definition: FramedPose.h:37
armarx::Contains
bool Contains(const ContainerType &container, const ElementType &searchElement)
Definition: algorithm.h:295
BringObjectGroupStatechartContext.h
armarx::XMLStateConstructorParams
Definition: XMLState.h:50
GridFileManager.h
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:43
armarx::BringObjectGroup::SelectArm::onEnter
void onEnter() override
Definition: SelectArm.cpp:85
ObjectClass.h
armarx::BringObjectGroup::SelectArm::checkForCollision
bool checkForCollision(Vector3Ptr targetPlatformPose)
Definition: SelectArm.cpp:54
armarx::BringObjectGroup::SelectArm::CreateInstance
static XMLStateFactoryBasePtr CreateInstance(XMLStateConstructorParams stateData)
Definition: SelectArm.cpp:356
StringHelpers.h
IceInternal::Handle< Vector3 >
armarx::XMLStateTemplate
Class for legacy to stay compatible with old statecharts.
Definition: XMLState.h:137
armarx::BringObjectGroup::BringObjectGroupStatechartContext
Definition: BringObjectGroupStatechartContext.h:77
FramedPose.h
armarx::BringObjectGroup::SelectArm::onExit
void onExit() override
Definition: SelectArm.cpp:347
armarx::FramedPosition
The FramedPosition class.
Definition: FramedPose.h:142
getClosestTCP
int getClosestTCP(FramedPosePtr localObjectPose, BringObjectGroupStatechartContext *c, const std::vector< std::string > &memoryNames, const std::vector< std::string > &chains)
Definition: SelectArm.cpp:62
max
T max(T t1, T t2)
Definition: gdiam.h:48
armarx::BringObjectGroup::SelectArm::Registry
static SubClassRegistry Registry
Definition: SelectArm.h:45
ARMARX_ERROR
#define ARMARX_ERROR
Definition: Logging.h:189
armarx::FramedOrientation
The FramedOrientation class.
Definition: FramedPose.h:199
memoryx::EntityWrappers::SimoxObjectWrapper
SimoxObjectWrapper offers a simplified access to the Simox ManipulationObject (i.e visualization,...
Definition: SimoxObjectWrapper.h:46
armarx::XMLStateFactoryBasePtr
IceInternal::Handle< XMLStateFactoryBase > XMLStateFactoryBasePtr
Definition: XMLState.h:65
SimoxObjectWrapper.h
GfxTL::Matrix3f
MatrixXX< 3, 3, float > Matrix3f
Definition: MatrixXX.h:600
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::BringObjectGroup::SelectArm::SelectArm
SelectArm(XMLStateConstructorParams stateData)
Definition: SelectArm.cpp:49
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
memoryx::GridFileManagerPtr
std::shared_ptr< GridFileManager > GridFileManagerPtr
Definition: AbstractEntityWrapper.h:32
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
memoryx::KBM::Vector3
Eigen::Vector3d Vector3
Definition: kbm.h:41
memoryx::GridFileManager
GridFileManager provides utility functions for working with files in Mongo GridFS and links to them s...
Definition: GridFileManager.h:42
MemoryXTypesObjectFactories.h
ARMARX_VERBOSE_S
#define ARMARX_VERBOSE_S
Definition: Logging.h:200
distance
double distance(const Point &a, const Point &b)
Definition: point.hpp:88
SelectArm.h
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
armarx::BringObjectGroup::SelectArm
Definition: SelectArm.h:31