Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
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 int ChainIkSolverPos_NR_JL::CartToJnt(const JntArray& q_init, const Frame& p_in, JntArray& q_out)
00054 {
00055 if(nj != q_init.rows() || nj != q_out.rows())
00056 return (error = E_SIZE_MISMATCH);
00057
00058 q_out = q_init;
00059
00060 unsigned int i;
00061 for(i=0;i<maxiter;i++){
00062 if ( fksolver.JntToCart(q_out,f) < 0)
00063 return (error = E_FKSOLVERPOS_FAILED);
00064 delta_twist = diff(f,p_in);
00065
00066 if(Equal(delta_twist,Twist::Zero(),eps))
00067 break;
00068
00069 if ( iksolver.CartToJnt(q_out,delta_twist,delta_q) < 0)
00070 return (error = E_IKSOLVERVEL_FAILED);
00071 Add(q_out,delta_q,q_out);
00072
00073 for(unsigned int j=0; j<q_min.rows(); j++) {
00074 if(q_out(j) < q_min(j))
00075 q_out(j) = q_min(j);
00076 }
00077
00078
00079 for(unsigned int j=0; j<q_max.rows(); j++) {
00080 if(q_out(j) > q_max(j))
00081 q_out(j) = q_max(j);
00082 }
00083 }
00084
00085 if(i!=maxiter)
00086 return (error = E_NOERROR);
00087 else
00088 return (error = E_MAX_ITERATIONS_EXCEEDED);
00089 }
00090
00091 int ChainIkSolverPos_NR_JL::setJointLimits(const JntArray& q_min_in, const JntArray& q_max_in) {
00092 if (q_min_in.rows() != nj || q_max_in.rows() != nj)
00093 return (error = E_SIZE_MISMATCH);
00094 q_min = q_min_in;
00095 q_max = q_max_in;
00096 return (error = E_NOERROR);
00097 }
00098
00099 ChainIkSolverPos_NR_JL::~ChainIkSolverPos_NR_JL()
00100 {
00101 }
00102
00103 const char* ChainIkSolverPos_NR_JL::strError(const int error) const
00104 {
00105 if (E_FKSOLVERPOS_FAILED == error) return "Internal forward position solver failed.";
00106 else if (E_IKSOLVERVEL_FAILED == error) return "Internal inverse velocity solver failed.";
00107 else return SolverI::strError(error);
00108 }
00109 }
00110