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 #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 void ChainJntToJacDotSolver::updateInternalDataStructures() {
00039 locked_joints_.resize(chain.getNrOfJoints(),false);
00040 this->setLockedJoints(locked_joints_);
00041 jac_solver_.updateInternalDataStructures();
00042 jac_.resize(chain.getNrOfJoints());
00043 jac_dot_.resize(chain.getNrOfJoints());
00044 fk_solver_.updateInternalDataStructures();
00045 }
00046
00047 int ChainJntToJacDotSolver::JntToJacDot(const JntArrayVel& q_in, Twist& jac_dot_q_dot, int seg_nr)
00048 {
00049 error = JntToJacDot(q_in,jac_dot_,seg_nr);
00050 if (error != E_NOERROR) {
00051 return error;
00052 }
00053 MultiplyJacobian(jac_dot_,q_in.qdot,jac_dot_q_dot);
00054 return (error = E_NOERROR);
00055 }
00056
00057 int ChainJntToJacDotSolver::JntToJacDot(const JntArrayVel& q_in, Jacobian& jdot, int seg_nr)
00058 {
00059 if(locked_joints_.size() != chain.getNrOfJoints())
00060 return (error = E_NOT_UP_TO_DATE);
00061
00062 unsigned int segmentNr;
00063 if(seg_nr<0)
00064 segmentNr=chain.getNrOfSegments();
00065 else
00066 segmentNr = seg_nr;
00067
00068
00069 SetToZero(jdot) ;
00070
00071 if(q_in.q.rows()!=chain.getNrOfJoints() || nr_of_unlocked_joints_!=jdot.columns())
00072 return (error = E_SIZE_MISMATCH);
00073 else if(segmentNr>chain.getNrOfSegments())
00074 return (error = E_OUT_OF_RANGE);
00075
00076
00077 if (jac_solver_.JntToJac(q_in.q,jac_,segmentNr) != E_NOERROR)
00078 return (error = E_JACSOLVER_FAILED);
00079
00080
00081 if (representation_ != HYBRID)
00082 {
00083 if (fk_solver_.JntToCart(q_in.q,F_bs_ee_,segmentNr) != E_NOERROR)
00084 return (error = E_FKSOLVERPOS_FAILED);
00085 if (representation_ == BODYFIXED) {
00086
00087 jac_.changeBase(F_bs_ee_.M.Inverse());
00088 } else if (representation_ == INERTIAL) {
00089
00090 jac_.changeRefPoint(-F_bs_ee_.p);
00091 } else {
00092 return (error = E_JAC_DOT_FAILED);
00093 }
00094 }
00095
00096
00097 int k=0;
00098 for(unsigned int i=0;i<segmentNr;++i)
00099 {
00100
00101 if(chain.getSegment(i).getJoint().getType()!=Joint::None){
00102
00103 for(unsigned int j=0;j<chain.getNrOfJoints();++j)
00104 {
00105
00106 if(!locked_joints_[j])
00107 jac_dot_k_ += getPartialDerivative(jac_,j,k,representation_) * q_in.qdot(j);
00108 }
00109 jdot.setColumn(k++,jac_dot_k_);
00110 SetToZero(jac_dot_k_);
00111 }
00112 }
00113
00114 return (error = E_NOERROR);
00115 }
00116
00117 const Twist& ChainJntToJacDotSolver::getPartialDerivative(const KDL::Jacobian& J,
00118 const unsigned int& joint_idx,
00119 const unsigned int& column_idx,
00120 const int& representation)
00121 {
00122 switch(representation)
00123 {
00124 case HYBRID:
00125 return getPartialDerivativeHybrid(J,joint_idx,column_idx);
00126 case BODYFIXED:
00127 return getPartialDerivativeBodyFixed(J,joint_idx,column_idx);
00128 case INERTIAL:
00129 return getPartialDerivativeInertial(J,joint_idx,column_idx);
00130 default:
00131 SetToZero(this->t_djdq_);
00132 return t_djdq_;
00133 }
00134 }
00135
00136 const Twist& ChainJntToJacDotSolver::getPartialDerivativeHybrid(const KDL::Jacobian& bs_J_ee,
00137 const unsigned int& joint_idx,
00138 const unsigned int& column_idx)
00139 {
00140 int j=joint_idx;
00141 int i=column_idx;
00142
00143 jac_j_ = bs_J_ee.getColumn(j);
00144 jac_i_ = bs_J_ee.getColumn(i);
00145
00146 SetToZero(t_djdq_);
00147
00148 if(j < i)
00149 {
00150
00151 t_djdq_.vel = jac_j_.rot * jac_i_.vel;
00152 t_djdq_.rot = jac_j_.rot * jac_i_.rot;
00153 }else if(j > i)
00154 {
00155
00156 SetToZero(t_djdq_.rot);
00157 t_djdq_.vel = -jac_j_.vel * jac_i_.rot;
00158 }else if(j == i)
00159 {
00160
00161 SetToZero(t_djdq_.rot);
00162 t_djdq_.vel = jac_i_.rot * jac_i_.vel;
00163 }
00164 return t_djdq_;
00165 }
00166
00167 const Twist& ChainJntToJacDotSolver::getPartialDerivativeBodyFixed(const Jacobian& ee_J_ee,
00168 const unsigned int& joint_idx,
00169 const unsigned int& column_idx)
00170 {
00171 int j=joint_idx;
00172 int i=column_idx;
00173
00174 SetToZero(t_djdq_);
00175
00176 if(j > i)
00177 {
00178 jac_j_ = ee_J_ee.getColumn(j);
00179 jac_i_ = ee_J_ee.getColumn(i);
00180
00181
00182 t_djdq_.vel = jac_j_.rot * jac_i_.vel + jac_j_.vel * jac_i_.rot;
00183 t_djdq_.rot = jac_j_.rot * jac_i_.rot;
00184 t_djdq_ = -t_djdq_;
00185 }
00186
00187 return t_djdq_;
00188 }
00189 const Twist& ChainJntToJacDotSolver::getPartialDerivativeInertial(const KDL::Jacobian& bs_J_bs,
00190 const unsigned int& joint_idx,
00191 const unsigned int& column_idx)
00192 {
00193 int j=joint_idx;
00194 int i=column_idx;
00195
00196 SetToZero(t_djdq_);
00197
00198 if(j < i)
00199 {
00200 jac_j_ = bs_J_bs.getColumn(j);
00201 jac_i_ = bs_J_bs.getColumn(i);
00202
00203
00204 t_djdq_.vel = jac_j_.rot * jac_i_.vel + jac_j_.vel * jac_i_.rot;
00205 t_djdq_.rot = jac_j_.rot * jac_i_.rot;
00206 }
00207
00208 return t_djdq_;
00209 }
00210 void ChainJntToJacDotSolver::setRepresentation(const int& representation)
00211 {
00212 if(representation == HYBRID ||
00213 representation == BODYFIXED ||
00214 representation == INERTIAL)
00215 this->representation_ = representation;
00216 }
00217
00218
00219 int ChainJntToJacDotSolver::setLockedJoints(const std::vector<bool>& locked_joints)
00220 {
00221 if(locked_joints.size()!=locked_joints_.size())
00222 return E_SIZE_MISMATCH;
00223 locked_joints_=locked_joints;
00224 nr_of_unlocked_joints_=0;
00225 for(unsigned int i=0;i<locked_joints_.size();i++){
00226 if(!locked_joints_[i])
00227 nr_of_unlocked_joints_++;
00228 }
00229
00230 return (error = E_NOERROR);
00231 }
00232
00233 const char* ChainJntToJacDotSolver::strError(const int error) const
00234 {
00235 if (E_JAC_DOT_FAILED == error) return "Jac Dot Failed";
00236 else if (E_JACSOLVER_FAILED == error) return "Jac Solver Failed";
00237 else if (E_FKSOLVERPOS_FAILED == error) return "FK Position Solver Failed";
00238 return SolverI::strError(error);
00239 }
00240
00241 ChainJntToJacDotSolver::~ChainJntToJacDotSolver()
00242 {
00243 }
00244 }