29 #include <VirtualRobot/Grasping/Grasp.h>
30 #include <VirtualRobot/Grasping/GraspSet.h>
31 #include <VirtualRobot/Robot.h>
32 #include <VirtualRobot/RobotNodeSet.h>
36 #include <RobotAPI/interface/core/FramedPoseBase.h>
47 using namespace BringObjectGroup;
69 const std::vector<std::string>& memoryNames,
70 const std::vector<std::string>& chains)
72 int closestChainId = -1;
76 for (
size_t i = 0; i < chains.size(); i++)
78 std::string chain = chains[i];
79 auto set =
c->getRobot()->getRobotNodeSet(chain);
81 (
set->getTCP()->getPositionInRootFrame() - localObjectPose->toEigen().block<3, 1>(0, 3))
92 return closestChainId;
103 auto instance = in.getObjectInstanceToGraspChannel();
107 orientation->toEigen(), position->toEigen(), position->getFrame(), position->agent);
111 objectPoseRootFrame = FramedPosePtr::dynamicCast(globalObjectPose->clone());
112 objectPoseRootFrame->changeFrame(
c->getRobot(),
c->getRobot()->getRootNode()->getName());
115 if (in.isPreselectedKinematicChainSet() && in.isPreselectedMemoryHandNameSet())
117 out.setSelectedKinematicChain(in.getPreselectedKinematicChain());
118 out.setSelectedMemoryHandName(in.getPreselectedMemoryHandName());
120 else if (in.isKinematicChainsSet() && in.isMemoryHandNamesSet())
125 auto chains = in.getKinematicChains();
126 auto memoryNames = in.getMemoryHandNames();
127 int closestChainId =
getClosestTCP(objectPoseRootFrame,
c, memoryNames, chains);
129 out.setSelectedKinematicChain(chains.at(closestChainId));
130 out.setSelectedMemoryHandName(memoryNames.at(closestChainId));
134 ARMARX_ERROR <<
"Either PreselectedKinematicChainSet and PreselectedMemoryHandNameSet or "
135 "KinematicChainsSet and MemoryHandNamesSet parameter must be set.";
140 ARMARX_IMPORTANT <<
"Selected Memory Name is: " << out.getSelectedMemoryHandName();
142 c->getRobot()->getRobotNodeSet(out.getSelectedKinematicChain())->getTCP()->getName());
145 std::string objectName =
146 in.getObjectInstanceToGraspChannel()->getDataField(
"className")->getString();
148 memoryx::PersistentObjectClassSegmentBasePrx classesSegmentPrx =
149 c->getPriorKnowledgeProxy()->getObjectClassesSegment();
150 memoryx::CommonStorageInterfacePrx databasePrx =
151 c->getPriorKnowledgeProxy()->getCommonStorage();
153 memoryx::EntityBasePtr entity = classesSegmentPrx->getEntityByName(objectName);
157 VirtualRobot::ManipulationObjectPtr mo = simoxWrapper->getManipulationObject();
159 VirtualRobot::GraspSetPtr graspSet = mo->getGraspSet(out.getSelectedTCP());
161 auto findGrasp = [](VirtualRobot::GraspSetPtr graspSet,
162 const Ice::StringSeq& requiredInfixes,
163 const Ice::StringSeq& exludedInfixes)
167 auto grasps = graspSet->getGrasps();
169 for (VirtualRobot::GraspPtr grasp : grasps)
171 std::string graspName = grasp->getName();
173 for (
const auto& infix : requiredInfixes)
175 found &=
Contains(graspName, infix,
true);
177 for (
const auto& infix : exludedInfixes)
179 found &= !
Contains(graspName, infix,
true);
187 return std::string(
"");
193 std::string preposeName;
194 Ice::StringSeq infixes;
195 if (in.isGraspNameInfixSet())
197 infixes.push_back(in.getGraspNameInfix());
199 infixes.push_back({
"pre"});
201 preposeName = findGrasp(graspSet, infixes, Ice::StringSeq());
202 if (!preposeName.empty())
204 out.setGraspPreposeName(preposeName);
209 infixes.push_back({
"pre"});
210 preposeName = findGrasp(graspSet, infixes, Ice::StringSeq());
211 if (!preposeName.empty())
213 out.setGraspPreposeName(preposeName);
218 if (in.isGraspNameInfixSet())
220 infixes.push_back(in.getGraspNameInfix());
222 infixes.push_back({
"grasp"});
223 std::string graspName = findGrasp(graspSet, infixes, {
"pre"});
224 if (!graspName.empty())
226 out.setGraspName(graspName);
231 infixes.push_back({
"grasp"});
232 graspName = findGrasp(graspSet, infixes, {
"pre"});
233 if (!graspName.empty())
235 out.setGraspName(graspName);
240 auto getGraspNames = [](VirtualRobot::GraspSetPtr graspSet)
242 Ice::StringSeq graspNames;
243 for (VirtualRobot::GraspPtr& g : graspSet->getGrasps())
245 graspNames.push_back(g->getName());
250 if (!out.isGraspPreposeNameSet())
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(
"");
262 if (!out.isGraspNameSet())
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(
"");
275 ARMARX_ERROR <<
"graspSet Ptr NULL - Could not find grasp set for tcp "
276 << out.getSelectedTCP() <<
" for object " << objectName;
282 Eigen::Vector3f tcpPosition =
c->getRobot()
283 ->getRobotNodeSet(out.getSelectedKinematicChain())
285 ->getPositionInRootFrame();
286 if (tcpPosition[0] < 0)
288 out.setPregraspArmConfig(in.getPregraspArmConfigLeft());
292 out.setPregraspArmConfig(in.getPregraspArmConfigRight());
296 if (in.getUsePlatform())
299 Eigen::Vector3f objPosRootFrame =
300 Vector3Ptr::dynamicCast(objectPoseRootFrame->position)->toEigen();
303 Eigen::Vector3f newPlatformPos = objPosRootFrame;
306 if (tcpPosition[0] < 0)
308 offset = in.getPlatformToObjectOffsetLeft();
312 offset = in.getPlatformToObjectOffsetRight();
315 newPlatformPos[0] += offset->x;
316 newPlatformPos[1] += offset->y;
318 if (fabs(newPlatformPos[1]) > 500)
320 ARMARX_ERROR <<
"Target platform pose is too far away: " << 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);
329 ARMARX_INFO <<
"Root Node: " <<
c->getRobot()->getRootNode()->getName();
330 ARMARX_INFO <<
c->getRobot()->getRootNode()->getGlobalPose().block<3, 3>(0, 0);
332 Eigen::Vector3f x = rotMat * Eigen::Vector3f::UnitX();
333 newGlobalPlatformPos[2] = atan2(x[1], x[0]);
334 std::vector<Vector3Ptr> pose;
337 Eigen::Vector3f platformPos =
338 c->getRobot()->getRootNode()->getGlobalPose().block<3, 1>(0, 3);
340 if (in.isMaxPlatformMotionXSet() &&
341 fabs(newGlobalPlatformPos[0] - platformPos[0]) > in.getMaxPlatformMotionX())
343 newGlobalPlatformPos[0] =
345 std::copysign(in.getMaxPlatformMotionX(), newGlobalPlatformPos[0] - platformPos[0]);
346 ARMARX_WARNING <<
"Platform motion clamped to maximum in X direction: "
347 << newGlobalPlatformPos[0];
350 if (in.isMaxPlatformMotionYSet() &&
351 fabs(newGlobalPlatformPos[1] - platformPos[1]) > in.getMaxPlatformMotionY())
353 newGlobalPlatformPos[1] =
355 std::copysign(in.getMaxPlatformMotionY(), newGlobalPlatformPos[1] - platformPos[1]);
356 ARMARX_WARNING <<
"Platform motion clamped to maximum in Y direction: "
357 << newGlobalPlatformPos[1];
370 pose.push_back(newPlatformVec);
372 out.setPlatformTargetPose(pose);
373 emitArmSelectedMovePlatform();