Esempio n. 1
0
    void getFloatingBaseJacobianLoop(const UndirectedTree & undirected_tree,
                                     const GeneralizedJntPositions &q,
                                     const Traversal & traversal,
                                     const int link_index,
                                     Jacobian & jac)
    {
        Frame T_total = Frame::Identity(); //The transformation between link_index frame and current_link frame

        assert(link_index < (int)undirected_tree.getNrOfLinks());

        KDL::CoDyCo::LinkMap::const_iterator current_link;
        current_link = undirected_tree.getLink(link_index);

        //All the columns not modified are zero
        SetToZero(jac);

        KDL::CoDyCo::LinkMap::const_iterator parent_link=traversal.getParentLink(current_link);
        while(current_link != traversal.getBaseLink()) {
            double joint_pos = 0.0;
            if( current_link->getAdjacentJoint(parent_link)->getNrOfDOFs() == 1 ) {
                KDL::Twist jac_col;

                int dof_index = current_link->getAdjacentJoint(parent_link)->getDOFIndex();

                joint_pos = q.jnt_pos(dof_index);
                KDL::Twist S_current_parent = parent_link->S(current_link,joint_pos);

                jac_col = T_total*S_current_parent;

                assert(6+dof_index < (int)jac.columns());
                assert( dof_index < (int)undirected_tree.getNrOfDOFs() );
                jac.setColumn(6+dof_index,jac_col);
            }

            KDL::Frame X_current_parent = parent_link->pose(current_link,joint_pos);

            T_total = T_total*X_current_parent;

            current_link = parent_link;
            parent_link = traversal.getParentLink(current_link);
        }

        //Setting the floating part of the Jacobian
        T_total = T_total*KDL::Frame(q.base_pos.M.Inverse());

        jac.data.block(0,0,6,6) = TwistTransformationMatrix(T_total);

        jac.changeBase(T_total.M.Inverse());
    }
Esempio n. 2
0
int crba_momentum_jacobian_loop(const UndirectedTree & undirected_tree,
                                const Traversal & traversal,
                                const JntArray & q,
                                std::vector<RigidBodyInertia> & Ic,
                                MomentumJacobian & H,
                                RigidBodyInertia & InertiaCOM
                               )
{
#ifndef NDEBUG
    if( undirected_tree.getNrOfLinks() != traversal.getNrOfVisitedLinks() ||
            undirected_tree.getNrOfDOFs() != q.rows() ||
            Ic.size() != undirected_tree.getNrOfLinks() ||
            H.columns() != (undirected_tree.getNrOfDOFs() + 6) )
    {
        std::cerr << "crba_momentum_jacobian_loop: input data error" << std::endl;
        return -1;
    }
#endif

    double q_;
    Wrench F = Wrench::Zero();

    //Sweep from root to leaf
    for(int i=0; i<(int)traversal.getNrOfVisitedLinks(); i++)
    {
        LinkMap::const_iterator link_it = traversal.getOrderedLink(i);
        int link_index = link_it->getLinkIndex();

        //Collect RigidBodyInertia
        Ic[link_index]=link_it->getInertia();

    }

    for(int i=(int)traversal.getNrOfVisitedLinks()-1; i >= 1; i-- ) {
        int dof_id;
        LinkMap::const_iterator link_it = traversal.getOrderedLink(i);
        int link_index = link_it->getLinkIndex();

        LinkMap::const_iterator parent_it = traversal.getParentLink(link_index);
        int parent_index = parent_it->getLinkIndex();

        if( link_it->getAdjacentJoint(parent_it)->getNrOfDOFs() == 1 ) {
            dof_id = link_it->getAdjacentJoint(parent_it)->getDOFIndex();
            q_ = q(dof_id);
        } else {
            q_ = 0.0;
            dof_id = -1;
        }

        Ic[parent_index] = Ic[parent_index]+link_it->pose(parent_it,q_)*Ic[link_index];

        if( link_it->getAdjacentJoint(parent_it)->getNrOfDOFs() == 1 ) {
            KDL::Twist S_link_parent = parent_it->S(link_it,q_);
            F = Ic[link_index]*S_link_parent;

            if( traversal.getParentLink(link_it) != undirected_tree.getInvalidLinkIterator() ) {
                double q__;
                int dof_id_;
                LinkMap::const_iterator predecessor_it = traversal.getParentLink(link_it);
                LinkMap::const_iterator successor_it = link_it;

                while(true) {

                    if( predecessor_it->getAdjacentJoint(successor_it)->getNrOfDOFs() == 1 ) {
                        q__ = q( predecessor_it->getAdjacentJoint(successor_it)->getDOFIndex());
                    } else {
                        q__ = 0.0;
                    }

                    F = successor_it->pose(predecessor_it,q__)*F;

                    successor_it = predecessor_it;
                    predecessor_it = traversal.getParentLink(predecessor_it);

                    if( predecessor_it == undirected_tree.getInvalidLinkIterator() ) {
                        break;
                    }

                    if( predecessor_it->getAdjacentJoint(successor_it)->getNrOfDOFs() == 1 ) {
                        dof_id_ =  predecessor_it->getAdjacentJoint(successor_it)->getDOFIndex();
                        q__ = q(dof_id_);
                    } else {
                        q__ = 0.0;
                        dof_id_ = -1;
                    }


                }
                if( dof_id >= 0 ) {
                    H.data.block(0,6+dof_id,6,1) = toEigen(F);
                }

                //The first 6x6 submatrix of the Momentum Jacobian are simply the spatial inertia
                //of all the structure expressed in the base reference frame
                H.data.block(0,0,6,6) = toEigen(Ic[traversal.getBaseLink()->getLinkIndex()]);


            }

        }
    }

    //We have then to translate the reference point of the obtained jacobian to the com
    //The Ic[traversal.order[0]->getLink(index)] contain the spatial inertial of all the tree
    //expressed in link coordite frames
    Vector com = Ic[traversal.getBaseLink()->getLinkIndex()].getCOG();
    H.changeRefPoint(com);

    InertiaCOM = Frame(com)*Ic[traversal.getBaseLink()->getLinkIndex()];

    return 0;
}