chainjnttojacdotsolver.cpp
Go to the documentation of this file.
00001 /*
00002     Computes the Jacobian time derivative
00003     Copyright (C) 2015  Antoine Hoarau <hoarau [at] isir.upmc.fr>
00004 
00005     This library is free software; you can redistribute it and/or
00006     modify it under the terms of the GNU Lesser General Public
00007     License as published by the Free Software Foundation; either
00008     version 2.1 of the License, or (at your option) any later version.
00009 
00010     This library is distributed in the hope that it will be useful,
00011     but WITHOUT ANY WARRANTY; without even the implied warranty of
00012     MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00013     Lesser General Public License for more details.
00014 
00015     You should have received a copy of the GNU Lesser General Public
00016     License along with this library; if not, write to the Free Software
00017     Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
00018 */
00019 
00020 
00021 #include "chainjnttojacdotsolver.hpp"
00022 
00023 namespace KDL
00024 {
00025 
00026 ChainJntToJacDotSolver::ChainJntToJacDotSolver(const Chain& _chain):
00027     chain(_chain),
00028     locked_joints_(chain.getNrOfJoints(),false),
00029     nr_of_unlocked_joints_(chain.getNrOfJoints()),
00030     jac_solver_(chain),
00031     jac_(chain.getNrOfJoints()),
00032     jac_dot_(chain.getNrOfJoints()),
00033     representation_(HYBRID),
00034     fk_solver_(chain)
00035 {
00036 }
00037 
00038 int ChainJntToJacDotSolver::JntToJacDot(const JntArrayVel& q_in, Twist& jac_dot_q_dot, int seg_nr)
00039 {
00040     JntToJacDot(q_in,jac_dot_,seg_nr);
00041     MultiplyJacobian(jac_dot_,q_in.qdot,jac_dot_q_dot);
00042     return (error = E_NOERROR);
00043 }
00044 
00045 int ChainJntToJacDotSolver::JntToJacDot(const JntArrayVel& q_in, Jacobian& jdot, int seg_nr)
00046 {
00047     unsigned int segmentNr;
00048     if(seg_nr<0)
00049         segmentNr=chain.getNrOfSegments();
00050     else
00051         segmentNr = seg_nr;
00052 
00053     //Initialize Jacobian to zero since only segmentNr columns are computed
00054     SetToZero(jdot) ;
00055 
00056     if(q_in.q.rows()!=chain.getNrOfJoints()||nr_of_unlocked_joints_!=jdot.columns())
00057         return (error = E_JAC_DOT_FAILED);
00058     else if(segmentNr>chain.getNrOfSegments())
00059         return (error = E_JAC_DOT_FAILED);
00060 
00061     // First compute the jacobian in the Hybrid representation
00062     jac_solver_.JntToJac(q_in.q,jac_,segmentNr);
00063 
00064     // Change the reference frame and/or the reference point
00065     switch(representation_)
00066     {
00067         case HYBRID:
00068             // Do Nothing as it is the default in KDL;
00069             break;
00070         case BODYFIXED:
00071             // Ref Frame {ee}, Ref Point {ee}
00072             fk_solver_.JntToCart(q_in.q,F_bs_ee_,segmentNr);
00073             jac_.changeBase(F_bs_ee_.M.Inverse());
00074             break;
00075         case INTERTIAL:
00076             // Ref Frame {bs}, Ref Point {bs}
00077             fk_solver_.JntToCart(q_in.q,F_bs_ee_,segmentNr);
00078             jac_.changeRefPoint(-F_bs_ee_.p);
00079             break;
00080         default:
00081             return (error = E_JAC_DOT_FAILED);
00082     }
00083 
00084     // Let's compute Jdot in the corresponding representation
00085     int k=0;
00086     for(unsigned int i=0;i<segmentNr;++i)
00087     {
00088         //Only increase joint nr if the segment has a joint
00089         if(chain.getSegment(i).getJoint().getType()!=Joint::None){
00090 
00091             for(unsigned int j=0;j<chain.getNrOfJoints();++j)
00092             {
00093                 // Column J is the sum of all partial derivatives  ref (41)
00094                 if(!locked_joints_[j])
00095                     jac_dot_k_ += getPartialDerivative(jac_,j,k,representation_) * q_in.qdot(j);
00096             }
00097             jdot.setColumn(k++,jac_dot_k_);
00098             SetToZero(jac_dot_k_);
00099         }
00100     }
00101 
00102     return (error = E_NOERROR);
00103 }
00104 
00105 const Twist& ChainJntToJacDotSolver::getPartialDerivative(const KDL::Jacobian& J, 
00106                                                           const unsigned int& joint_idx, 
00107                                                           const unsigned int& column_idx, 
00108                                                           const int& representation)
00109 {
00110     switch(representation)
00111     {
00112         case HYBRID:
00113             return getPartialDerivativeHybrid(J,joint_idx,column_idx);
00114         case BODYFIXED:
00115             return getPartialDerivativeBodyFixed(J,joint_idx,column_idx);
00116         case INTERTIAL:
00117             return getPartialDerivativeInertial(J,joint_idx,column_idx);
00118         default:
00119             SetToZero(this->t_djdq_);
00120             return t_djdq_;
00121     }
00122 }
00123 
00124 const Twist& ChainJntToJacDotSolver::getPartialDerivativeHybrid(const KDL::Jacobian& bs_J_ee, 
00125                                                                 const unsigned int& joint_idx, 
00126                                                                 const unsigned int& column_idx)
00127 {
00128     int j=joint_idx;
00129     int i=column_idx;
00130 
00131     jac_j_ = bs_J_ee.getColumn(j);
00132     jac_i_ = bs_J_ee.getColumn(i);
00133 
00134     SetToZero(t_djdq_);
00135 
00136     if(j < i)
00137     {
00138         // P_{\Delta}({}_{bs}J^{j})  ref (20)
00139         t_djdq_.vel = jac_j_.rot * jac_i_.vel;
00140         t_djdq_.rot = jac_j_.rot * jac_i_.rot;
00141     }else if(j > i)
00142     {
00143         // M_{\Delta}({}_{bs}J^{j})  ref (23)
00144         SetToZero(t_djdq_.rot);
00145         t_djdq_.vel = -jac_j_.vel * jac_i_.rot;
00146     }else if(j == i)
00147     {
00148          // ref (40)
00149          SetToZero(t_djdq_.rot);
00150          t_djdq_.vel = jac_i_.rot * jac_i_.vel;
00151     }
00152     return t_djdq_;
00153 }
00154 
00155 const Twist& ChainJntToJacDotSolver::getPartialDerivativeBodyFixed(const Jacobian& ee_J_ee, 
00156                                                             const unsigned int& joint_idx, 
00157                                                             const unsigned int& column_idx)
00158 {
00159     int j=joint_idx;
00160     int i=column_idx;
00161 
00162     SetToZero(t_djdq_);
00163 
00164     if(j > i)
00165     {
00166         jac_j_ = ee_J_ee.getColumn(j);
00167         jac_i_ = ee_J_ee.getColumn(i);
00168 
00169         // - S_d_(ee_J^j) * ee_J^ee  ref (23)
00170         t_djdq_.vel = jac_j_.rot * jac_i_.vel + jac_j_.vel * jac_i_.rot;
00171         t_djdq_.rot = jac_j_.rot * jac_i_.rot;
00172         t_djdq_ = -t_djdq_;
00173     }
00174 
00175     return t_djdq_;
00176 }
00177 const Twist& ChainJntToJacDotSolver::getPartialDerivativeInertial(const KDL::Jacobian& bs_J_bs, 
00178                                                                   const unsigned int& joint_idx, 
00179                                                                   const unsigned int& column_idx)
00180 {
00181     int j=joint_idx;
00182     int i=column_idx;
00183 
00184     SetToZero(t_djdq_);
00185 
00186     if(j < i)
00187     {
00188         jac_j_ = bs_J_bs.getColumn(j);
00189         jac_i_ = bs_J_bs.getColumn(i);
00190 
00191         // S_d_(bs_J^j) * bs_J^bs  ref (23)
00192         t_djdq_.vel = jac_j_.rot * jac_i_.vel + jac_j_.vel * jac_i_.rot;
00193         t_djdq_.rot = jac_j_.rot * jac_i_.rot;
00194     }
00195 
00196     return t_djdq_;
00197 }
00198 void ChainJntToJacDotSolver::setRepresentation(const int& representation)
00199 {
00200     if(representation == HYBRID ||
00201         representation == BODYFIXED ||
00202         representation == INTERTIAL)   
00203     this->representation_ = representation;
00204 }
00205 
00206 
00207 int ChainJntToJacDotSolver::setLockedJoints(const std::vector< bool > locked_joints)
00208 {
00209     if(locked_joints.size()!=locked_joints_.size())
00210         return -1;
00211     locked_joints_=locked_joints;
00212     nr_of_unlocked_joints_=0;
00213     for(unsigned int i=0;i<locked_joints_.size();i++){
00214         if(!locked_joints_[i])
00215             nr_of_unlocked_joints_++;
00216     }
00217 
00218     return 0;
00219 }
00220 const char* ChainJntToJacDotSolver::strError(const int error) const
00221 {
00222     if (E_JAC_DOT_FAILED == error) return "Jac Dot Failed";
00223     else return SolverI::strError(error);
00224 }
00225 
00226 ChainJntToJacDotSolver::~ChainJntToJacDotSolver()
00227 {
00228 }
00229 }  // namespace KDL


orocos_kdl
Author(s):
autogenerated on Sat Oct 7 2017 03:04:28