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