28 #include <unordered_map>
29 #include <unordered_set>
31 #include <MotionPlanning/CSpace/CSpaceSampled.h>
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"
75 static Initializer init;
76 return init.doStuff();
81 SimoxCSpace::SimoxCSpace(memoryx::CommonStorageInterfacePrx commonStoragePrx,
bool loadVisualizationModel,
float stationaryObjectMargin):
84 this->stationaryObjectMargin = stationaryObjectMargin;
104 commonStorage = commonStoragePrx;
109 throw std::invalid_argument {
"SimoxCSpace ctor: commonStorage == null"};
118 for (
const auto& obj : stationaryObjects)
120 cloned->addStationaryObject(obj);
122 cloned->agentInfo = agentInfo;
133 VirtualRobot::CDManagerPtr tmpCd = VirtualRobot::CDManagerPtr(
new VirtualRobot::CDManager(
cd));
139 Saba::CSpaceSampledPtr result(
new Saba::CSpaceSampled(
agentSceneObj, tmpCd,
140 agentInfo.kinemaicChainNames.size() > 0 ?
agentSceneObj->getRobotNodeSet(agentInfo.kinemaicChainNames.at(0)) : VirtualRobot::RobotNodeSetPtr()));
149 stationaryObjects.emplace_back(obj);
154 stationaryObjects = objList;
159 this->agentInfo = agentInfo;
169 jointValues[agentJoint->getName()] = *it;
170 agentJoint->setJointValueNoUpdate(*(it++));
177 const ::std::pair<const Ice::Float*, const Ice::Float*>& cfg,
189 return !
cd.isInCollision();
207 TIMING_END(CSpaceInit_ensureCoinIsInitialized)
223 stationaryObjectSet.reset(
new VirtualRobot::SceneObjectSet {
"StationaryObjectSet",
cd.getCollisionChecker()});
227 for (std::size_t i = 0; i < stationaryObjects.size(); ++i)
230 const auto& obj = stationaryObjects.at(i);
233 sceneObj->setUpdateVisualization(
false);
239 VirtualRobot::CoinVisualizationNodePtr visu(
new VirtualRobot::CoinVisualizationNode((SoNode*)VirtualRobot::CoinVisualizationFactory::CreatePolygonVisualization(plane)));
241 VirtualRobot::CollisionModelPtr(
new VirtualRobot::CollisionModel(visu)),
242 VirtualRobot::SceneObject::Physics {},
cd.getCollisionChecker()));
250 return obj->getName();
262 if (agentInfo.agentPose)
264 agentData.
agent->setGlobalPose(armarx::PosePtr::dynamicCast(agentInfo.agentPose)->toEigen());
271 const std::size_t numberOfJoints = agentData.
joints.size();
281 cd.addCollisionModel(std::move(colMod));
292 auto packageNames = agentInfo.agentProjectNames;
293 if (!agentInfo.agentProjectName.empty())
295 packageNames.emplace_back(agentInfo.agentProjectName);
298 std::string absoluteFilePath;
299 std::vector<std::string> paths;
300 for (
const auto& package : packageNames)
304 std::vector<std::string> packagePaths =
Split(pathStr,
";,",
false,
true);
306 paths.reserve(paths.size() + packagePaths.size());
307 std::move(packagePaths.begin(), packagePaths.end(), std::back_inserter(paths));
313 s <<
"could not find file " << agentInfo.agentRelativeFilePath <<
" in project " << agentInfo.agentProjectName;
315 throw std::invalid_argument {
s.str()};
324 VirtualRobot::RobotIO::eCollisionModel
325 ) : VirtualRobot::RobotIO::eStructure;
326 auto pair = std::make_pair(loadType, absoluteFilePath);
330 agent = VirtualRobot::RobotIO::loadRobot(
335 ARMARX_DEBUG <<
"Robot Cache MISS! Path: " << absoluteFilePath <<
" load type: " << (int)loadType;
337 agent = pool->getRobot();
343 ARMARX_DEBUG <<
"Robot Cache hit! load type: " << (int)loadType;
361 s <<
"Can't load agent from: " << absoluteFilePath;
363 throw std::invalid_argument {
s.str()};
375 data.agent = robotPtr;
382 std::unordered_map<std::string, std::vector<VirtualRobot::RobotNodePtr>> toCollSetAssociatedObjects;
383 toCollSetAssociatedObjects.reserve(agentInfo.collisionSetNames.size());
385 for (std::size_t i = 0; i < agentInfo.attachedObjects.size(); ++i)
387 const auto& attached = agentInfo.attachedObjects.at(i);
389 std::stringstream sceneObjName;
390 sceneObjName <<
"attached_obj_" << i <<
"_" << sceneObj->getName();
391 sceneObj->setName(sceneObjName.str());
394 if (!
data.agent->hasRobotNode(attached.attachedToRobotNodeName))
397 s <<
"Agent " <<
data.agent->getName() <<
" has no node " << attached.attachedToRobotNodeName
398 <<
"to attach object " << attached.objectClassBase->getName();
400 throw std::invalid_argument {
s.str()};
403 VirtualRobot::RobotNodePtr nodeToAttachTo =
data.agent->getRobotNode(attached.attachedToRobotNodeName);
404 VirtualRobot::RobotFactory::attach(
data.agent, sceneObj, nodeToAttachTo, armarx::PosePtr::dynamicCast(attached.relativeObjectPose)->toEigen());
407 if (attached.associatedCollisionSetName.empty())
410 data.collisionSets.emplace_back(
new VirtualRobot::SceneObjectSet {sceneObjName.str(),
data.agent->getCollisionChecker()});
411 data.collisionSets.back()->addSceneObject(
data.agent->getRobotNode(sceneObjName.str()));
418 agentInfo.collisionSetNames.begin(),
419 agentInfo.collisionSetNames.end(),
420 attached.associatedCollisionSetName
422 == agentInfo.collisionSetNames.end()
426 s <<
"Agent " <<
data.agent->getName() <<
" has no set " << attached.associatedCollisionSetName
427 <<
" to use as associated collision set for attached object " << attached.objectClassBase->getName();
429 throw std::invalid_argument {
s.str()};
432 toCollSetAssociatedObjects[attached.associatedCollisionSetName].emplace_back(
data.agent->getRobotNode(sceneObjName.str()));
436 for (
const auto& name : agentInfo.collisionSetNames)
438 if (!
data.agent->hasRobotNodeSet(name))
441 s <<
"Agent " <<
data.agent->getName() <<
" has no collision model " << name;
443 throw std::invalid_argument {
s.str()};
447 data.collisionSets.emplace_back(
new VirtualRobot::SceneObjectSet {name,
data.agent->getCollisionChecker()});
448 data.collisionSets.back()->addSceneObjects(
data.agent->getRobotNodeSet(name));
450 for (
auto& obj : toCollSetAssociatedObjects[name])
452 data.collisionSets.back()->addSceneObject(std::move(obj));
455 if (!agentInfo.collisionObjectNames.empty())
457 data.collisionSets.emplace_back(
new VirtualRobot::SceneObjectSet {
"collisionObjects",
data.agent->getCollisionChecker()});
458 for (
const auto& name : agentInfo.collisionObjectNames)
460 if (!
data.agent->hasRobotNode(name))
463 s <<
"Agent " <<
data.agent->getName() <<
" has no collision model " << name;
465 throw std::invalid_argument {
s.str()};
469 data.collisionSets.back()->addSceneObject(
data.agent->getRobotNode(name));
471 for (
auto& obj : toCollSetAssociatedObjects[name])
473 data.collisionSets.back()->addSceneObject(std::move(obj));
481 std::set<std::string> blacklist(agentInfo.jointsExcludedFromPlanning.begin(), agentInfo.jointsExcludedFromPlanning.end());
483 for (
const auto& name : agentInfo.kinemaicChainNames)
485 if (!
data.agent->hasRobotNodeSet(name))
488 s <<
"Agent " <<
data.agent->getName() <<
" has no kinematic chain " << name;
490 throw std::invalid_argument {
s.str()};
494 for (
auto& node : * (
data.agent->getRobotNodeSet(name)))
496 auto nodeIt = blacklist.find(node->getName());
497 if (nodeIt != blacklist.end())
502 if (!(node->isTranslationalJoint() || node->isRotationalJoint()))
505 s <<
"The node " << node->getName() <<
" in the kinematic chain "
506 << name <<
" of agent " <<
data.agent->getName()
507 <<
" is neither rotational nor tranlational";
509 throw std::invalid_argument {
s.str()};
512 data.joints.emplace_back(node);
513 blacklist.emplace_hint(nodeIt, node->getName());
517 for (
const auto& name : agentInfo.additionalJointsForPlanning)
519 if (!
data.agent->hasRobotNode(name))
522 s <<
"Agent " <<
data.agent->getName() <<
" has no node " << name;
524 throw std::invalid_argument {
s.str()};
526 auto node =
data.agent->getRobotNode(name);
528 auto nodeIt = blacklist.find(node->getName());
529 if (nodeIt != blacklist.end())
534 if (!(node->isTranslationalJoint() || node->isRotationalJoint()))
537 s <<
"The node " << node->getName()
538 <<
" of agent " <<
data.agent->getName()
539 <<
" is neither rotational nor tranlational";
541 throw std::invalid_argument {
s.str()};
544 data.joints.emplace_back(node);
545 blacklist.emplace_hint(nodeIt, node->getName());
556 VirtualRobot::ManipulationObjectPtr mo;
560 s <<
"Can't use object class with ice id " <<
object->ice_id();
562 throw armarx::InvalidArgumentException {
s.str()};
566 auto pair = std::make_pair((
int)(stationaryObjectMargin * 1000), object->getId());
567 auto pairZeroMargin = std::make_pair(0, object->getId());
573 mo = tmpMo->clone(tmpMo->getName(), colChecker,
true);
575 ARMARX_DEBUG <<
"mesh Cache hit for " << tmpMo->getName() <<
" - Cloning took " << (end - start).toMilliSeconds();
582 ARMARX_DEBUG <<
"mesh Cache HALFMISS - mesh inflation needed for " << tmpMo->getName();
583 mo = tmpMo->clone(tmpMo->getName(), colChecker,
true);
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);
594 if (this->stationaryObjectMargin != 0.0f && inflate)
598 mo->getCollisionModel()->inflateModel(this->stationaryObjectMargin);
614 const auto objectPose = armarx::PosePtr::dynamicCast(pose);
619 s <<
"Can't convert pose of " << memoryx::ObjectClassPtr::dynamicCast(
object)->getName() <<
" to armarx::Pose.";
621 throw armarx::InvalidArgumentException {
s.str()};
624 mo->setGlobalPose(objectPose->toEigen());
632 auto objInstPrx = workingMemoryPrx->getObjectInstancesSegment();
633 const auto objs = objInstPrx->getAllEntities();
634 auto agentSeg = workingMemoryPrx->getAgentInstancesSegment();
636 for (
const auto& entityBase : objs)
638 auto id = entityBase->getId();
639 if (std::find(excludedInstancesIds.cbegin(), excludedInstancesIds.cend(),
id) != excludedInstancesIds.cend())
645 auto objPose =
object->getPose();
646 if (objPose->frame !=
GlobalFrame && !objPose->frame.empty())
648 objPose = FramedPosePtr::dynamicCast(agentSeg->convertToWorldPose(objPose->agent, objPose));
653 const std::string className =
object->getMostProbableClass();
655 memoryx::ObjectClassList classes = workingMemoryPrx->getPriorKnowledge()->getObjectClassesSegment()->getClassWithSubclasses(className);
659 ARMARX_INFO_S <<
"No classes for most probable class '" << className <<
"' of object '" <<
object->getName() <<
"' with id " << id;
666 armarx::PoseBasePtr{objPose}
677 AgentPlanningInformation agentData;
678 agentData.agentProjectNames = rsc->getArmarXPackages();
679 agentData.agentRelativeFilePath = rsc->getRobotFilename();
681 cspace->setAgent(agentData);
683 cspace->addObjectsFromWorkingMemory(workingMemoryPrx);
684 cspace->initCollisionTest();
697 ARMARX_ERROR_S <<
"SimoxCSpace ice_postUnmarshal: commonStorage == null";
698 throw std::invalid_argument {
"SimoxCSpace ice_postUnmarshal: commonStorage == null"};
705 template<
class T,
class Thrower>
706 std::vector<std::vector<T>>
transpose(
const std::vector<std::vector<T>>& src, Thrower thrower)
708 std::size_t numDatapoints = src.size();
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)
717 auto& datapoint = src.at(i);
718 if (datapoint.size() !=
static_cast<std::size_t
>(numDimensions))
720 thrower(i, datapoint.size(), numDimensions);
722 for (std::size_t dim = 0; dim < numDimensions; ++dim)
724 transposed.at(dim).at(i) = datapoint.at(dim);
731 std::vector<std::vector<T>>
transpose(
const std::vector<std::vector<T>>& src)
735 [](std::size_t idx, std::size_t szi, std::size_t numDim)
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()};
752 auto thrower = [](std::size_t idx, std::size_t szi, std::size_t numDim)
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()};
765 LimitlessStateSeq limitlessStates;
768 LimitlessState state;
769 state.enabled = joint->isLimitless();
770 state.limitHi = joint->getJointLimitHigh();
771 state.limitLo = joint->getJointLimitLow();
772 limitlessStates.push_back(state);
774 traj->setLimitless(limitlessStates);
784 [](
const VirtualRobot::RobotNodePtr & joint)
786 return FloatRange {joint->getJointLimitLo(), joint->getJointLimitHi()};
792 Ice::StringSeq SimoxCSpace::getAgentJointNames()
const
794 Ice::StringSeq result;
795 result.reserve(getAgentJoints().size());
796 for (
const auto& e : getAgentJoints())
798 result.emplace_back(e->getName());
803 VectorXf SimoxCSpace::jointMapToVector(
const std::map<std::string, float>& jointMap,
bool checkForNonexistenJointsInCspace)
const
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)
810 auto it = jointMap.find(jointNames.at(i));
811 if (it != jointMap.end())
813 result.at(i) = it->second;
817 if (checkForNonexistenJointsInCspace && (valuesFromMapUsed != jointMap.size()))
819 throw std::invalid_argument {
"the joint map contained a joint not contained by the cspace!"};
824 SimoxCSpaceWith2DPose::SimoxCSpaceWith2DPose(memoryx::CommonStorageInterfacePrx commonStoragePrx,
bool loadVisualizationModel,
float stationaryObjectMargin):
825 SimoxCSpace(commonStoragePrx, loadVisualizationModel, stationaryObjectMargin)
833 for (
const auto& obj : stationaryObjects)
835 cloned->addStationaryObject(obj);
837 cloned->poseBounds = poseBounds;
838 cloned->agentInfo = agentInfo;
846 bounds.at(0).min = poseBounds.min.e0 ;
847 bounds.at(0).max = poseBounds.max.e0 ;
849 bounds.at(1).min = poseBounds.min.e1 ;
850 bounds.at(1).max = poseBounds.max.e1 ;
852 bounds.at(2).min = poseBounds.min.e2;
853 bounds.at(2).max = poseBounds.max.e2;
856 std::move(parentBounds.begin(), parentBounds.end(), bounds.begin() + 3);
863 joints.resize(joints.size() + 3);
864 std::move_backward(joints.begin(), joints.end() - 3, joints.end());
867 joints.at(2) =
"alpha";
876 const auto rot = *(it++);
878 const auto crot = std::cos(rot);
879 const auto srot = std::sin(rot);
894 SimoxCSpace(commonStoragePrx, loadVisualizationModel, stationaryObjectMargin)
902 for (
const auto& obj : stationaryObjects)
904 cloned->addStationaryObject(obj);
906 cloned->poseBounds = poseBounds;
907 cloned->agentInfo = agentInfo;
915 bounds.at(0).min = poseBounds.min.e0;
916 bounds.at(0).max = poseBounds.max.e0;
918 bounds.at(1).min = poseBounds.min.e1;
919 bounds.at(1).max = poseBounds.max.e1;
921 bounds.at(2).min = poseBounds.min.e2;
922 bounds.at(2).max = poseBounds.max.e2;
924 bounds.at(3).min = poseBounds.min.e3;
925 bounds.at(3).max = poseBounds.max.e3;
927 bounds.at(4).min = poseBounds.min.e4;
928 bounds.at(4).max = poseBounds.max.e4;
930 bounds.at(5).min = poseBounds.min.e5;
931 bounds.at(5).max = poseBounds.max.e5;
933 std::move(parentBounds.begin(), parentBounds.end(), bounds.begin() + 6);
943 const auto roll = *(it++);
944 const auto pitch = *(it++);
945 const auto yaw = *(it++);
947 const auto croll = std::cos(roll);
948 const auto sroll = std::sin(roll);
950 const auto cpitch = std::cos(pitch);
951 const auto spitch = std::sin(pitch);
953 const auto cyaw = std::cos(yaw);
954 const auto syaw = std::sin(yaw);
977 joints.resize(joints.size() + 6);
978 std::move_backward(joints.begin(), joints.end() - 6, joints.end());
982 joints.at(3) =
"alpha";
983 joints.at(4) =
"betha";
984 joints.at(5) =
"gamma";
988 std::vector<armarx::DebugDrawerLineSet>
SimoxCSpace::getTraceVisu(
const armarx::VectorXfSeq& vecs,
const std::vector<std::string>& nodeNames,
float traceStepSize)
990 if (traceStepSize <= 0)
992 throw std::invalid_argument {
"SimoxCSpace::getTraces: traceStepSize <= 0"};
994 std::vector<armarx::DebugDrawerLineSet> traces;
995 if (nodeNames.empty())
999 traces.resize(nodeNames.size());
1000 if (vecs.size() < 2)
1004 auto addPoints = [&]
1006 for (std::size_t i = 0; i < nodeNames.size(); ++i)
1008 const auto& name = nodeNames.at(i);
1009 armarx::DebugDrawerLineSet&
trace = traces.at(i);
1011 trace.points.emplace_back(DebugDrawerPointCloudElement {pose(0, 3), pose(1, 3), pose(2, 3)});
1014 for (std::size_t vecI = 0; vecI < vecs.size() - 1; ++vecI)
1016 const auto& vecStart = vecs.at(vecI);
1017 const auto& vecEnd = vecs.at(vecI + 1);
1018 assert(vecStart.size() == vecEnd.size());
1020 auto dist =
euclideanDistance(vecStart.begin(), vecStart.end(), vecEnd.begin());
1021 if (dist > traceStepSize)
1023 VectorXf vecCfg = vecStart;
1024 Eigen::Map<const Eigen::VectorXf> eStart {vecStart.data(),
getDimensionality()};
1028 Eigen::VectorXf eStep = (eEnd - eStart).normalized() * traceStepSize;
1030 while (dist > traceStepSize)
1036 dist -= traceStepSize;