28 #include <VirtualRobot/Robot.h>
29 #include <VirtualRobot/RobotNodeSet.h>
30 #include <VirtualRobot/Grasping/GraspSet.h>
31 #include <RobotAPI/interface/core/FramedPoseBase.h>
42 using namespace BringObjectGroup;
64 int closestChainId = -1;
68 for (
size_t i = 0; i < chains.size(); i++)
70 std::string chain = chains[i];
71 auto set =
c->getRobot()->getRobotNodeSet(chain);
72 auto distance = (
set->getTCP()->getPositionInRootFrame() - localObjectPose->toEigen().block<3, 1>(0, 3)).norm();
82 return closestChainId;
92 auto instance = in.getObjectInstanceToGraspChannel();
95 FramedPosePtr globalObjectPose =
new FramedPose(orientation->toEigen(), position->toEigen(), position->getFrame(), position->agent);
99 objectPoseRootFrame = FramedPosePtr::dynamicCast(globalObjectPose->clone());
100 objectPoseRootFrame->changeFrame(
c->getRobot(),
c->getRobot()->getRootNode()->getName());
103 if (in.isPreselectedKinematicChainSet() && in.isPreselectedMemoryHandNameSet())
105 out.setSelectedKinematicChain(in.getPreselectedKinematicChain());
106 out.setSelectedMemoryHandName(in.getPreselectedMemoryHandName());
108 else if (in.isKinematicChainsSet() && in.isMemoryHandNamesSet())
113 auto chains = in.getKinematicChains();
114 auto memoryNames = in.getMemoryHandNames();
115 int closestChainId =
getClosestTCP(objectPoseRootFrame,
c, memoryNames, chains);
117 out.setSelectedKinematicChain(chains.at(closestChainId));
118 out.setSelectedMemoryHandName(memoryNames.at(closestChainId));
122 ARMARX_ERROR <<
"Either PreselectedKinematicChainSet and PreselectedMemoryHandNameSet or KinematicChainsSet and MemoryHandNamesSet parameter must be set.";
127 ARMARX_IMPORTANT <<
"Selected Memory Name is: " << out.getSelectedMemoryHandName();
128 out.setSelectedTCP(
c->getRobot()->getRobotNodeSet(out.getSelectedKinematicChain())->getTCP()->getName());
131 std::string objectName = in.getObjectInstanceToGraspChannel()->getDataField(
"className")->getString();
133 memoryx::PersistentObjectClassSegmentBasePrx classesSegmentPrx =
c->getPriorKnowledgeProxy()->getObjectClassesSegment();
134 memoryx::CommonStorageInterfacePrx databasePrx =
c->getPriorKnowledgeProxy()->getCommonStorage();
136 memoryx::EntityBasePtr entity = classesSegmentPrx->getEntityByName(objectName);
139 VirtualRobot::ManipulationObjectPtr mo = simoxWrapper->getManipulationObject();
141 VirtualRobot::GraspSetPtr graspSet = mo->getGraspSet(out.getSelectedTCP());
143 auto findGrasp = [](VirtualRobot::GraspSetPtr graspSet,
const Ice::StringSeq & requiredInfixes,
const Ice::StringSeq & exludedInfixes)
147 auto grasps = graspSet->getGrasps();
149 for (VirtualRobot::GraspPtr grasp : grasps)
151 std::string graspName = grasp->getName();
153 for (
const auto& infix : requiredInfixes)
155 found &=
Contains(graspName, infix,
true);
157 for (
const auto& infix : exludedInfixes)
159 found &= !
Contains(graspName, infix,
true);
167 return std::string(
"");
173 std::string preposeName;
174 Ice::StringSeq infixes;
175 if (in.isGraspNameInfixSet())
177 infixes.push_back(in.getGraspNameInfix());
179 infixes.push_back({
"pre"});
181 preposeName = findGrasp(graspSet, infixes, Ice::StringSeq());
182 if (!preposeName.empty())
184 out.setGraspPreposeName(preposeName);
189 infixes.push_back({
"pre"});
190 preposeName = findGrasp(graspSet, infixes, Ice::StringSeq());
191 if (!preposeName.empty())
193 out.setGraspPreposeName(preposeName);
198 if (in.isGraspNameInfixSet())
200 infixes.push_back(in.getGraspNameInfix());
202 infixes.push_back({
"grasp"});
203 std::string graspName = findGrasp(graspSet, infixes, {
"pre"});
204 if (!graspName.empty())
206 out.setGraspName(graspName);
211 infixes.push_back({
"grasp"});
212 graspName = findGrasp(graspSet, infixes, {
"pre"});
213 if (!graspName.empty())
215 out.setGraspName(graspName);
220 auto getGraspNames = [](VirtualRobot::GraspSetPtr graspSet)
222 Ice::StringSeq graspNames;
223 for (VirtualRobot::GraspPtr& g : graspSet->getGrasps())
225 graspNames.push_back(g->getName());
230 if (!out.isGraspPreposeNameSet())
233 ARMARX_ERROR <<
"could not find any matching pre pose for " << out.getSelectedTCP() <<
" for object " << objectName <<
" - Found Grasps are: " << getGraspNames(graspSet);
234 out.setGraspPreposeName(
"");
235 out.setGraspName(
"");
241 if (!out.isGraspNameSet())
243 ARMARX_ERROR <<
"could not find any matching grasp pose for " << out.getSelectedTCP() <<
" for object " << objectName <<
" - Found Grasps are: " << getGraspNames(graspSet);
244 out.setGraspPreposeName(
"");
245 out.setGraspName(
"");
254 ARMARX_ERROR <<
"graspSet Ptr NULL - Could not find grasp set for tcp " << out.getSelectedTCP() <<
" for object " << objectName;
260 Eigen::Vector3f tcpPosition =
c->getRobot()->getRobotNodeSet(out.getSelectedKinematicChain())->getTCP()->getPositionInRootFrame();
261 if (tcpPosition[0] < 0)
263 out.setPregraspArmConfig(in.getPregraspArmConfigLeft());
267 out.setPregraspArmConfig(in.getPregraspArmConfigRight());
271 if (in.getUsePlatform())
274 Eigen::Vector3f objPosRootFrame = Vector3Ptr::dynamicCast(objectPoseRootFrame->position)->toEigen();
277 Eigen::Vector3f newPlatformPos = objPosRootFrame;
280 if (tcpPosition[0] < 0)
282 offset = in.getPlatformToObjectOffsetLeft();
286 offset = in.getPlatformToObjectOffsetRight();
289 newPlatformPos[0] += offset->x;
290 newPlatformPos[1] += offset->y;
292 if (fabs(newPlatformPos[1]) > 500)
294 ARMARX_ERROR <<
"Target platform pose is too far away: " << newPlatformPos;
298 ARMARX_INFO <<
"rootnode pose: " <<
c->getRobot()->getRootNode()->getGlobalPose();
299 Eigen::Vector3f newGlobalPlatformPos =
c->getRobot()->getRootNode()->toGlobalCoordinateSystemVec(newPlatformPos);
300 Eigen::Matrix3f rotMat =
c->getRobot()->getRootNode()->getGlobalPose().block<3, 3>(0, 0);
302 ARMARX_INFO <<
"Root Node: " <<
c->getRobot()->getRootNode()->getName();
303 ARMARX_INFO <<
c->getRobot()->getRootNode()->getGlobalPose().block<3, 3>(0, 0);
305 Eigen::Vector3f x = rotMat * Eigen::Vector3f::UnitX();
306 newGlobalPlatformPos[2] = atan2(x[1], x[0]);
307 std::vector<Vector3Ptr> pose;
310 Eigen::Vector3f platformPos =
c->getRobot()->getRootNode()->getGlobalPose().block<3, 1>(0, 3);
312 if (in.isMaxPlatformMotionXSet() && fabs(newGlobalPlatformPos[0] - platformPos[0]) > in.getMaxPlatformMotionX())
314 newGlobalPlatformPos[0] = platformPos[0] + std::copysign(in.getMaxPlatformMotionX(), newGlobalPlatformPos[0] - platformPos[0]);
315 ARMARX_WARNING <<
"Platform motion clamped to maximum in X direction: " << newGlobalPlatformPos[0];
318 if (in.isMaxPlatformMotionYSet() && fabs(newGlobalPlatformPos[1] - platformPos[1]) > in.getMaxPlatformMotionY())
320 newGlobalPlatformPos[1] = platformPos[1] + std::copysign(in.getMaxPlatformMotionY(), newGlobalPlatformPos[1] - platformPos[1]);
321 ARMARX_WARNING <<
"Platform motion clamped to maximum in Y direction: " << newGlobalPlatformPos[1];
334 pose.push_back(newPlatformVec);
336 out.setPlatformTargetPose(pose);
337 emitArmSelectedMovePlatform();