chainjnttojacsolver.cpp 2.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384
  1. /** \file itasc/kdl/chainjnttojacsolver.cpp
  2. * \ingroup itasc
  3. */
  4. // Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
  5. // Version: 1.0
  6. // Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
  7. // Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
  8. // URL: http://www.orocos.org/kdl
  9. // This library is free software; you can redistribute it and/or
  10. // modify it under the terms of the GNU Lesser General Public
  11. // License as published by the Free Software Foundation; either
  12. // version 2.1 of the License, or (at your option) any later version.
  13. // This library is distributed in the hope that it will be useful,
  14. // but WITHOUT ANY WARRANTY; without even the implied warranty of
  15. // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
  16. // Lesser General Public License for more details.
  17. // You should have received a copy of the GNU Lesser General Public
  18. // License along with this library; if not, write to the Free Software
  19. // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
  20. #include "chainjnttojacsolver.hpp"
  21. namespace KDL
  22. {
  23. ChainJntToJacSolver::ChainJntToJacSolver(const Chain& _chain):
  24. chain(_chain)
  25. {
  26. }
  27. ChainJntToJacSolver::~ChainJntToJacSolver()
  28. {
  29. }
  30. int ChainJntToJacSolver::JntToJac(const JntArray& q_in,Jacobian& jac)
  31. {
  32. assert(q_in.rows()==chain.getNrOfJoints()&&
  33. q_in.rows()==jac.columns());
  34. Frame T_local, T_joint;
  35. T_total = Frame::Identity();
  36. SetToZero(t_local);
  37. int i=chain.getNrOfSegments()-1;
  38. unsigned int q_nr = chain.getNrOfJoints();
  39. //Lets recursively iterate until we are in the root segment
  40. while (i >= 0) {
  41. const Segment& segment = chain.getSegment(i);
  42. int ndof = segment.getJoint().getNDof();
  43. q_nr -= ndof;
  44. //get the pose of the joint.
  45. T_joint = segment.getJoint().pose(((JntArray&)q_in)(q_nr));
  46. // combine with the tip to have the tip pose
  47. T_local = T_joint*segment.getFrameToTip();
  48. //calculate new T_end:
  49. T_total = T_local * T_total;
  50. for (int dof=0; dof<ndof; dof++) {
  51. // combine joint rotation with tip position to get a reference frame for the joint
  52. T_joint.p = T_local.p;
  53. // in which the twist can be computed (needed for NDof joint)
  54. t_local = segment.twist(T_joint, 1.0, dof);
  55. //transform the endpoint of the local twist to the global endpoint:
  56. t_local = t_local.RefPoint(T_total.p - T_local.p);
  57. //transform the base of the twist to the endpoint
  58. t_local = T_total.M.Inverse(t_local);
  59. //store the twist in the jacobian:
  60. jac.twists[q_nr+dof] = t_local;
  61. }
  62. i--;
  63. }//endwhile
  64. //Change the base of the complete jacobian from the endpoint to the base
  65. changeBase(jac, T_total.M, jac);
  66. return 0;
  67. }
  68. }