chainiksolver_pos_nr_jl_mimic.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 // Modified to account for "mimic" joints, i.e. joints whose motion has a
00025 // linear relationship to that of another joint.
00026 // Copyright  (C)  2013  Sachin Chitta, Willow Garage
00027 
00028 #include "moveit/kdl_kinematics_plugin/chainiksolver_pos_nr_jl_mimic.hpp"
00029 #include <ros/console.h>
00030 
00031 namespace KDL
00032 {
00033 
00034 ChainIkSolverPos_NR_JL_Mimic::ChainIkSolverPos_NR_JL_Mimic(const Chain& _chain, const JntArray& _q_min, const JntArray& _q_max, ChainFkSolverPos& _fksolver, ChainIkSolverVel& _iksolver, unsigned int _maxiter, double _eps, bool _position_ik): chain(_chain), q_min(_q_min), q_max(_q_max), q_temp(chain.getNrOfJoints()), fksolver(_fksolver), iksolver(_iksolver), delta_q(_chain.getNrOfJoints()), maxiter(_maxiter), eps(_eps), q_min_mimic(chain.getNrOfJoints()), q_max_mimic(chain.getNrOfJoints()), position_ik(_position_ik)
00035 {
00036   mimic_joints.resize(chain.getNrOfJoints());
00037   for(std::size_t i=0; i < mimic_joints.size(); ++i)
00038     mimic_joints[i].reset(i);
00039 }
00040 
00041 bool ChainIkSolverPos_NR_JL_Mimic::setMimicJoints(const std::vector<kdl_kinematics_plugin::JointMimic>& _mimic_joints)
00042 {
00043   if(_mimic_joints.size() != chain.getNrOfJoints())
00044   {
00045     ROS_ERROR("kdl","Mimic Joint info should be same size as number of joints in chain: %d", chain.getNrOfJoints());
00046     return false;
00047   }
00048 
00049   for(std::size_t i=0; i < _mimic_joints.size(); ++i)
00050   {
00051     if(_mimic_joints[i].map_index >= chain.getNrOfJoints())
00052     {
00053       ROS_ERROR("kdl","Mimic Joint index should be less than number of joints in chain: %d", chain.getNrOfJoints());
00054       return false;
00055     }
00056   }
00057   mimic_joints = _mimic_joints;
00058 
00059   //Note that q_min and q_max will be of size chain.getNrOfJoints() - num_mimic_joints
00060   qToqMimic(q_min,q_min_mimic);
00061   qToqMimic(q_max,q_max_mimic);
00062 
00063   ROS_DEBUG_NAMED("kdl","Set mimic joints");
00064   return true;
00065 }
00066 
00067 void ChainIkSolverPos_NR_JL_Mimic::qToqMimic(const JntArray& q, JntArray& q_result)
00068 {
00069   for(std::size_t i=0; i < chain.getNrOfJoints(); ++i)
00070   {
00071     q_result(i) = mimic_joints[i].offset + mimic_joints[i].multiplier * q(mimic_joints[i].map_index);
00072   }
00073 }
00074 
00075 void ChainIkSolverPos_NR_JL_Mimic::qMimicToq(const JntArray& q, JntArray& q_result)
00076 {
00077   for(std::size_t i=0; i < chain.getNrOfJoints(); ++i)
00078   {
00079     if(mimic_joints[i].active) //This is not a mimic joint
00080     {
00081       q_result(mimic_joints[i].map_index) = q(i);
00082     }
00083   }
00084 }
00085 
00086 int ChainIkSolverPos_NR_JL_Mimic::CartToJnt(const JntArray& q_init, const Frame& p_in, JntArray& q_out)
00087 {
00088   return CartToJntAdvanced(q_init,p_in,q_out,false);
00089 }
00090 
00091 int ChainIkSolverPos_NR_JL_Mimic::CartToJntAdvanced(const JntArray& q_init, const Frame& p_in, JntArray& q_out, bool lock_redundant_joints)
00092 {
00093   //Note that q_init and q_out will be of size chain.getNrOfJoints() - num_mimic_joints
00094   qToqMimic(q_init,q_temp);
00095 
00096   unsigned int i;
00097   for(i=0;i<maxiter;++i)
00098   {
00099     fksolver.JntToCart(q_temp,f);
00100     delta_twist = diff(f,p_in);
00101 
00102     if(position_ik)
00103     {
00104       if(fabs(delta_twist(0)) < eps && fabs(delta_twist(1)) < eps && fabs(delta_twist(2)) < eps)
00105         break;
00106     }
00107     else
00108     {
00109       if(Equal(delta_twist,Twist::Zero(),eps))
00110         break;
00111     }
00112 
00113     ROS_DEBUG_STREAM_NAMED("kdl","delta_twist");
00114     for(std::size_t i=0; i < 6; ++i)
00115       ROS_DEBUG_NAMED("kdl","%d: %f",(int) i, delta_twist(i));
00116 
00117     iksolver.CartToJnt(q_temp,delta_twist,delta_q);
00118 
00119     Add(q_temp,delta_q,q_temp);
00120 
00121     ROS_DEBUG_STREAM_NAMED("kdl","delta_q");
00122     for(std::size_t i=0; i < delta_q.rows(); ++i)
00123       ROS_DEBUG_NAMED("kdl","%d: %f",(int) i, delta_q(i));
00124 
00125     for(std::size_t j=0; j<q_min_mimic.rows(); ++j)
00126     {
00127       if(mimic_joints[j].active)
00128         if(q_temp(j) < q_min_mimic(j))
00129           q_temp(j) = q_min_mimic(j);
00130     }
00131     for(std::size_t j=0; j<q_max_mimic.rows(); ++j)
00132     {
00133       if(mimic_joints[j].active)
00134         if(q_temp(j) > q_max_mimic(j))
00135           q_temp(j) = q_max_mimic(j);
00136     }
00137 
00138     //Make sure limits are applied on the mimic joints to
00139     qMimicToq(q_temp,q_out);
00140     qToqMimic(q_out,q_temp);
00141 
00142   }
00143 
00144   qMimicToq(q_temp, q_out);
00145   ROS_DEBUG_STREAM_NAMED("kdl","Full Solution:");
00146   for(std::size_t i=0; i < q_temp.rows(); ++i)
00147     ROS_DEBUG_NAMED("kdl","%d: %f",(int) i,q_temp(i));
00148 
00149   ROS_DEBUG_STREAM_NAMED("kdl","Actual Solution:");
00150   for(std::size_t i=0; i < q_out.rows(); ++i)
00151     ROS_DEBUG_NAMED("kdl","%d: %f",(int) i,q_out(i));
00152 
00153   if(i!=maxiter)
00154     return 0;
00155   else
00156     return -3;
00157 }
00158 
00159 ChainIkSolverPos_NR_JL_Mimic::~ChainIkSolverPos_NR_JL_Mimic()
00160 {
00161 }
00162 }


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:31:39