BodySymmetry::BodySymmetry(BodyPtr body) : body(body) { const YamlSequence& sjoints = *body->info()->findSequence("symmetricJoints"); if(sjoints.isValid() && !sjoints.empty()){ for(int i=0; i < sjoints.size(); ++i){ const YamlSequence& jointPair = *sjoints[i].toSequence(); if(jointPair.size() == 1){ Link* link = body->link(jointPair[0].toString()); if(link){ JointSymmetry& symmetry = jointSymmetryMap[link->jointId]; symmetry.counterPartJointId = link->jointId; symmetry.jointPositionSign = -1.0; symmetry.offset = 0.0; } } else if(jointPair.size() >= 2){ Link* joint[2]; joint[0] = body->link(jointPair[0].toString()); joint[1] = body->link(jointPair[1].toString()); if(joint[0] && joint[1] && joint[0]->jointId >= 0 && joint[1]->jointId >= 0){ for(int j=0; j < 2; ++j){ int other = 1 - j; JointSymmetry& symmetry = jointSymmetryMap[joint[j]->jointId]; symmetry.counterPartJointId = joint[other]->jointId; symmetry.sign = (jointPair.size() >= 3) ? jointPair[2].toDouble() : 1.0; symmetry.offset = (jointPair.size() >= 4) ? jointPair[3].toDouble() : 0.0; } } } } } const YamlSequence& slinks = *body->info()->findSequence("symmetricIkLinks"); if(slinks.isValid() && !slinks.empty()){ for(int i=0; i < slinks.size(); ++i){ const YamlSequence& linkPair = *slinks[i].toSequence(); if(linkPair.size() == 1){ Link* link = body->link(linkPair[0].toString()); if(link){ LinkSymmetry& symmetry = linkFlipMap[link->index]; symmetry.counterPartIndex = link->index; } } else if(linkPair.size() >= 2){ Link* link[2]; link[0] = body->link(linkPair[0].toString()); link[1] = body->link(linkPair[1].toString()); if(link[0] && link[1]){ for(int j=0; j < 2; ++j){ int other = 1 - j; LinkSymmetry& symmetry = linkFlipMap[link[j]->index]; symmetry.counterPartIndex = link[other]->index; } } } } } }
void BodyBarImpl::onSymmetricCopyButtonClicked(int direction, bool doMirrorCopy) { for(size_t i=0; i < targetBodyItems.size(); ++i){ const Listing& slinks = *targetBodyItems[i]->body()->info()->findListing("symmetricJoints"); if(slinks.isValid() && !slinks.empty()){ targetBodyItems[i]->beginKinematicStateEdit(); int from = direction; int to = 1 - direction; BodyPtr body = targetBodyItems[i]->body(); for(int j=0; j < slinks.size(); ++j){ const Listing& linkPair = *slinks[j].toListing(); if(linkPair.size() == 1 && doMirrorCopy){ Link* link = body->link(linkPair[0].toString()); if(link){ link->q() = -link->q(); } } else if(linkPair.size() >= 2){ Link* link1 = body->link(linkPair[from].toString()); Link* link2 = body->link(linkPair[to].toString()); if(link1 && link2){ double sign = 1.0; if(linkPair.size() >= 3){ sign = linkPair[2].toDouble(); } if(doMirrorCopy){ double q1 = link1->q(); link1->q() = sign * link2->q(); link2->q() = sign * q1; } else { link2->q() = sign * link1->q(); } } } } targetBodyItems[i]->notifyKinematicStateChange(true); targetBodyItems[i]->acceptKinematicStateEdit(); } } }
void BodyLinkViewImpl::update() { currentLink = 0; if(!currentBodyItem){ nameLabel.setText(""); return; } propertyWidgetConnections.block(); stateWidgetConnections.block(); BodyPtr body = currentBodyItem->body(); const vector<int>& selectedLinkIndices = LinkSelectionView::mainInstance()->getSelectedLinkIndices(currentBodyItem); if(selectedLinkIndices.empty()){ currentLink = body->rootLink(); } else { currentLink = body->link(selectedLinkIndices.front()); } if(currentLink){ nameLabel.setText(QString("%1 / %2").arg(body->name().c_str()).arg(currentLink->name().c_str())); updateLink(); } else { nameLabel.setText(body->name().c_str()); } if(currentBodyItem->isLeggedBody()){ zmpBox.show(); } else { zmpBox.hide(); } updateKinematicState(false); updateCollisions(); stateWidgetConnections.unblock(); propertyWidgetConnections.unblock(); }
void MultiAffine3SeqGraphView::setupGraphWidget() { graph.clearDataHandlers(); for(list<ItemInfo>::iterator it = itemInfos.begin(); it != itemInfos.end(); ++it){ if(it->bodyItem){ MultiAffine3SeqPtr seq = it->item->seq(); int numParts = seq->numParts(); BodyPtr body = it->bodyItem->body(); const std::vector<int>& selectedLinkIndices = linkSelection->getSelectedLinkIndices(it->bodyItem); for(size_t i=0; i < selectedLinkIndices.size(); ++i){ Link* link = body->link(selectedLinkIndices[i]); if(link && link->index < numParts){ addPositionTrajectory(it, link, seq); } } } } }
int KinematicFaultCheckerImpl::checkFaults (BodyItem* bodyItem, BodyMotionItem* motionItem, std::ostream& os, bool checkPosition, bool checkVelocity, bool checkCollision, dynamic_bitset<> linkSelection, double beginningTime, double endingTime) { numFaults = 0; BodyPtr body = bodyItem->body(); BodyMotionPtr motion = motionItem->motion(); MultiValueSeqPtr qseq = motion->jointPosSeq();; MultiSE3SeqPtr pseq = motion->linkPosSeq(); if((!checkPosition && !checkVelocity && !checkCollision) || body->isStaticModel() || !qseq->getNumFrames()){ return numFaults; } BodyState orgKinematicState; if(USE_DUPLICATED_BODY){ body = body->clone(); } else { bodyItem->storeKinematicState(orgKinematicState); } CollisionDetectorPtr collisionDetector; WorldItem* worldItem = bodyItem->findOwnerItem<WorldItem>(); if(worldItem){ collisionDetector = worldItem->collisionDetector()->clone(); } else { int index = CollisionDetector::factoryIndex("AISTCollisionDetector"); if(index >= 0){ collisionDetector = CollisionDetector::create(index); } else { collisionDetector = CollisionDetector::create(0); os << _("A collision detector is not found. Collisions cannot be detected this time.") << endl; } } addBodyToCollisionDetector(*body, *collisionDetector); collisionDetector->makeReady(); const int numJoints = std::min(body->numJoints(), qseq->numParts()); const int numLinks = std::min(body->numLinks(), pseq->numParts()); frameRate = motion->frameRate(); double stepRatio2 = 2.0 / frameRate; angleMargin = radian(angleMarginSpin.value()); translationMargin = translationMarginSpin.value(); velocityLimitRatio = velocityLimitRatioSpin.value() / 100.0; int beginningFrame = std::max(0, (int)(beginningTime * frameRate)); int endingFrame = std::min((motion->numFrames() - 1), (int)lround(endingTime * frameRate)); lastPosFaultFrames.clear(); lastPosFaultFrames.resize(numJoints, std::numeric_limits<int>::min()); lastVelFaultFrames.clear(); lastVelFaultFrames.resize(numJoints, std::numeric_limits<int>::min()); lastCollisionFrames.clear(); if(checkCollision){ Link* root = body->rootLink(); root->p().setZero(); root->R().setIdentity(); } for(int frame = beginningFrame; frame <= endingFrame; ++frame){ int prevFrame = (frame == beginningFrame) ? beginningFrame : frame - 1; int nextFrame = (frame == endingFrame) ? endingFrame : frame + 1; for(int i=0; i < numJoints; ++i){ Link* joint = body->joint(i); double q = qseq->at(frame, i); joint->q() = q; if(joint->index() >= 0 && linkSelection[joint->index()]){ if(checkPosition){ bool fault = false; if(joint->isRotationalJoint()){ fault = (q > (joint->q_upper() - angleMargin) || q < (joint->q_lower() + angleMargin)); } else if(joint->isSlideJoint()){ fault = (q > (joint->q_upper() - translationMargin) || q < (joint->q_lower() + translationMargin)); } if(fault){ putJointPositionFault(frame, joint, os); } } if(checkVelocity){ double dq = (qseq->at(nextFrame, i) - qseq->at(prevFrame, i)) / stepRatio2; joint->dq() = dq; if(dq > (joint->dq_upper() * velocityLimitRatio) || dq < (joint->dq_lower() * velocityLimitRatio)){ putJointVelocityFault(frame, joint, os); } } } } if(checkCollision){ Link* link = body->link(0); if(!pseq->empty()) { const SE3& p = pseq->at(frame, 0); link->p() = p.translation(); link->R() = p.rotation().toRotationMatrix(); } else { link->p() = Vector3d(0., 0., 0.); link->R() = Matrix3d::Identity(); } body->calcForwardKinematics(); for(int i=1; i < numLinks; ++i){ link = body->link(i); if(!pseq->empty()) { const SE3& p = pseq->at(frame, i); link->p() = p.translation(); link->R() = p.rotation().toRotationMatrix(); } } for(int i=0; i < numLinks; ++i){ link = body->link(i); collisionDetector->updatePosition(i, link->position()); } collisionDetector->detectCollisions( boost::bind(&KinematicFaultCheckerImpl::putSelfCollision, this, body.get(), frame, _1, boost::ref(os))); } } if(!USE_DUPLICATED_BODY){ bodyItem->restoreKinematicState(orgKinematicState); } return numFaults; }
virtual bool initialize() { if(!qseq){ string filename = getNativePathString( boost::filesystem::path(shareDirectory()) / "motion" / "SR1" / "SR1WalkPattern3.yaml"); BodyMotion motion; if(!motion.loadStandardYAMLformat(filename)){ os() << motion.seqMessage() << endl; return false; } qseq = motion.jointPosSeq(); if(qseq->numFrames() == 0){ os() << "Empty motion data." << endl; return false; } timeStep_ = qseq->getTimeStep(); } if(fabs(timeStep() - timeStep_) > 1.0e-6){ os() << "Time step must be " << timeStep_ << "." << endl;; return false; } body = ioBody(); rarm_shoulder_p = body->link("RARM_SHOULDER_P")->jointId(); rarm_shoulder_r = body->link("RARM_SHOULDER_R")->jointId(); rarm_elbow = body->link("RARM_ELBOW")->jointId(); rarm_wrist_y = body->link("RARM_WRIST_Y")->jointId(); rarm_wrist_r = body->link("RARM_WRIST_R")->jointId(); rhsensor = body->findDevice<ForceSensor>("rhsensor"); numJoints = body->numJoints(); if(numJoints != qseq->numParts()){ os() << "The number of joints must be " << qseq->numParts() << endl; return false; } qold.resize(numJoints); VectorXd q0(numJoints); VectorXd q1(numJoints); for(int i=0; i < numJoints; ++i){ qold[i] = q0[i] = body->joint(i)->q(); } MultiValueSeq::Frame frame = qseq->frame(0); for(int i=0; i < numJoints; ++i){ q1[i] = frame[i]; } interpolator.clear(); interpolator.appendSample(0.0, q0); interpolator.appendSample(2.0, q1); interpolator.update(); qref_old = interpolator.interpolate(0.0); currentFrame = 0; phase = 0; time = 0.0; return true; }
int main(int argc, char *argv[]) { srand((unsigned)time(NULL)); const char *robotURL = NULL; std::vector<std::string> obstacleURL; std::vector<Vector3> obstacleP; std::vector<Vector3> obstacleRpy; for(int i = 1 ; i < argc; i++) { if (strcmp(argv[i], "-robot") == 0) { robotURL = argv[++i]; } else if (strcmp(argv[i], "-obstacle") == 0) { obstacleURL.push_back(argv[++i]); Vector3 p, rpy; for (int j=0; j<3; j++) p[j] = atof(argv[++i]); obstacleP.push_back(p); for (int j=0; j<3; j++) rpy[j] = atof(argv[++i]); obstacleRpy.push_back(rpy); } } if (robotURL == NULL) { std::cerr << "please specify URL of VRML model by -robot option" << std::endl; return 1; } BodyPtr robot = new Body(); loadBodyFromModelLoader(robot, robotURL, argc, argv, true); problem prob; prob.addRobot("robot", robotURL, robot); std::vector<BodyPtr> obstacles; for (unsigned int i=0; i<obstacleURL.size(); i++) { char buf[20]; sprintf(buf, "obstacle%02d", i); obstacles.push_back(prob.addObstacle(buf, obstacleURL[i])); } // This must be called after all bodies are added prob.initOLV(argc, argv); PathEngine::Configuration::size(4+6+6); PathEngine::Configuration::bounds(0, 0.2, 0.8); // body z PathEngine::Configuration::bounds(1, -0.5, 0.5); // body roll PathEngine::Configuration::bounds(2, -0.0, 0.5); // body pitch PathEngine::Configuration::bounds(3, -0.5, 0.5); // body yaw int arm; PathEngine::Configuration goalCfg; std::ifstream ifs("goal.txt"); ifs >> arm; for (unsigned int i=0; i<PathEngine::Configuration::size(); i++) { ifs >> goalCfg[i]; } #if 1 PathEngine::Configuration::weight(0) = 0.1; // z PathEngine::Configuration::weight(1) = 1; // roll PathEngine::Configuration::weight(2) = 1; // pitch PathEngine::Configuration::weight(3) = 1; // yaw PathEngine::Configuration::weight(4) = 0.8; PathEngine::Configuration::weight(5) = 0.6; PathEngine::Configuration::weight(6) = 0.4; PathEngine::Configuration::weight(7) = 0.3; PathEngine::Configuration::weight(8) = 0.2; PathEngine::Configuration::weight(9) = 0.1; PathEngine::Configuration::weight(10) = 0.8; PathEngine::Configuration::weight(11) = 0.6; PathEngine::Configuration::weight(12) = 0.4; PathEngine::Configuration::weight(13) = 0.3; PathEngine::Configuration::weight(14) = 0.2; PathEngine::Configuration::weight(15) = 0.1; #endif JointPathPtr armPath[2]; Link *chest = robot->link("CHEST_JOINT1"); Link *wrist[2] = {robot->link("RARM_JOINT5"), robot->link("LARM_JOINT5") }; for (int k=0; k<2; k++) { armPath[k] = robot->getJointPath(chest, wrist[k]); for (int i=0; i<armPath[k]->numJoints(); i++) { Link *j = armPath[k]->joint(i); PathEngine::Configuration::bounds(4+k*6+i, j->llimit, j->ulimit); } } PathEngine::PathPlanner *planner = prob.planner(); planner->setMobilityName("OmniWheel"); planner->setAlgorithmName("RRT"); PathEngine::RRT *rrt = (PathEngine::RRT *)planner->getAlgorithm(); rrt->extendFromGoal(true); planner->getAlgorithm()->setProperty("eps", "0.1"); planner->getAlgorithm()->setProperty("max-trials", "50000"); planner->getAlgorithm()->setProperty("interpolation-distance", "0.05"); prob.initCollisionCheckPairs(); prob.initPlanner(); for (unsigned int i=0; i<obstacles.size(); i++) { Link *root = obstacles[i]->rootLink(); root->p = obstacleP[i]; root->R = rotFromRpy(obstacleRpy[i]); root->coldetModel->setPosition(root->R, root->p); obstacles[i]->calcForwardKinematics(); } // set halfconf dvector halfconf; halfconf.setZero(robot->numJoints()); #define ToRad(x) ((x)*M_PI/180) halfconf[2] = halfconf[ 8] = ToRad(-40); halfconf[3] = halfconf[ 9] = ToRad( 78); halfconf[4] = halfconf[10] = ToRad(-38); double leg_link_len1=0, leg_link_len2=0; halfconf[16] = halfconf[23] = ToRad(20); halfconf[17] = ToRad(-10); halfconf[24] = -halfconf[17]; halfconf[19] = halfconf[26] = ToRad(-30); if (robot->modelName() == "HRP2") { halfconf[20] = ToRad(80); halfconf[27] = -halfconf[20]; halfconf[22] = halfconf[29] = -1.0; } leg_link_len1 = leg_link_len2 = 0.3; double waistHeight = leg_link_len1*cos(halfconf[2]) + leg_link_len2*cos(halfconf[4]) + 0.105; robot->rootLink()->p(2) = waistHeight; for (int i=0; i<robot->numJoints(); i++) { robot->joint(i)->q = halfconf[i]; } robot->calcForwardKinematics(); myCfgSetter setter(robot); PathEngine::Configuration startCfg; startCfg[0] = robot->rootLink()->p[2]; startCfg[1] = startCfg[2] = startCfg[3] = 0; for (int j=0; j<2; j++) { for (int i=0; i<armPath[j]->numJoints(); i++) { startCfg[4+j*6+i] = armPath[j]->joint(i)->q; } } planner->setStartConfiguration(startCfg); planner->setGoalConfiguration(goalCfg); planner->setApplyConfigFunc(boost::bind(&myCfgSetter::set, &setter, _1, _2)); planner->setConfiguration(startCfg); prob.updateOLV(); planner->setConfiguration(goalCfg); prob.updateOLV(); #if 0 int earm; ifs >> earm; while (!ifs.eof()) { PathEngine::Configuration cfg; for (unsigned int i=0; i<PathEngine::Configuration::size(); i++) { ifs >> cfg[i]; } if (arm == earm) { rrt->addExtraGoal(cfg); std::cout << "added an extra goal" << std::endl; planner->setConfiguration(cfg); prob.updateOLV(); } ifs >> earm; } #endif CustomCD cd(robot, "hrp2.shape", "hrp2.pairs", obstacles[0], "plant.pc"); prob.planner()->setCollisionDetector(&cd); struct timeval tv1, tv2; gettimeofday(&tv1, NULL); // plan bool ret = planner->calcPath(); if (ret) { for (int i=0; i<5; i++) { planner->optimize("Shortcut"); planner->optimize("RandomShortcut"); } } gettimeofday(&tv2, NULL); if (ret) { const std::vector<PathEngine::Configuration>& postures = planner->getWayPoints(); std::ofstream ofs("path.txt"); ofs << arm << std::endl; for (unsigned int i=0; i<postures.size(); i++) { planner->setConfiguration(postures[i]); for (int j=0; j<3; j++) { ofs << robot->rootLink()->p[j] << " "; } for (int j=0; j<3; j++) { for (int k=0; k<3; k++) { ofs << robot->rootLink()->R(j,k) << " "; } } for (int j=0; j<robot->numJoints(); j++) { ofs << robot->joint(j)->q << " "; } ofs << std::endl; prob.updateOLV(); } } else { PathEngine::Roadmap *roadmap = planner->getRoadmap(); for (unsigned int i=0; i<roadmap->nNodes(); i++) { PathEngine::RoadmapNode *node = roadmap->node(i); planner->setConfiguration(node->position()); prob.updateOLV(); } } double time = (tv2.tv_sec - tv1.tv_sec) + ((double)(tv2.tv_usec - tv1.tv_usec))/1e6; std::cout << "total time = " << time << "[s]" << std::endl; double cdtime = prob.planner()->timeCollisionCheck(); std::cout << "time spent in collision detection:" << cdtime << "[s](" << cdtime/time*100 << "[%]), " << cdtime*1e3/prob.planner()->countCollisionCheck() << "[ms/call]" << std::endl; std::cout << "profile:"; setter.profile(); return 0; }
int main(int argc, char *argv[]) { OnlineViewer_var olv; olv = hrp::getOnlineViewer(argc, argv); olv->load("robot", url); olv->clearLog(); BodyPtr body = BodyPtr(new Body()); loadBodyFromModelLoader(body, url, argc, argv, true); body->setName("robot"); convertToConvexHull(body); WorldState wstate; wstate.time = 0.0; wstate.characterPositions.length(1); setupCharacterPosition(wstate.characterPositions[0], body); wstate.collisions.length(3); // ワイヤの固定部 std::vector<Anchor> anchors; anchors.push_back(Anchor(body->link("CHEST_Y"), Vector3(-0.03, 0.1,0.35))); anchors.push_back(Anchor(body->link("R_HIP_P"), Vector3(-0.08,0,-0.2))); anchors.push_back(Anchor(body->link("CHEST_Y"), Vector3(-0.03,-0.1,0.35))); anchors.push_back(Anchor(body->link("L_HIP_P"), Vector3(-0.08,0,-0.2))); wstate.collisions.length(anchors.size()+1); for (size_t i=1; i<wstate.collisions.length(); i++){ setupFrame(wstate.collisions[i], 0.05); } // ワイヤと接触するリンクセットその1 std::vector<Link *> linkset1; linkset1.push_back(body->link("CHEST_Y")); linkset1.push_back(body->link("WAIST")); linkset1.push_back(body->link("R_HIP_P")); // ワイヤと接触するリンクセットその2 std::vector<Link *> linkset2; linkset2.push_back(body->link("CHEST_Y")); linkset2.push_back(body->link("WAIST")); linkset2.push_back(body->link("L_HIP_P")); // ワイヤ(両端点及びリンクセット)の定義 std::vector<String> strings; strings.push_back(String(&anchors[0], &anchors[1], linkset1)); strings.push_back(String(&anchors[2], &anchors[3], linkset2)); std::ifstream ifs(logfile); if (!ifs.is_open()){ std::cerr << "failed to open the log file:" << logfile << std::endl; return 1; } char buf[1024]; ifs.getline(buf, 1024); // skip header double q; while(1){ for (int i=0; i<body->numJoints(); i++){ ifs >> q; if (ifs.eof()) return 0; Link *j = body->joint(i); if (j) j->q = q; } ifs.getline(buf, 1024); // skip rest of the line body->calcForwardKinematics(); for (size_t i=0; i<strings.size(); i++){ if (!strings[i].update()){ std::cerr << "failed to update string state" << std::endl; } } // update body updateCharacterPosition(wstate.characterPositions[0], body); // update anchors for (size_t i=0; i<anchors.size(); i++){ updateFrame(wstate.collisions[i+1], anchors[i].position(), Matrix33::Identity()); } // update strings size_t n=0, index=0; for (size_t i=0; i<strings.size(); i++){ n += strings[i].polyLine.lines.size(); } wstate.collisions[0].points.length(n); for (size_t i=0; i<strings.size(); i++){ const std::vector<LineSegment>& lines = strings[i].polyLine.lines; for (size_t i=0; i<lines.size(); i++){ updateLineSegment(wstate.collisions[0].points[index++], lines[i].first, lines[i].second); } } olv->update(wstate); wstate.time += 0.005; std::cout << wstate.time << " "; for (size_t i=0; i<strings.size(); i++){ std::cout << strings[i].length() << " "; } std::cout << std::endl; } return 0; }
bool PoseProviderToBodyMotionConverter::convert(BodyPtr body, PoseProvider* provider, BodyMotion& motion) { const double frameRate = motion.frameRate(); const int beginningFrame = static_cast<int>(frameRate * std::max(provider->beginningTime(), lowerTime)); const int endingFrame = static_cast<int>(frameRate * std::min(provider->endingTime(), upperTime)); const int numJoints = body->numJoints(); const int numLinksToPut = (allLinkPositionOutputMode ? body->numLinks() : 1); motion.setDimension(endingFrame + 1, numJoints, numLinksToPut, true); MultiValueSeq& qseq = *motion.jointPosSeq(); MultiAffine3Seq& pseq = *motion.linkPosSeq(); Vector3Seq& relZmpSeq = *motion.relativeZmpSeq(); bool isZmpValid = false; Link* rootLink = body->rootLink(); Link* baseLink = rootLink; shared_ptr<LinkTraverse> fkTraverse; if(allLinkPositionOutputMode){ fkTraverse.reset(new LinkTraverse(baseLink, true, true)); } else { fkTraverse.reset(new LinkPath(baseLink, rootLink)); } // store the original state vector<double> orgq(numJoints); for(int i=0; i < numJoints; ++i){ orgq[i] = body->joint(i)->q; } Affine3 orgp; orgp.translation() = rootLink->p; orgp.linear() = rootLink->R; std::vector< boost::optional<double> > jointPositions(numJoints); for(int frame = beginningFrame; frame <= endingFrame; ++frame){ provider->seek(frame / frameRate); const int baseLinkIndex = provider->baseLinkIndex(); if(baseLinkIndex >= 0){ if(baseLinkIndex != baseLink->index){ baseLink = body->link(baseLinkIndex); if(allLinkPositionOutputMode){ fkTraverse->find(baseLink, true, true); } else { static_pointer_cast<LinkPath>(fkTraverse)->find(baseLink, rootLink); } } provider->getBaseLinkPosition(baseLink->p, baseLink->R); } MultiValueSeq::View qs = qseq.frame(frame); provider->getJointPositions(jointPositions); for(int i=0; i < numJoints; ++i){ const optional<double>& q = jointPositions[i]; qs[i] = q ? *q : 0.0; body->joint(i)->q = qs[i]; } if(allLinkPositionOutputMode || baseLink != rootLink){ fkTraverse->calcForwardKinematics(); } for(int i=0; i < numLinksToPut; ++i){ Affine3& p = pseq.at(frame, i); Link* link = body->link(i); p.translation() = link->p; p.linear() = link->R; } optional<Vector3> zmp = provider->zmp(); if(zmp){ relZmpSeq[frame].noalias() = rootLink->R.transpose() * (*zmp - rootLink->p); isZmpValid = true; } } if(!isZmpValid){ //bodyMotionItem->clearRelativeZmpSeq(); } // restore the original state for(int i=0; i < numJoints; ++i){ body->joint(i)->q = orgq[i]; } rootLink->p = orgp.translation(); rootLink->R = orgp.linear(); body->calcForwardKinematics(); return true; }
bool PoseSeqItem::convertSub(BodyPtr orgBody, const Mapping& convInfo) { bool converted = false; const Listing& jointMap = *convInfo.findListing("jointMap"); const Mapping& linkMap = *convInfo.findMapping("linkMap"); BodyPtr body = ownerBodyItem->body(); for(PoseSeq::iterator p = seq->begin(); p != seq->end(); ++p){ PosePtr pose = p->get<Pose>(); if(pose){ bool modified = false; seq->beginPoseModification(p); PosePtr orgPose = dynamic_cast<Pose*>(pose->duplicate()); if(jointMap.isValid()){ modified = true; pose->setNumJoints(0); int n = orgPose->numJoints(); for(int i=0; i < n; ++i){ if(orgPose->isJointValid(i)){ if(i < jointMap.size()){ int newJointId = jointMap[i].toInt(); if(newJointId >= 0){ pose->setJointPosition(newJointId, orgPose->jointPosition(i)); pose->setJointStationaryPoint(newJointId, orgPose->isJointStationaryPoint(i)); } } } } } if(linkMap.isValid()){ modified = true; pose->clearIkLinks(); int baseLinkIndex = -1; for(Pose::LinkInfoMap::const_iterator q = orgPose->ikLinkBegin(); q != orgPose->ikLinkEnd(); ++q){ Link* orgLink = orgBody->link(q->first); string linkName; ValueNode* linkNameNode = linkMap.find(orgLink->name()); if(linkNameNode->isValid()){ linkName = linkNameNode->toString(); } else { linkName = orgLink->name(); } Link* link = body->link(linkName); if(link){ const Pose::LinkInfo& orgLinkInfo = q->second; Pose::LinkInfo* linkInfo = pose->addIkLink(link->index()); linkInfo->p = orgLinkInfo.p; linkInfo->R = orgLinkInfo.R; linkInfo->setStationaryPoint(orgLinkInfo.isStationaryPoint()); if(orgLinkInfo.isTouching()){ linkInfo->setTouching(orgLinkInfo.partingDirection()); } linkInfo->setSlave(orgLinkInfo.isSlave()); if(orgLinkInfo.isBaseLink()){ baseLinkIndex = link->index(); } } } if(baseLinkIndex >= 0){ pose->setBaseLink(baseLinkIndex); } } if(modified){ seq->endPoseModification(p); converted = true; } } } return converted; }