chainiksolverpos_nr_jl.cpp
Go to the documentation of this file.
00001 // Copyright  (C)  2007  Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
00002 // Copyright  (C)  2008  Mikael Mayer
00003 // Copyright  (C)  2008  Julia Jesse
00004 
00005 // Version: 1.0
00006 // Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
00007 // Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
00008 // URL: http://www.orocos.org/kdl
00009 
00010 // This library is free software; you can redistribute it and/or
00011 // modify it under the terms of the GNU Lesser General Public
00012 // License as published by the Free Software Foundation; either
00013 // version 2.1 of the License, or (at your option) any later version.
00014 
00015 // This library is distributed in the hope that it will be useful,
00016 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00017 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00018 // Lesser General Public License for more details.
00019 
00020 // You should have received a copy of the GNU Lesser General Public
00021 // License along with this library; if not, write to the Free Software
00022 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
00023 
00024 #include "chainiksolverpos_nr_jl.hpp"
00025 
00026 #include <limits>
00027 
00028 namespace KDL
00029 {
00030     ChainIkSolverPos_NR_JL::ChainIkSolverPos_NR_JL(const Chain& _chain, const JntArray& _q_min, const JntArray& _q_max, ChainFkSolverPos& _fksolver,ChainIkSolverVel& _iksolver,
00031                                              unsigned int _maxiter, double _eps):
00032         chain(_chain), nj(chain.getNrOfJoints()),
00033         q_min(_q_min), q_max(_q_max),
00034         iksolver(_iksolver), fksolver(_fksolver),
00035         delta_q(_chain.getNrOfJoints()),
00036         maxiter(_maxiter),eps(_eps)
00037     {
00038 
00039     }
00040 
00041     ChainIkSolverPos_NR_JL::ChainIkSolverPos_NR_JL(const Chain& _chain, ChainFkSolverPos& _fksolver,ChainIkSolverVel& _iksolver,
00042             unsigned int _maxiter, double _eps):
00043          chain(_chain), nj(chain.getNrOfJoints()),
00044          q_min(nj), q_max(nj),
00045          iksolver(_iksolver), fksolver(_fksolver),
00046          delta_q(nj),
00047          maxiter(_maxiter),eps(_eps)
00048     {
00049         q_min.data.setConstant(std::numeric_limits<double>::min());
00050         q_max.data.setConstant(std::numeric_limits<double>::max());
00051     }
00052 
00053     void ChainIkSolverPos_NR_JL::updateInternalDataStructures() {
00054        nj = chain.getNrOfJoints();
00055        q_min.data.conservativeResizeLike(Eigen::VectorXd::Constant(nj,std::numeric_limits<double>::min()));
00056        q_max.data.conservativeResizeLike(Eigen::VectorXd::Constant(nj,std::numeric_limits<double>::max()));
00057        iksolver.updateInternalDataStructures();
00058        fksolver.updateInternalDataStructures();
00059        delta_q.resize(nj);
00060     }
00061 
00062     int ChainIkSolverPos_NR_JL::CartToJnt(const JntArray& q_init, const Frame& p_in, JntArray& q_out)
00063     {
00064         if(nj != chain.getNrOfJoints())
00065             return (error = E_NOT_UP_TO_DATE);
00066 
00067         if(nj != q_init.rows() || nj != q_out.rows() || nj != q_min.rows() || nj != q_max.rows())
00068             return (error = E_SIZE_MISMATCH);
00069 
00070             q_out = q_init;
00071 
00072             unsigned int i;
00073             for(i=0;i<maxiter;i++){
00074                 if ( fksolver.JntToCart(q_out,f) < 0)
00075                     return (error = E_FKSOLVERPOS_FAILED);
00076                 delta_twist = diff(f,p_in);
00077 
00078         if(Equal(delta_twist,Twist::Zero(),eps))
00079             break;
00080 
00081         if ( iksolver.CartToJnt(q_out,delta_twist,delta_q) < 0)
00082             return (error = E_IKSOLVERVEL_FAILED);
00083                 Add(q_out,delta_q,q_out);
00084 
00085                 for(unsigned int j=0; j<q_min.rows(); j++) {
00086                   if(q_out(j) < q_min(j))
00087                     q_out(j) = q_min(j);
00088                 }
00089 
00090 
00091                 for(unsigned int j=0; j<q_max.rows(); j++) {
00092                     if(q_out(j) > q_max(j))
00093                       q_out(j) = q_max(j);
00094                 }
00095             }
00096 
00097             if(i!=maxiter)
00098                 return (error = E_NOERROR);
00099             else
00100                 return (error = E_MAX_ITERATIONS_EXCEEDED);
00101     }
00102 
00103     int ChainIkSolverPos_NR_JL::setJointLimits(const JntArray& q_min_in, const JntArray& q_max_in) {
00104         if (q_min_in.rows() != nj || q_max_in.rows() != nj)
00105             return (error = E_SIZE_MISMATCH);
00106         q_min = q_min_in;
00107         q_max = q_max_in;
00108         return (error = E_NOERROR);
00109     }
00110 
00111     ChainIkSolverPos_NR_JL::~ChainIkSolverPos_NR_JL()
00112     {
00113     }
00114 
00115     const char* ChainIkSolverPos_NR_JL::strError(const int error) const
00116     {
00117         if (E_FKSOLVERPOS_FAILED == error) return "Internal forward position solver failed.";
00118         else if (E_IKSOLVERVEL_FAILED == error) return "Internal inverse velocity solver failed.";
00119         else return SolverI::strError(error);
00120     }
00121 }
00122 


orocos_kdl
Author(s):
autogenerated on Fri Jun 14 2019 19:33:22