SimoxCSpace.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2011-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 RobotComponents
19  * @author Raphael Grimm ( raphael dot grimm at kit dot edu )
20  * @date 2015
21  * @copyright http://www.gnu.org/licenses/gpl.txt
22  * GNU General Public License
23  */
24 
25 #include <exception>
26 #include <algorithm>
27 #include <cmath>
28 #include <unordered_map>
29 #include <unordered_set>
30 
31 #include <MotionPlanning/CSpace/CSpaceSampled.h>
32 
39 #include <VirtualRobot/XML/RobotIO.h>
40 #include <VirtualRobot/RobotNodeSet.h>
41 #include <VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.h>
42 #include <VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h>
48 #include <VirtualRobot/CollisionDetection/CDManager.h>
49 #include <VirtualRobot/RobotFactory.h>
51 #include "../util/Metrics.h"
52 #include "SimoxCSpace.h"
53 
54 namespace armarx
55 {
57  {
58  struct Initializer
59  {
60  //this is not threadsave
61  Initializer()
62  {
63  //this is checked by SoDB::init()
64  //if (!SoDB::isInitialized())
65  //{
66  SoDB::init();
67  //}
68  }
69 
70  bool doStuff()
71  {
72  return true;
73  }
74  };
75  static Initializer init;
76  return init.doStuff(); //suppresses unused variable
77  }
78 
79 
80 
81  SimoxCSpace::SimoxCSpace(memoryx::CommonStorageInterfacePrx commonStoragePrx, bool loadVisualizationModel, float stationaryObjectMargin):
82  loadVisualizationModel {loadVisualizationModel}
83  {
84  this->stationaryObjectMargin = stationaryObjectMargin;
85  //check eigen layout for mapped vectors
87  ARMARX_CHECK_EXPRESSION(a.data() + 0 == &a(0, 0));
88  ARMARX_CHECK_EXPRESSION(a.data() + 1 == &a(1, 0));
89  ARMARX_CHECK_EXPRESSION(a.data() + 2 == &a(2, 0));
90  ARMARX_CHECK_EXPRESSION(a.data() + 3 == &a(3, 0));
91  ARMARX_CHECK_EXPRESSION(a.data() + 4 == &a(0, 1));
92  ARMARX_CHECK_EXPRESSION(a.data() + 5 == &a(1, 1));
93  ARMARX_CHECK_EXPRESSION(a.data() + 6 == &a(2, 1));
94  ARMARX_CHECK_EXPRESSION(a.data() + 7 == &a(3, 1));
95  ARMARX_CHECK_EXPRESSION(a.data() + 8 == &a(0, 2));
96  ARMARX_CHECK_EXPRESSION(a.data() + 9 == &a(1, 2));
97  ARMARX_CHECK_EXPRESSION(a.data() + 10 == &a(2, 2));
98  ARMARX_CHECK_EXPRESSION(a.data() + 11 == &a(3, 2));
99  ARMARX_CHECK_EXPRESSION(a.data() + 12 == &a(0, 3));
100  ARMARX_CHECK_EXPRESSION(a.data() + 13 == &a(1, 3));
101  ARMARX_CHECK_EXPRESSION(a.data() + 14 == &a(2, 3));
102  ARMARX_CHECK_EXPRESSION(a.data() + 15 == &a(3, 3));
103 
104  commonStorage = commonStoragePrx;
105 
106  if (!commonStorage)
107  {
108  ARMARX_ERROR_S << "SimoxCSpace ctor: commonStorage == null";
109  throw std::invalid_argument {"SimoxCSpace ctor: commonStorage == null"};
110  }
111  }
112 
113  CSpaceBasePtr SimoxCSpace::clone(bool loadVisualizationModel)
114  {
115  TIMING_START(SimoxCSpaceClone);
116  SimoxCSpacePtr cloned = new SimoxCSpace {commonStorage, loadVisualizationModel, stationaryObjectMargin};
117 
118  for (const auto& obj : stationaryObjects)
119  {
120  cloned->addStationaryObject(obj);
121  }
122  cloned->agentInfo = agentInfo;
124  cloned->initAgent();
125  TIMING_END(SimoxCSpaceClone);
126  return cloned;
127  }
128 
129  Saba::CSpaceSampledPtr SimoxCSpace::createSimoxCSpace() const
130  {
131 
132  // ARMARX_INFO << "using kinematic chain set: " << agentInfo.kinemaicChainNames.at(0);
133  VirtualRobot::CDManagerPtr tmpCd = VirtualRobot::CDManagerPtr(new VirtualRobot::CDManager(cd));
134 
135  // for (VirtualRobot::SceneObjectSetPtr& set : tmpCd->getSceneObjectSets())
136  // {
137  // ARMARX_INFO << "set size: " << set->getSize();
138  // }
139  Saba::CSpaceSampledPtr result(new Saba::CSpaceSampled(agentSceneObj, tmpCd,
140  agentInfo.kinemaicChainNames.size() > 0 ? agentSceneObj->getRobotNodeSet(agentInfo.kinemaicChainNames.at(0)) : VirtualRobot::RobotNodeSetPtr()));
141  return result;
142  }
143 
144  //from SimoxCSpace
145  void SimoxCSpace::addStationaryObject(const StationaryObject& obj, const Ice::Current&)
146  {
147  ARMARX_CHECK_EXPRESSION(obj.objectPose);
148  ARMARX_CHECK_EXPRESSION(obj.objectClassBase);
149  stationaryObjects.emplace_back(obj);
150  }
151 
152  void SimoxCSpace::setStationaryObjects(const StationaryObjectList& objList)
153  {
154  stationaryObjects = objList;
155  }
156 
157  void SimoxCSpace::setAgent(const AgentPlanningInformation& agentInfo, const Ice::Current&)
158  {
159  this->agentInfo = agentInfo;
160  initAgent();
161  }
162 
163  void SimoxCSpace::setConfig(const float*& it)
164  {
165  //stationary agents joints
166  NameValueMap jointValues;
167  for (auto agentJoint : agentJoints)
168  {
169  jointValues[agentJoint->getName()] = *it;
170  agentJoint->setJointValueNoUpdate(*(it++));
171  }
172  // ARMARX_VERBOSE << agentSceneObj.get() << " " << agentSceneObj->getUpdateVisualizationStatus() << " Setting joint values to new values: " << jointValues;
173  agentSceneObj->applyJointValues();
174  }
175 
177  const ::std::pair<const Ice::Float*, const Ice::Float*>& cfg,
178  const Ice::Current&
179  )
180  {
181  ARMARX_CHECK_EXPRESSION(std::distance(cfg.first, cfg.second) == getDimensionality());
182  const Ice::Float* it;
183  it = cfg.first;
184 
185  setConfig(it);
186 
187  ARMARX_CHECK_EXPRESSION(cfg.second == it);
188  //check
189  return !cd.isInCollision();
190  }
191 
192  void SimoxCSpace::initCollisionTest(const Ice::Current&)
193  {
194  if (isInitialized)
195  {
196  ARMARX_DEBUG_S << "was already initialized SimoxCSpace " << this;
197  return;
198  }
199  TIMING_START(CSpaceInit);
200  //init file manager
202  fileManager.reset(new memoryx::GridFileManager(commonStorage));
203 
204  //just to be save (may crash otherwise)
205  TIMING_START(CSpaceInit_ensureCoinIsInitialized)
207  TIMING_END(CSpaceInit_ensureCoinIsInitialized)
208 
209  isInitialized = true;
210  TIMING_START(CSpaceInit_initAgent)
211  initAgent();
212  TIMING_END(CSpaceInit_initAgent)
213  TIMING_START(CSpaceInit_initStationaryObjects)
215  TIMING_END(CSpaceInit_initStationaryObjects)
216  agentSceneObj->setJointValues(agentInfo.initialJointValues);
217  ARMARX_CHECK_EXPRESSION(stationaryObjectSet->getSize() == stationaryObjects.size());
218  TIMING_END(CSpaceInit);
219  }
220 
222  {
223  stationaryObjectSet.reset(new VirtualRobot::SceneObjectSet {"StationaryObjectSet", cd.getCollisionChecker()});
224  if (stationaryObjects.size() || stationaryPlanes.size())
225  {
227  for (std::size_t i = 0; i < stationaryObjects.size(); ++i)
228  {
230  const auto& obj = stationaryObjects.at(i);
231  auto&& sceneObj = getMovedSimoxManipulatorObject(obj.objectClassBase, obj.objectPose, fileManager);
232  //deactivate visu since it is not needed and moving visu is as expensive as moving the col mod
233  sceneObj->setUpdateVisualization(false);
234  stationaryObjectSet->addSceneObject(std::move(sceneObj));
235  }
236 
237  for (auto& plane : stationaryPlanes)
238  {
239  VirtualRobot::CoinVisualizationNodePtr visu(new VirtualRobot::CoinVisualizationNode((SoNode*)VirtualRobot::CoinVisualizationFactory::CreatePolygonVisualization(plane)));
240  VirtualRobot::SceneObjectPtr s(new VirtualRobot::SceneObject("Plane", visu,
241  VirtualRobot::CollisionModelPtr(new VirtualRobot::CollisionModel(visu)),
242  VirtualRobot::SceneObject::Physics {}, cd.getCollisionChecker()));
243 
244  stationaryObjectSet->addSceneObject(s);
245  }
246  if (stationaryObjectSet->getSize())
247  {
248  ARMARX_INFO << "SceneObjects: " << armarx::transform(stationaryObjectSet->getSceneObjects(), +[](VirtualRobot::SceneObjectPtr const & obj)
249  {
250  return obj->getName();
251  });
252  ARMARX_CHECK_EXPRESSION(!cd.hasSceneObjectSet(stationaryObjectSet));
253  cd.addCollisionModel(stationaryObjectSet);
254  }
255  }
256 
257  }
258 
260  {
261  //move agent
262  if (agentInfo.agentPose) //if none is set the default pose is used
263  {
264  agentData.agent->setGlobalPose(armarx::PosePtr::dynamicCast(agentInfo.agentPose)->toEigen());
265  }
266 
267  agentSceneObj = std::move(agentData.agent);
268  //deactivate visu since it is not needed and moving visu is as expensive as moving the col mod
269  agentSceneObj->setUpdateVisualization(false);
270 
271  const std::size_t numberOfJoints = agentData.joints.size();
272  agentJoints.clear();
273  agentJoints.reserve(numberOfJoints);
274  std::move(agentData.joints.begin(), agentData.joints.end(), std::back_inserter(agentJoints));
275 
276  if (isInitialized)
277  {
278  cd = VirtualRobot::CDManager {agentSceneObj->getCollisionChecker()};
279  for (auto& colMod : agentData.collisionSets)
280  {
281  cd.addCollisionModel(std::move(colMod));
282  }
283  // cd.addCollisionModel(stationaryObjectSet);
284  }
285  }
286 
288  {
289  //load agent
291  {
292  auto packageNames = agentInfo.agentProjectNames;
293  if (!agentInfo.agentProjectName.empty())
294  {
295  packageNames.emplace_back(agentInfo.agentProjectName);
296  }
297 
298  std::string absoluteFilePath;
299  std::vector<std::string> paths;
300  for (const auto& package : packageNames)
301  {
302  armarx::CMakePackageFinder packageFinder(package);
303  auto pathStr = packageFinder.getDataDir();
304  std::vector<std::string> packagePaths = Split(pathStr, ";,", false, true);
305 
306  paths.reserve(paths.size() + packagePaths.size());
307  std::move(packagePaths.begin(), packagePaths.end(), std::back_inserter(paths));
308  }
309 
310  if (!armarx::ArmarXDataPath::getAbsolutePath(agentInfo.agentRelativeFilePath, absoluteFilePath, paths))
311  {
312  std::stringstream s;
313  s << "could not find file " << agentInfo.agentRelativeFilePath << " in project " << agentInfo.agentProjectName;
314  ARMARX_ERROR_S << s.str();
315  throw std::invalid_argument {s.str()};
316  }
317  // static std::map<std::pair<VirtualRobot::RobotIO::RobotDescription, std::string>, VirtualRobot::RobotPtr> agentCache;
318  // static armarx::Mutex agentCacheMutex;
319  // ScopedLock lock(agentCacheMutex);
320  auto loadType = isInitialized ?//the cspace is initializing => load models
321  (
324  VirtualRobot::RobotIO::eCollisionModel
325  ) : VirtualRobot::RobotIO::eStructure;
326  auto pair = std::make_pair(loadType, absoluteFilePath);
327  // auto it = robotCache.find(pair);
328  if (!robotCache.hasObject(pair))
329  {
330  agent = VirtualRobot::RobotIO::loadRobot(
331  absoluteFilePath,
332  loadType
333  );
334 
335  ARMARX_DEBUG << "Robot Cache MISS! Path: " << absoluteFilePath << " load type: " << (int)loadType;
336  RobotPoolPtr pool(new RobotPool(agent, 2));
337  agent = pool->getRobot();
338  robotCache.insertObject(pair, pool);
339  // agentCache.insert(std::make_pair(pair, agent)).first;
340  }
341  else
342  {
343  ARMARX_DEBUG << "Robot Cache hit! load type: " << (int)loadType;
344  agent = robotCache.getCacheObject(pair)->getRobot();
345  }
346 
347  // auto loadType = isInitialized ?//the cspace is initializing => load models
348  // (
349  // loadVisualizationModel ?
350  // VirtualRobot::RobotIO::eFull :
351  // VirtualRobot::RobotIO::eCollisionModel
352  // ) : VirtualRobot::RobotIO::eStructure;
353  // agent = VirtualRobot::RobotIO::loadRobot(
354  // absoluteFilePath,
355  // loadType
356  // );
357  // ARMARX_VERBOSE << "Loading robot! Path: " << absoluteFilePath << " load type: " << (int)loadType << " addr: " << agent.get();
358  if (!agent)
359  {
360  std::stringstream s;
361  s << "Can't load agent from: " << absoluteFilePath;
362  ARMARX_ERROR_S << s.str();
363  throw std::invalid_argument {s.str()};
364  }
365  }
366 
367  return getAgentDataFromRobot(agent);
368  }
369 
371  {
372  AgentData data;
373 
374  ARMARX_CHECK_EXPRESSION(robotPtr);
375  data.agent = robotPtr;
376 
377  if (isInitialized)
378  {
380  //attach objects
381  //use the map to track this association
382  std::unordered_map<std::string, std::vector<VirtualRobot::RobotNodePtr>> toCollSetAssociatedObjects;
383  toCollSetAssociatedObjects.reserve(agentInfo.collisionSetNames.size());
384 
385  for (std::size_t i = 0; i < agentInfo.attachedObjects.size(); ++i)
386  {
387  const auto& attached = agentInfo.attachedObjects.at(i);
388  auto&& sceneObj = getSimoxManipulatorObject(attached.objectClassBase, fileManager, false, robotPtr->getCollisionChecker());
389  std::stringstream sceneObjName;
390  sceneObjName << "attached_obj_" << i << "_" << sceneObj->getName();
391  sceneObj->setName(sceneObjName.str());
392 
393  //find node to attach to and attach
394  if (! data.agent->hasRobotNode(attached.attachedToRobotNodeName))
395  {
396  std::stringstream s;
397  s << "Agent " << data.agent->getName() << " has no node " << attached.attachedToRobotNodeName
398  << "to attach object " << attached.objectClassBase->getName();
399  ARMARX_ERROR_S << s.str();
400  throw std::invalid_argument {s.str()};
401  }
402 
403  VirtualRobot::RobotNodePtr nodeToAttachTo = data.agent->getRobotNode(attached.attachedToRobotNodeName);
404  VirtualRobot::RobotFactory::attach(data.agent, sceneObj, nodeToAttachTo, armarx::PosePtr::dynamicCast(attached.relativeObjectPose)->toEigen());
405 
406  //adding to cd
407  if (attached.associatedCollisionSetName.empty())
408  {
409  //add alone
410  data.collisionSets.emplace_back(new VirtualRobot::SceneObjectSet {sceneObjName.str(), data.agent->getCollisionChecker()});
411  data.collisionSets.back()->addSceneObject(data.agent->getRobotNode(sceneObjName.str()));
412  }
413  else
414  {
415  //does the set exist?
416  if (
417  std::find(
418  agentInfo.collisionSetNames.begin(),
419  agentInfo.collisionSetNames.end(),
420  attached.associatedCollisionSetName
421  )
422  == agentInfo.collisionSetNames.end()
423  )
424  {
425  std::stringstream s;
426  s << "Agent " << data.agent->getName() << " has no set " << attached.associatedCollisionSetName
427  << " to use as associated collision set for attached object " << attached.objectClassBase->getName();
428  ARMARX_ERROR_S << s.str();
429  throw std::invalid_argument {s.str()};
430  }
431  //add to set
432  toCollSetAssociatedObjects[attached.associatedCollisionSetName].emplace_back(data.agent->getRobotNode(sceneObjName.str()));
433  }
434  }
435  //get collision models
436  for (const auto& name : agentInfo.collisionSetNames)
437  {
438  if (! data.agent->hasRobotNodeSet(name))
439  {
440  std::stringstream s;
441  s << "Agent " << data.agent->getName() << " has no collision model " << name;
442  ARMARX_ERROR_S << s.str();
443  throw std::invalid_argument {s.str()};
444  }
445 
446  //add set + associated objects for cd
447  data.collisionSets.emplace_back(new VirtualRobot::SceneObjectSet {name, data.agent->getCollisionChecker()});
448  data.collisionSets.back()->addSceneObjects(data.agent->getRobotNodeSet(name));
449 
450  for (auto& obj : toCollSetAssociatedObjects[name])
451  {
452  data.collisionSets.back()->addSceneObject(std::move(obj));
453  }
454  }
455  if (!agentInfo.collisionObjectNames.empty())
456  {
457  data.collisionSets.emplace_back(new VirtualRobot::SceneObjectSet {"collisionObjects", data.agent->getCollisionChecker()});
458  for (const auto& name : agentInfo.collisionObjectNames)
459  {
460  if (! data.agent->hasRobotNode(name))
461  {
462  std::stringstream s;
463  s << "Agent " << data.agent->getName() << " has no collision model " << name;
464  ARMARX_ERROR_S << s.str();
465  throw std::invalid_argument {s.str()};
466  }
467 
468  //add set + associated objects for cd
469  data.collisionSets.back()->addSceneObject(data.agent->getRobotNode(name));
470 
471  for (auto& obj : toCollSetAssociatedObjects[name])
472  {
473  data.collisionSets.back()->addSceneObject(std::move(obj));
474  }
475  }
476  }
477  }
478 
479  //get joints
480  //some joints may be blacklisted or already added
481  std::set<std::string> blacklist(agentInfo.jointsExcludedFromPlanning.begin(), agentInfo.jointsExcludedFromPlanning.end());
482  //add kinematic chains
483  for (const auto& name : agentInfo.kinemaicChainNames)
484  {
485  if (! data.agent->hasRobotNodeSet(name))
486  {
487  std::stringstream s;
488  s << "Agent " << data.agent->getName() << " has no kinematic chain " << name;
489  ARMARX_ERROR_S << s.str();
490  throw std::invalid_argument {s.str()};
491  }
492 
493  //add chain
494  for (auto& node : * (data.agent->getRobotNodeSet(name)))
495  {
496  auto nodeIt = blacklist.find(node->getName());
497  if (nodeIt != blacklist.end())
498  {
499  continue;
500  }
501 
502  if (!(node->isTranslationalJoint() || node->isRotationalJoint()))
503  {
504  std::stringstream s;
505  s << "The node " << node->getName() << " in the kinematic chain "
506  << name << " of agent " << data.agent->getName()
507  << " is neither rotational nor tranlational";
508  ARMARX_ERROR_S << s.str();
509  throw std::invalid_argument {s.str()};
510  }
511 
512  data.joints.emplace_back(node);
513  blacklist.emplace_hint(nodeIt, node->getName());
514  }
515  }
516  //add single nodes
517  for (const auto& name : agentInfo.additionalJointsForPlanning)
518  {
519  if (!data.agent->hasRobotNode(name))
520  {
521  std::stringstream s;
522  s << "Agent " << data.agent->getName() << " has no node " << name;
523  ARMARX_ERROR_S << s.str();
524  throw std::invalid_argument {s.str()};
525  }
526  auto node = data.agent->getRobotNode(name);
527 
528  auto nodeIt = blacklist.find(node->getName());
529  if (nodeIt != blacklist.end())
530  {
531  continue;
532  }
533 
534  if (!(node->isTranslationalJoint() || node->isRotationalJoint()))
535  {
536  std::stringstream s;
537  s << "The node " << node->getName()
538  << " of agent " << data.agent->getName()
539  << " is neither rotational nor tranlational";
540  ARMARX_ERROR_S << s.str();
541  throw std::invalid_argument {s.str()};
542  }
543 
544  data.joints.emplace_back(node);
545  blacklist.emplace_hint(nodeIt, node->getName());
546  }
547  return data;
548  }
549 
550  VirtualRobot::ManipulationObjectPtr SimoxCSpace::getSimoxManipulatorObject(const memoryx::ObjectClassBasePtr& object, const memoryx::GridFileManagerPtr& fileManager, bool inflate, VirtualRobot::CollisionCheckerPtr const& colChecker) const
551  {
552  memoryx::ObjectClassPtr objectClass = memoryx::ObjectClassPtr::dynamicCast(object);
553  // static boost::mutex meshCacheMutex;
554  // static std::map<std::pair<int, std::string>, VirtualRobot::ManipulationObjectPtr> meshCache;
556  VirtualRobot::ManipulationObjectPtr mo;
557  if (!objectClass)
558  {
559  std::stringstream s;
560  s << "Can't use object class with ice id " << object->ice_id();
561  ARMARX_ERROR_S << s.str();
562  throw armarx::InvalidArgumentException {s.str()};
563  }
564  {
565  // boost::mutex::scoped_lock lock(meshCacheMutex);
566  auto pair = std::make_pair((int)(stationaryObjectMargin * 1000), object->getId());
567  auto pairZeroMargin = std::make_pair(0, object->getId());
568 
569  if (meshCache.hasObject(pair))
570  {
571  auto tmpMo = meshCache.getCacheObject(pair);
572  IceUtil::Time start = IceUtil::Time::now();
573  mo = tmpMo->clone(tmpMo->getName(), colChecker, true);
574  IceUtil::Time end = IceUtil::Time::now();
575  ARMARX_DEBUG << "mesh Cache hit for " << tmpMo->getName() << " - Cloning took " << (end - start).toMilliSeconds();
576  }
577  else
578  {
579  if (meshCache.hasObject(pairZeroMargin))
580  {
581  auto tmpMo = meshCache.getCacheObject(pairZeroMargin);
582  ARMARX_DEBUG << "mesh Cache HALFMISS - mesh inflation needed for " << tmpMo->getName();
583  mo = tmpMo->clone(tmpMo->getName(), colChecker, true);
584  }
585  else
586  {
587  sw = objectClass->addWrapper(new memoryx::EntityWrappers::SimoxObjectWrapper(fileManager, VirtualRobot::RobotIO::eCollisionModel));
588  VirtualRobot::ManipulationObjectPtr orgMo = sw->getManipulationObject();
589  ARMARX_DEBUG << "mesh Cache MISS for " << orgMo->getName();
591  std::string moName = orgMo->getName();
592  mo = orgMo->clone(moName, colChecker, true);
593  }
594  if (this->stationaryObjectMargin != 0.0f && inflate)
595  {
596  ARMARX_DEBUG << deactivateSpam(3, to_string(stationaryObjectMargin)) << "Using " << stationaryObjectMargin << " as margin";
597 
598  mo->getCollisionModel()->inflateModel(this->stationaryObjectMargin);
599  }
600  meshCache.insertObject(pair, mo);
601  }
602 
603  }
604 
605 
606  return mo;
607  }
608 
609  VirtualRobot::ManipulationObjectPtr SimoxCSpace::getMovedSimoxManipulatorObject(const memoryx::ObjectClassBasePtr& object, const PoseBasePtr& pose, memoryx::GridFileManagerPtr& fileManager) const
610  {
611  VirtualRobot::ManipulationObjectPtr mo = getSimoxManipulatorObject(object, fileManager, true, const_cast<VirtualRobot::CDManager*>(&cd)->getCollisionChecker());
612 
613  //move the object to the given position
614  const auto objectPose = armarx::PosePtr::dynamicCast(pose);
615 
616  if (!objectPose)
617  {
618  std::stringstream s;
619  s << "Can't convert pose of " << memoryx::ObjectClassPtr::dynamicCast(object)->getName() << " to armarx::Pose.";
620  ARMARX_ERROR_S << s.str();
621  throw armarx::InvalidArgumentException {s.str()};
622  }
623 
624  mo->setGlobalPose(objectPose->toEigen());
625  return mo;
626  }
627 
628  void SimoxCSpace::addObjectsFromWorkingMemory(memoryx::WorkingMemoryInterfacePrx workingMemoryPrx, const std::vector<std::string>& excludedInstancesIds /* = std::vector<std::string>() */)
629  {
630  TIMING_START(LoadFromWM);
631  //pass all objects from the scene to the cspace
632  auto objInstPrx = workingMemoryPrx->getObjectInstancesSegment();
633  const auto objs = objInstPrx->getAllEntities();
634  auto agentSeg = workingMemoryPrx->getAgentInstancesSegment();
635 
636  for (const auto& entityBase : objs)
637  {
638  auto id = entityBase->getId();
639  if (std::find(excludedInstancesIds.cbegin(), excludedInstancesIds.cend(), id) != excludedInstancesIds.cend())
640  {
641  continue;
642  }
643 
644  const memoryx::ObjectInstancePtr object = memoryx::ObjectInstancePtr::dynamicCast(entityBase);
645  auto objPose = object->getPose();
646  if (objPose->frame != GlobalFrame && !objPose->frame.empty())
647  {
648  objPose = FramedPosePtr::dynamicCast(agentSeg->convertToWorldPose(objPose->agent, objPose));
649  }
650 
651  ARMARX_CHECK_EXPRESSION(object);
652 
653  const std::string className = object->getMostProbableClass();
654 
655  memoryx::ObjectClassList classes = workingMemoryPrx->getPriorKnowledge()->getObjectClassesSegment()->getClassWithSubclasses(className);
656 
657  if (!classes.size())
658  {
659  ARMARX_INFO_S << "No classes for most probable class '" << className << "' of object '" << object->getName() << "' with id " << id;
660  continue;
661  }
662 
664  {
665  classes.at(0),
666  armarx::PoseBasePtr{objPose}
667  });
668  }
669  TIMING_END(LoadFromWM);
670  }
671 
672 
673  SimoxCSpacePtr SimoxCSpace::PrefetchWorkingMemoryObjects(memoryx::WorkingMemoryInterfacePrx workingMemoryPrx, memoryx::CommonStorageInterfacePrx commonStoragePrx, armarx::RobotStateComponentInterfacePrx rsc)
674  {
675  SimoxCSpacePtr cspace(new SimoxCSpace(commonStoragePrx));
676 
677  AgentPlanningInformation agentData;
678  agentData.agentProjectNames = rsc->getArmarXPackages();
679  agentData.agentRelativeFilePath = rsc->getRobotFilename();
680 
681  cspace->setAgent(agentData);
682 
683  cspace->addObjectsFromWorkingMemory(workingMemoryPrx);
684  cspace->initCollisionTest();
685  return cspace;
686  }
687 
688  void SimoxCSpace::addPlanarObject(const std::vector<Eigen::Vector3f>& convexHull)
689  {
690  stationaryPlanes.push_back(convexHull);
691  }
692 
694  {
695  if (!commonStorage)
696  {
697  ARMARX_ERROR_S << "SimoxCSpace ice_postUnmarshal: commonStorage == null";
698  throw std::invalid_argument {"SimoxCSpace ice_postUnmarshal: commonStorage == null"};
699  }
700 
701  //should throw no direct exception since they were prevented when adding an agent
702  initAgent();
703  }
704 
705  template<class T, class Thrower>
706  std::vector<std::vector<T>> transpose(const std::vector<std::vector<T>>& src, Thrower thrower)
707  {
708  std::size_t numDatapoints = src.size();
709  if (!numDatapoints)
710  {
711  return {};
712  }
713  std::size_t numDimensions = src.at(0).size();
714  std::vector<std::vector<T>> transposed(numDimensions, std::vector<T>(numDatapoints));
715  for (std::size_t i = 0; i < numDatapoints; ++i)
716  {
717  auto& datapoint = src.at(i);
718  if (datapoint.size() != static_cast<std::size_t>(numDimensions))
719  {
720  thrower(i, datapoint.size(), numDimensions);
721  }
722  for (std::size_t dim = 0; dim < numDimensions; ++dim)
723  {
724  transposed.at(dim).at(i) = datapoint.at(dim);
725  }
726  }
727  return transposed;
728  }
729 
730  template<class T>
731  std::vector<std::vector<T>> transpose(const std::vector<std::vector<T>>& src)
732  {
733  return transpose(
734  src,
735  [](std::size_t idx, std::size_t szi, std::size_t numDim)
736  {
737  std::stringstream ss;
738  ss << "transpose: Element " << idx
739  << " has " << szi << " dimensions. The Element 0 has "
740  << numDim << "dimensions.";
741  throw std::invalid_argument {ss.str()};
742  }
743  );
744  }
745 
746  TrajectoryPtr SimoxCSpace::pathToTrajectory(const VectorXfSeq& p) const
747  {
748  if (p.empty())
749  {
750  return nullptr;
751  }
752  auto thrower = [](std::size_t idx, std::size_t szi, std::size_t numDim)
753  {
754  std::stringstream ss;
755  ss << "SimoxCSpace::pathToTrajectory: The datapoint " << idx
756  << " has " << szi << " dimensions. The CSpace has "
757  << numDim << "dimensions.";
758  throw std::invalid_argument {ss.str()};
759  };
760  if (static_cast<std::size_t>(getDimensionality()) != p.front().size())
761  {
762  thrower(0, p.front().size(), static_cast<std::size_t>(getDimensionality()));
763  }
764  TrajectoryPtr traj = new Trajectory {transpose(p, thrower), Ice::DoubleSeq() /*timestamps*/, getAgentJointNames()};
765  LimitlessStateSeq limitlessStates;
766  for (auto& joint : getAgentJoints())
767  {
768  LimitlessState state;
769  state.enabled = joint->isLimitless();
770  state.limitHi = joint->getJointLimitHigh();
771  state.limitLo = joint->getJointLimitLow();
772  limitlessStates.push_back(state);
773  }
774  traj->setLimitless(limitlessStates);
775  return traj;
776  }
777 
778  FloatRangeSeq SimoxCSpace::getDimensionsBounds(const Ice::Current&) const
779  {
780  FloatRangeSeq dims;
781  dims.reserve(getDimensionality());
783  agentJoints.begin(), agentJoints.end(), std::back_inserter(dims),
784  [](const VirtualRobot::RobotNodePtr & joint)
785  {
786  return FloatRange {joint->getJointLimitLo(), joint->getJointLimitHi()};
787  }
788  );
789  return dims;
790  }
791 
792  Ice::StringSeq SimoxCSpace::getAgentJointNames() const
793  {
794  Ice::StringSeq result;
795  result.reserve(getAgentJoints().size());
796  for (const auto& e : getAgentJoints())
797  {
798  result.emplace_back(e->getName());
799  }
800  return result;
801  }
802 
803  VectorXf SimoxCSpace::jointMapToVector(const std::map<std::string, float>& jointMap, bool checkForNonexistenJointsInCspace) const
804  {
805  VectorXf result(getDimensionality(), 0.f);
806  std::size_t valuesFromMapUsed = 0;
807  auto jointNames = getAgentJointNames();
808  for (std::size_t i = 0; i < jointNames.size(); ++i)
809  {
810  auto it = jointMap.find(jointNames.at(i));
811  if (it != jointMap.end())
812  {
813  result.at(i) = it->second;
814  ++valuesFromMapUsed;
815  }
816  }
817  if (checkForNonexistenJointsInCspace && (valuesFromMapUsed != jointMap.size()))
818  {
819  throw std::invalid_argument {"the joint map contained a joint not contained by the cspace!"};
820  }
821  return result;
822  }
823 
824  SimoxCSpaceWith2DPose::SimoxCSpaceWith2DPose(memoryx::CommonStorageInterfacePrx commonStoragePrx, bool loadVisualizationModel, float stationaryObjectMargin):
825  SimoxCSpace(commonStoragePrx, loadVisualizationModel, stationaryObjectMargin)
826  {
827  ARMARX_CHECK_EXPRESSION(commonStoragePrx);
828  }
829 
830  CSpaceBasePtr SimoxCSpaceWith2DPose::clone(bool loadVisualizationModel)
831  {
832  SimoxCSpaceWith2DPosePtr cloned = new SimoxCSpaceWith2DPose {commonStorage, loadVisualizationModel, stationaryObjectMargin};
833  for (const auto& obj : stationaryObjects)
834  {
835  cloned->addStationaryObject(obj);
836  }
837  cloned->poseBounds = poseBounds;
838  cloned->agentInfo = agentInfo;
839  cloned->initAgent();
840  return cloned;
841  }
842 
843  FloatRangeSeq SimoxCSpaceWith2DPose::getDimensionsBounds(const Ice::Current&) const
844  {
845  FloatRangeSeq bounds(getDimensionality());
846  bounds.at(0).min = poseBounds.min.e0 ;
847  bounds.at(0).max = poseBounds.max.e0 ;
848 
849  bounds.at(1).min = poseBounds.min.e1 ;
850  bounds.at(1).max = poseBounds.max.e1 ;
851 
852  bounds.at(2).min = poseBounds.min.e2;
853  bounds.at(2).max = poseBounds.max.e2;
854 
855  auto parentBounds = SimoxCSpace::getDimensionsBounds();
856  std::move(parentBounds.begin(), parentBounds.end(), bounds.begin() + 3);
857  return bounds;
858  }
859 
861  {
862  auto joints = SimoxCSpace::getAgentJointNames();
863  joints.resize(joints.size() + 3);
864  std::move_backward(joints.begin(), joints.end() - 3, joints.end());
865  joints.at(0) = "x";
866  joints.at(1) = "y";
867  joints.at(2) = "alpha";
868  return joints;
869  }
870 
871  void SimoxCSpaceWith2DPose::setConfig(const float*& it)
872  {
873  globalPoseBuffer(0, 3) = *(it++) ;
874  globalPoseBuffer(1, 3) = *(it++) ;
875 
876  const auto rot = *(it++);
877 
878  const auto crot = std::cos(rot);
879  const auto srot = std::sin(rot);
880 
881  //see http://planning.cs.uiuc.edu/node102.html
882  //row 0
883  globalPoseBuffer(0, 0) = crot;
884  globalPoseBuffer(0, 1) = -srot;
885  //row 1
886  globalPoseBuffer(1, 0) = srot;
887  globalPoseBuffer(1, 1) = crot;
888 
889  agentSceneObj->setGlobalPoseNoChecks(globalPoseBuffer);
891  }
892 
893  SimoxCSpaceWith3DPose::SimoxCSpaceWith3DPose(memoryx::CommonStorageInterfacePrx commonStoragePrx, bool loadVisualizationModel, float stationaryObjectMargin):
894  SimoxCSpace(commonStoragePrx, loadVisualizationModel, stationaryObjectMargin)
895  {
896  ARMARX_CHECK_EXPRESSION(commonStoragePrx);
897  }
898 
899  CSpaceBasePtr SimoxCSpaceWith3DPose::clone(bool loadVisualizationModel)
900  {
901  SimoxCSpaceWith3DPosePtr cloned = new SimoxCSpaceWith3DPose {commonStorage, loadVisualizationModel, stationaryObjectMargin};
902  for (const auto& obj : stationaryObjects)
903  {
904  cloned->addStationaryObject(obj);
905  }
906  cloned->poseBounds = poseBounds;
907  cloned->agentInfo = agentInfo;
908  cloned->initAgent();
909  return cloned;
910  }
911 
912  FloatRangeSeq SimoxCSpaceWith3DPose::getDimensionsBounds(const Ice::Current&) const
913  {
914  FloatRangeSeq bounds(getDimensionality());
915  bounds.at(0).min = poseBounds.min.e0;
916  bounds.at(0).max = poseBounds.max.e0;
917 
918  bounds.at(1).min = poseBounds.min.e1;
919  bounds.at(1).max = poseBounds.max.e1;
920 
921  bounds.at(2).min = poseBounds.min.e2;
922  bounds.at(2).max = poseBounds.max.e2;
923 
924  bounds.at(3).min = poseBounds.min.e3;
925  bounds.at(3).max = poseBounds.max.e3;
926 
927  bounds.at(4).min = poseBounds.min.e4;
928  bounds.at(4).max = poseBounds.max.e4;
929 
930  bounds.at(5).min = poseBounds.min.e5;
931  bounds.at(5).max = poseBounds.max.e5;
932  auto parentBounds = SimoxCSpace::getDimensionsBounds();
933  std::move(parentBounds.begin(), parentBounds.end(), bounds.begin() + 6);
934  return bounds;
935  }
936 
937  void SimoxCSpaceWith3DPose::setConfig(const float*& it)
938  {
939  globalPoseBuffer(0, 3) = *(it++);
940  globalPoseBuffer(1, 3) = *(it++);
941  globalPoseBuffer(2, 3) = *(it++);
942 
943  const auto roll = *(it++);
944  const auto pitch = *(it++);
945  const auto yaw = *(it++);
946 
947  const auto croll = std::cos(roll);
948  const auto sroll = std::sin(roll);
949 
950  const auto cpitch = std::cos(pitch);
951  const auto spitch = std::sin(pitch);
952 
953  const auto cyaw = std::cos(yaw);
954  const auto syaw = std::sin(yaw);
955 
956  //see http://planning.cs.uiuc.edu/node102.html
957  //row 0
958  globalPoseBuffer(0, 0) = cyaw * cpitch;
959  globalPoseBuffer(0, 1) = cyaw * spitch * sroll - syaw * croll;
960  globalPoseBuffer(0, 2) = cyaw * spitch * sroll + syaw * sroll;
961  //row 1
962  globalPoseBuffer(1, 0) = syaw * cpitch;
963  globalPoseBuffer(1, 1) = syaw * spitch * sroll + cyaw * croll;
964  globalPoseBuffer(1, 2) = syaw * spitch * croll - cyaw * sroll;
965  //row 2
966  globalPoseBuffer(2, 0) = -spitch;
967  globalPoseBuffer(2, 1) = cpitch * sroll;
968  globalPoseBuffer(2, 2) = cpitch * croll;
969 
970  agentSceneObj->setGlobalPoseNoChecks(globalPoseBuffer);
972  }
973 
975  {
976  auto joints = SimoxCSpace::getAgentJointNames();
977  joints.resize(joints.size() + 6);
978  std::move_backward(joints.begin(), joints.end() - 6, joints.end());
979  joints.at(0) = "x";
980  joints.at(1) = "y";
981  joints.at(2) = "z";
982  joints.at(3) = "alpha";
983  joints.at(4) = "betha";
984  joints.at(5) = "gamma";
985  return joints;
986  }
987 
988  std::vector<armarx::DebugDrawerLineSet> SimoxCSpace::getTraceVisu(const armarx::VectorXfSeq& vecs, const std::vector<std::string>& nodeNames, float traceStepSize)
989  {
990  if (traceStepSize <= 0)
991  {
992  throw std::invalid_argument {"SimoxCSpace::getTraces: traceStepSize <= 0"};
993  }
994  std::vector<armarx::DebugDrawerLineSet> traces;
995  if (nodeNames.empty())
996  {
997  return traces;
998  }
999  traces.resize(nodeNames.size());
1000  if (vecs.size() < 2)
1001  {
1002  return traces;
1003  }
1004  auto addPoints = [&]
1005  {
1006  for (std::size_t i = 0; i < nodeNames.size(); ++i)
1007  {
1008  const auto& name = nodeNames.at(i);
1009  armarx::DebugDrawerLineSet& trace = traces.at(i);
1010  const auto pose = getAgentSceneObj()->getRobotNode(name)->getGlobalPose();
1011  trace.points.emplace_back(DebugDrawerPointCloudElement {pose(0, 3), pose(1, 3), pose(2, 3)});
1012  };
1013  };
1014  for (std::size_t vecI = 0; vecI < vecs.size() - 1; ++vecI)
1015  {
1016  const auto& vecStart = vecs.at(vecI);
1017  const auto& vecEnd = vecs.at(vecI + 1);
1018  assert(vecStart.size() == vecEnd.size());
1019  assert(vecStart.size() == static_cast<std::size_t>(getDimensionality()));
1020  auto dist = euclideanDistance(vecStart.begin(), vecStart.end(), vecEnd.begin());
1021  if (dist > traceStepSize)
1022  {
1023  VectorXf vecCfg = vecStart;
1024  Eigen::Map<const Eigen::VectorXf> eStart {vecStart.data(), getDimensionality()};
1025  Eigen::Map<const Eigen::VectorXf> eEnd {vecEnd.data(), getDimensionality()};
1026  Eigen::Map<Eigen::VectorXf> eCfg {vecCfg.data(), getDimensionality()};
1027 
1028  Eigen::VectorXf eStep = (eEnd - eStart).normalized() * traceStepSize;
1029  setConfig(vecCfg);
1030  while (dist > traceStepSize)
1031  {
1032  addPoints();//start
1033  eCfg += eStep;
1034  setConfig(vecCfg);
1035  addPoints();//end
1036  dist -= traceStepSize;
1037  }
1038  addPoints();//start
1039  setConfig(vecEnd);
1040  addPoints();//end
1041  }
1042  else
1043  {
1044  setConfig(vecStart);
1045  addPoints();//start
1046  setConfig(vecEnd);
1047  addPoints();//end
1048  }
1049  }
1050  return traces;
1051  }
1052 }
armarx::SimoxCSpaceWith2DPose::setConfig
void setConfig(const float *&it) override
Definition: SimoxCSpace.cpp:871
TIMING_START
#define TIMING_START(name)
Definition: TimeUtil.h:280
armarx::eFull
@ eFull
Definition: MorphingItem.h:35
algorithm.h
armarx::SimoxCSpaceWith3DPose::setConfig
void setConfig(const float *&it) override
Definition: SimoxCSpace.cpp:937
armarx::VariantType::Float
const VariantTypeId Float
Definition: Variant.h:918
armarx::SimoxCSpace::getDimensionsBounds
FloatRangeSeq getDimensionsBounds(const Ice::Current &=Ice::emptyCurrent) const override
Definition: SimoxCSpace.cpp:778
armarx::SimoxCSpace::getAgentDataAndLoadRobot
AgentData getAgentDataAndLoadRobot() const
Definition: SimoxCSpace.cpp:287
TIMING_END
#define TIMING_END(name)
Definition: TimeUtil.h:296
armarx::SimoxCSpaceWith3DPose::SimoxCSpaceWith3DPose
SimoxCSpaceWith3DPose()=default
armarx::GlobalCache::hasObject
bool hasObject(const Id &id) const
Definition: GlobalCache.h:63
armarx::SimoxCSpace::getAgentDataFromRobot
AgentData getAgentDataFromRobot(VirtualRobot::RobotPtr robotPtr) const
Definition: SimoxCSpace.cpp:370
armarx::SimoxCSpace::AgentData::joints
std::vector< VirtualRobot::RobotNodePtr > joints
The agent's joints.
Definition: SimoxCSpace.h:314
armarx::SimoxCSpace::getAgentSceneObj
const VirtualRobot::RobotPtr & getAgentSceneObj() const
Definition: SimoxCSpace.h:186
armarx::SimoxCSpace::AgentData::agent
VirtualRobot::RobotPtr agent
The agent's collision model.
Definition: SimoxCSpace.h:310
CSpace.h
Pose.h
armarx::SimoxCSpace::pathToTrajectory
virtual TrajectoryPtr pathToTrajectory(const Path &p) const
Definition: SimoxCSpace.h:204
armarx::SimoxCSpace::isInitialized
bool isInitialized
Whether the collision check is initialized.
Definition: SimoxCSpace.h:264
armarx::GlobalFrame
const std::string GlobalFrame
Definition: FramedPose.h:62
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::SimoxCSpaceWith2DPose
Similar to armarx::SimoxCSpace, but prepends dimensions for translation in x and y and a rotation aro...
Definition: SimoxCSpace.h:366
armarx::CMakePackageFinder
The CMakePackageFinder class provides an interface to the CMake Package finder capabilities.
Definition: CMakePackageFinder.h:53
armarx::SimoxCSpaceWith2DPose::globalPoseBuffer
Eigen::Matrix4f globalPoseBuffer
Definition: SimoxCSpace.h:403
armarx::SimoxCSpace::getTraceVisu
std::vector< armarx::DebugDrawerLineSet > getTraceVisu(const Path &p, const std::vector< std::string > &nodeNames, float traceStepSize=std::numeric_limits< float >::infinity())
Definition: SimoxCSpace.h:214
Convex::convexHull
ConvexHull< Point >::type convexHull(const std::vector< Point > &points)
Definition: convexHull.hpp:487
armarx::SimoxCSpaceWith3DPose::globalPoseBuffer
Eigen::Matrix4f globalPoseBuffer
Definition: SimoxCSpace.h:449
armarx::RobotPoolPtr
std::shared_ptr< class RobotPool > RobotPoolPtr
Definition: RobotUnitModuleRobotData.h:35
ObjectClass.h
armarx::SimoxCSpace::AgentData::collisionSets
std::vector< VirtualRobot::SceneObjectSetPtr > collisionSets
The collision stes.
Definition: SimoxCSpace.h:318
armarx::SimoxCSpace::initStationaryObjects
void initStationaryObjects()
Initializes stationary objects for collision checking.
Definition: SimoxCSpace.cpp:221
armarx::SimoxCSpace::addObjectsFromWorkingMemory
virtual void addObjectsFromWorkingMemory(memoryx::WorkingMemoryInterfacePrx workingMemoryPrx, const std::vector< std::string > &excludedInstancesIds=std::vector< std::string >())
Adds all objects except the ones with ids specified in the parameter excludedInstancesIds from the wo...
Definition: SimoxCSpace.cpp:628
armarx::SimoxCSpace::createSimoxCSpace
virtual Saba::CSpaceSampledPtr createSimoxCSpace() const
Definition: SimoxCSpace.cpp:129
IceInternal::Handle< SimoxCSpace >
armarx::SimoxCSpaceWith2DPose::getDimensionsBounds
FloatRangeSeq getDimensionsBounds(const Ice::Current &=Ice::emptyCurrent) const override
Definition: SimoxCSpace.cpp:843
deactivateSpam
SpamFilterDataPtr deactivateSpam(SpamFilterDataPtr const &spamFilter, float deactivationDurationSec, const std::string &identifier, bool deactivate)
Definition: Logging.cpp:72
armarx::ensureCoinIsInitialized
bool ensureCoinIsInitialized()
Definition: SimoxCSpace.cpp:56
armarx::SimoxCSpace::fileManager
memoryx::GridFileManagerPtr fileManager
The file manager used to load objects.
Definition: SimoxCSpace.h:274
armarx::SimoxCSpaceWith3DPose::getDimensionsBounds
FloatRangeSeq getDimensionsBounds(const Ice::Current &=Ice::emptyCurrent) const override
Definition: SimoxCSpace.cpp:912
armarx::SimoxCSpace::stationaryPlanes
std::vector< std::vector< Eigen::Vector3f > > stationaryPlanes
Definition: SimoxCSpace.h:291
armarx::SimoxCSpace::robotCache
GlobalCache< RobotPoolPtr, std::pair< VirtualRobot::RobotIO::RobotDescription, std::string > > robotCache
Definition: SimoxCSpace.h:294
armarx::ctrlutil::a
double a(double t, double a0, double j)
Definition: CtrlUtil.h:45
armarx::SimoxCSpace::clone
CSpaceBasePtr clone(const Ice::Current &=Ice::emptyCurrent) override
Definition: SimoxCSpace.h:118
armarx::SimoxCSpace::getDimensionality
Ice::Long getDimensionality(const Ice::Current &=Ice::emptyCurrent) const override
Definition: SimoxCSpace.h:144
ARMARX_DEBUG_S
#define ARMARX_DEBUG_S
Definition: Logging.h:198
armarx::SimoxCSpace::getAgentJointNames
virtual Ice::StringSeq getAgentJointNames() const
Definition: SimoxCSpace.cpp:792
ARMARX_ERROR_S
#define ARMARX_ERROR_S
Definition: Logging.h:209
armarx::SimoxCSpace::ice_postUnmarshal
void ice_postUnmarshal() override
Initializes basic structures after transmission through ice.
Definition: SimoxCSpace.cpp:693
data
uint8_t data[1]
Definition: EtherCATFrame.h:68
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:177
armarx::SimoxCSpace::addPlanarObject
virtual void addPlanarObject(const std::vector< Eigen::Vector3f > &convexHull)
Definition: SimoxCSpace.cpp:688
armarx::SimoxCSpace::getAgentJoints
const std::vector< VirtualRobot::RobotNodePtr > & getAgentJoints() const
Definition: SimoxCSpace.h:250
armarx::SimoxCSpace::setAgent
void setAgent(const AgentPlanningInformation &agentInfo, const Ice::Current &=Ice::emptyCurrent) override
Adds a stationary agent to the cspace.
Definition: SimoxCSpace.cpp:157
armarx::CMakePackageFinder::getDataDir
std::string getDataDir() const
Definition: CMakePackageFinder.h:176
armarx::SimoxCSpace::initAgent
void initAgent()
Definition: SimoxCSpace.h:332
MemoryXCoreObjectFactories.h
armarx::RobotPool
This class holds a pool of local VirtualRobots for multi threaded applications that can be requested ...
Definition: RobotPool.h:39
armarx::SimoxCSpace::PrefetchWorkingMemoryObjects
static SimoxCSpacePtr PrefetchWorkingMemoryObjects(memoryx::WorkingMemoryInterfacePrx workingMemoryPrx, memoryx::CommonStorageInterfacePrx commonStoragePrx, RobotStateComponentInterfacePrx rsc)
Load objects from WorkingMemory and puts them into the mesh cache.
Definition: SimoxCSpace.cpp:673
armarx::SimoxCSpace::addStationaryObject
void addStationaryObject(const StationaryObject &obj, const Ice::Current &=Ice::emptyCurrent) override
Adds a stationary object to the cspace.
Definition: SimoxCSpace.cpp:145
armarx::SimoxCSpace::getMovedSimoxManipulatorObject
VirtualRobot::ManipulationObjectPtr getMovedSimoxManipulatorObject(const memoryx::ObjectClassBasePtr &object, const armarx::PoseBasePtr &pose, memoryx::GridFileManagerPtr &fileManager) const
Definition: SimoxCSpace.cpp:609
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
memoryx::EntityWrappers::SimoxObjectWrapper
SimoxObjectWrapper offers a simplified access to the Simox ManipulationObject (i.e visualization,...
Definition: SimoxObjectWrapper.h:46
armarx::to_string
const std::string & to_string(const std::string &s)
Definition: StringHelpers.h:40
armarx::SimoxCSpace::initCollisionTest
void initCollisionTest(const Ice::Current &=Ice::emptyCurrent) override
Initializes the collision test.
Definition: SimoxCSpace.cpp:192
armarx::SimoxCSpaceWith2DPose::getAgentJointNames
Ice::StringSeq getAgentJointNames() const override
Definition: SimoxCSpace.cpp:860
armarx::SimoxCSpaceWith3DPose::getAgentJointNames
Ice::StringSeq getAgentJointNames() const override
Definition: SimoxCSpace.cpp:974
armarx::control::njoint_controller::platform::platform_follower_controller::NameValueMap
std::map< std::string, float > NameValueMap
Definition: PlatformFollowerController.h:91
armarx::SimoxCSpace::AgentData
Contains information about an agent.
Definition: SimoxCSpace.h:305
armarx::SimoxCSpace::meshCache
GlobalCache< VirtualRobot::ManipulationObjectPtr, std::pair< int, std::string > > meshCache
Definition: SimoxCSpace.h:293
armarx::euclideanDistance
float euclideanDistance(IteratorType1 first1, IteratorType1 last1, IteratorType2 first2)
Returns the euclidean distance.
Definition: Metrics.h:94
CMakePackageFinder.h
SimoxObjectWrapper.h
SimoxCSpace.h
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
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::SimoxCSpaceWith2DPose::clone
CSpaceBasePtr clone(bool loadVisualizationModel) override
Definition: SimoxCSpace.cpp:830
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
memoryx::GridFileManagerPtr
std::shared_ptr< GridFileManager > GridFileManagerPtr
Definition: AbstractEntityWrapper.h:32
armarx::SimoxCSpace::stationaryObjectSet
VirtualRobot::SceneObjectSetPtr stationaryObjectSet
The scene objects for stationary objects.
Definition: SimoxCSpace.h:285
armarx::SimoxCSpaceWith3DPose::clone
CSpaceBasePtr clone(bool loadVisualizationModel) override
Definition: SimoxCSpace.cpp:899
armarx::SimoxCSpaceWith3DPose
Similar to armarx::SimoxCSpace, but prepends dimensions for translation in x, y and z and rotations a...
Definition: SimoxCSpace.h:412
armarx::transform
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT > >
Convenience function (with less typing) to transform a container of type InputT into the same contain...
Definition: algorithm.h:315
IceInternal::ProxyHandle<::IceProxy::armarx::RobotStateComponentInterface >
armarx::SimoxCSpace::setStationaryObjects
virtual void setStationaryObjects(const StationaryObjectList &objList)
Definition: SimoxCSpace.cpp:152
armarx::SimoxCSpace::loadVisualizationModel
bool loadVisualizationModel
Whether the visualization model of objects/agents sould be loaded.
Definition: SimoxCSpace.h:268
armarx::Trajectory
The Trajectory class represents n-dimensional sampled trajectories.
Definition: Trajectory.h:76
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:42
armarx::SimoxCSpace::cd
VirtualRobot::CDManager cd
The collision checker.
Definition: SimoxCSpace.h:280
MemoryXTypesObjectFactories.h
armarx::SimoxCSpace::agentSceneObj
VirtualRobot::RobotPtr agentSceneObj
Definition: SimoxCSpace.h:289
distance
double distance(const Point &a, const Point &b)
Definition: point.hpp:88
armarx::SimoxCSpace::setConfig
virtual void setConfig(const std::vector< float > cfg)
Sets a configuration to check for.
Definition: SimoxCSpace.h:153
ARMARX_INFO_S
#define ARMARX_INFO_S
Definition: Logging.h:195
armarx::ArmarXDataPath::getAbsolutePath
static bool getAbsolutePath(const std::string &relativeFilename, std::string &storeAbsoluteFilename, const std::vector< std::string > &additionalSearchPaths={}, bool verbose=true)
Definition: ArmarXDataPath.cpp:111
armarx::SimoxCSpace
The SimoxCSpace contains a set of stationary obstacles and an agent.
Definition: SimoxCSpace.h:67
armarx::transpose
std::vector< std::vector< T > > transpose(const std::vector< std::vector< T >> &src, Thrower thrower)
Definition: SimoxCSpace.cpp:706
armarx::SimoxCSpace::isCollisionFree
bool isCollisionFree(const ::std::pair< const Ice::Float *, const Ice::Float * > &cfg, const Ice::Current &=Ice::emptyCurrent) override
Definition: SimoxCSpace.cpp:176
armarx::GlobalCache::getCacheObject
ObjectTypePtr getCacheObject(const Id &id)
Definition: GlobalCache.h:68
ArmarXDataPath.h
armarx::SimoxCSpace::SimoxCSpace
SimoxCSpace()=default
Default ctor.
armarx::SimoxCSpace::getSimoxManipulatorObject
VirtualRobot::ManipulationObjectPtr getSimoxManipulatorObject(const memoryx::ObjectClassBasePtr &object, const memoryx::GridFileManagerPtr &fileManager, bool inflate=true, VirtualRobot::CollisionCheckerPtr const &colChecker=VirtualRobot::CollisionCheckerPtr {}) const
Definition: SimoxCSpace.cpp:550
armarx::ctrlutil::s
double s(double t, double s0, double v0, double a0, double j)
Definition: CtrlUtil.h:33
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
IceInternal::trace
void trace(const char *, const ::Ice::OutputStream &, const ::Ice::LoggerPtr &, const TraceLevelsPtr &)
armarx::GlobalCache::insertObject
void insertObject(const Id &id, const ObjectTypePtr &obj)
Definition: GlobalCache.h:83
armarx::SimoxCSpace::agentJoints
std::vector< VirtualRobot::RobotNodePtr > agentJoints
Definition: SimoxCSpace.h:287
armarx::SimoxCSpaceWith3DPose::getDimensionality
Ice::Long getDimensionality(const Ice::Current &=Ice::emptyCurrent) const override
Definition: SimoxCSpace.h:437
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:18
armarx::SimoxCSpaceWith2DPose::getDimensionality
Ice::Long getDimensionality(const Ice::Current &=Ice::emptyCurrent) const override
Definition: SimoxCSpace.h:391