chainjnttojacdotsolver.cpp
Go to the documentation of this file.
1 /*
2  Computes the Jacobian time derivative
3  Copyright (C) 2015 Antoine Hoarau <hoarau [at] isir.upmc.fr>
4 
5  This library is free software; you can redistribute it and/or
6  modify it under the terms of the GNU Lesser General Public
7  License as published by the Free Software Foundation; either
8  version 2.1 of the License, or (at your option) any later version.
9 
10  This library is distributed in the hope that it will be useful,
11  but WITHOUT ANY WARRANTY; without even the implied warranty of
12  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
13  Lesser General Public License for more details.
14 
15  You should have received a copy of the GNU Lesser General Public
16  License along with this library; if not, write to the Free Software
17  Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
18 */
19 
20 
22 
23 namespace KDL
24 {
25 
27  chain(_chain),
28  locked_joints_(chain.getNrOfJoints(),false),
29  nr_of_unlocked_joints_(chain.getNrOfJoints()),
30  jac_solver_(chain),
31  jac_(chain.getNrOfJoints()),
32  jac_dot_(chain.getNrOfJoints()),
33  representation_(HYBRID),
34  fk_solver_(chain)
35 {
36 }
37 
39  locked_joints_.resize(chain.getNrOfJoints(),false);
45 }
46 
47 int ChainJntToJacDotSolver::JntToJacDot(const JntArrayVel& q_in, Twist& jac_dot_q_dot, int seg_nr)
48 {
49  error = JntToJacDot(q_in,jac_dot_,seg_nr);
50  if (error != E_NOERROR) {
51  return error;
52  }
53  MultiplyJacobian(jac_dot_,q_in.qdot,jac_dot_q_dot);
54  return (error = E_NOERROR);
55 }
56 
57 int ChainJntToJacDotSolver::JntToJacDot(const JntArrayVel& q_in, Jacobian& jdot, int seg_nr)
58 {
59  if(locked_joints_.size() != chain.getNrOfJoints())
60  return (error = E_NOT_UP_TO_DATE);
61 
62  unsigned int segmentNr;
63  if(seg_nr<0)
64  segmentNr=chain.getNrOfSegments();
65  else
66  segmentNr = seg_nr;
67 
68  //Initialize Jacobian to zero since only segmentNr columns are computed
69  SetToZero(jdot) ;
70 
71  if(q_in.q.rows()!=chain.getNrOfJoints() || nr_of_unlocked_joints_!=jdot.columns())
72  return (error = E_SIZE_MISMATCH);
73  else if(segmentNr>chain.getNrOfSegments())
74  return (error = E_OUT_OF_RANGE);
75 
76  // First compute the jacobian in the Hybrid representation
77  if (jac_solver_.JntToJac(q_in.q,jac_,segmentNr) != E_NOERROR)
78  return (error = E_JACSOLVER_FAILED);
79 
80  // Change the reference frame and/or the reference point
81  if (representation_ != HYBRID) // If HYBRID do nothing is this is the default.
82  {
83  if (fk_solver_.JntToCart(q_in.q,F_bs_ee_,segmentNr) != E_NOERROR)
84  return (error = E_FKSOLVERPOS_FAILED);
85  if (representation_ == BODYFIXED) {
86  // Ref Frame {ee}, Ref Point {ee}
88  } else if (representation_ == INERTIAL) {
89  // Ref Frame {bs}, Ref Point {bs}
91  } else {
92  return (error = E_JAC_DOT_FAILED);
93  }
94  }
95 
96  // Let's compute Jdot in the corresponding representation
97  int k=0;
98  for(unsigned int i=0;i<segmentNr;++i)
99  {
100  //Only increase joint nr if the segment has a joint
102 
103  for(unsigned int j=0;j<chain.getNrOfJoints();++j)
104  {
105  // Column J is the sum of all partial derivatives ref (41)
106  if(!locked_joints_[j])
108  }
109  jdot.setColumn(k++,jac_dot_k_);
111  }
112  }
113 
114  return (error = E_NOERROR);
115 }
116 
118  const unsigned int& joint_idx,
119  const unsigned int& column_idx,
120  const int& representation)
121 {
122  switch(representation)
123  {
124  case HYBRID:
125  return getPartialDerivativeHybrid(J,joint_idx,column_idx);
126  case BODYFIXED:
127  return getPartialDerivativeBodyFixed(J,joint_idx,column_idx);
128  case INERTIAL:
129  return getPartialDerivativeInertial(J,joint_idx,column_idx);
130  default:
131  SetToZero(this->t_djdq_);
132  return t_djdq_;
133  }
134 }
135 
137  const unsigned int& joint_idx,
138  const unsigned int& column_idx)
139 {
140  int j=joint_idx;
141  int i=column_idx;
142 
143  jac_j_ = bs_J_ee.getColumn(j);
144  jac_i_ = bs_J_ee.getColumn(i);
145 
147 
148  if(j < i)
149  {
150  // P_{\Delta}({}_{bs}J^{j}) ref (20)
153  }else if(j > i)
154  {
155  // M_{\Delta}({}_{bs}J^{j}) ref (23)
158  }else if(j == i)
159  {
160  // ref (40)
163  }
164  return t_djdq_;
165 }
166 
168  const unsigned int& joint_idx,
169  const unsigned int& column_idx)
170 {
171  int j=joint_idx;
172  int i=column_idx;
173 
175 
176  if(j > i)
177  {
178  jac_j_ = ee_J_ee.getColumn(j);
179  jac_i_ = ee_J_ee.getColumn(i);
180 
181  // - S_d_(ee_J^j) * ee_J^ee ref (23)
184  t_djdq_ = -t_djdq_;
185  }
186 
187  return t_djdq_;
188 }
190  const unsigned int& joint_idx,
191  const unsigned int& column_idx)
192 {
193  int j=joint_idx;
194  int i=column_idx;
195 
197 
198  if(j < i)
199  {
200  jac_j_ = bs_J_bs.getColumn(j);
201  jac_i_ = bs_J_bs.getColumn(i);
202 
203  // S_d_(bs_J^j) * bs_J^bs ref (23)
206  }
207 
208  return t_djdq_;
209 }
210 void ChainJntToJacDotSolver::setRepresentation(const int& representation)
211 {
212  if(representation == HYBRID ||
213  representation == BODYFIXED ||
214  representation == INERTIAL)
215  this->representation_ = representation;
216 }
217 
218 
219 int ChainJntToJacDotSolver::setLockedJoints(const std::vector<bool>& locked_joints)
220 {
221  if(locked_joints.size()!=locked_joints_.size())
222  return E_SIZE_MISMATCH;
223  locked_joints_=locked_joints;
225  for(unsigned int i=0;i<locked_joints_.size();i++){
226  if(!locked_joints_[i])
228  }
229 
230  return (error = E_NOERROR);
231 }
232 
233 const char* ChainJntToJacDotSolver::strError(const int error) const
234 {
235  if (E_JAC_DOT_FAILED == error) return "Jac Dot Failed";
236  else if (E_JACSOLVER_FAILED == error) return "Jac Solver Failed";
237  else if (E_FKSOLVERPOS_FAILED == error) return "FK Position Solver Failed";
238  return SolverI::strError(error);
239 }
240 
242 {
243 }
244 } // namespace KDL
void setRepresentation(const int &representation)
Sets the internal variable for the representation (with a check on the value)
int setLockedJoints(const std::vector< bool > &locked_joints)
const Segment & getSegment(unsigned int nr) const
Definition: chain.cpp:68
virtual int JntToCart(const JntArray &q_in, Frame &p_out, int segmentNr=-1)
unsigned int rows() const
Definition: jntarray.cpp:72
void resize(unsigned int newNrOfColumns)
Allocates memory for new size (can break realtime behavior)
Definition: jacobian.cpp:55
Rotation Inverse() const
Gives back the inverse rotation matrix of *this.
Definition: frames.hpp:633
const Twist & getPartialDerivativeHybrid(const Jacobian &bs_J_ee, const unsigned int &joint_idx, const unsigned int &column_idx)
Computes .
This class encapsulates a serial kinematic interconnection structure. It is built out of segments...
Definition: chain.hpp:35
Vector vel
The velocity of that point.
Definition: frames.hpp:722
const Twist & getPartialDerivativeBodyFixed(const Jacobian &ee_J_ee, const unsigned int &joint_idx, const unsigned int &column_idx)
Computes .
Chain size changed.
Definition: solveri.hpp:97
unsigned int getNrOfSegments() const
Definition: chain.hpp:76
void MultiplyJacobian(const Jacobian &jac, const JntArray &src, Twist &dest)
Definition: jntarray.cpp:102
virtual const char * strError(const int error) const
Definition: solveri.hpp:125
Input size does not match internal state.
Definition: solveri.hpp:99
ChainFkSolverPos_recursive fk_solver_
virtual const char * strError(const int error) const
unsigned int columns() const
Definition: jacobian.cpp:75
Rotation M
Orientation of the Frame.
Definition: frames.hpp:573
represents both translational and rotational velocities.
Definition: frames.hpp:720
IMETHOD void SetToZero(Vector &v)
Definition: frames.hpp:1062
virtual void updateInternalDataStructures()
virtual int JntToJac(const JntArray &q_in, Jacobian &jac, int segmentNR=-1)
Vector rot
The rotational velocity of that point.
Definition: frames.hpp:723
Requested index out of range.
Definition: solveri.hpp:103
const Joint & getJoint() const
Definition: segment.hpp:118
void setColumn(unsigned int i, const Twist &t)
Definition: jacobian.cpp:149
Vector p
origine of the Frame
Definition: frames.hpp:572
friend bool changeBase(const Jacobian &src1, const Rotation &rot, Jacobian &dest)
Definition: jacobian.cpp:104
friend bool changeRefPoint(const Jacobian &src1, const Vector &base_AB, Jacobian &dest)
Definition: jacobian.cpp:90
unsigned int getNrOfJoints() const
Definition: chain.hpp:71
Twist getColumn(unsigned int i) const
Definition: jacobian.cpp:145
ChainJntToJacDotSolver(const Chain &chain)
virtual int JntToJacDot(const KDL::JntArrayVel &q_in, KDL::Twist &jac_dot_q_dot, int seg_nr=-1)
Computes .
const Twist & getPartialDerivative(const Jacobian &J, const unsigned int &joint_idx, const unsigned int &column_idx, const int &representation)
Computes .
int error
Latest error, initialized to E_NOERROR in constructor.
Definition: solveri.hpp:149
const Twist & getPartialDerivativeInertial(const Jacobian &bs_J_bs, const unsigned int &joint_idx, const unsigned int &column_idx)
Computes .
const JointType & getType() const
Definition: joint.hpp:159


orocos_kdl
Author(s):
autogenerated on Sat Jun 15 2019 19:07:36