chainjnttojacsolver.hpp 2.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566
  1. // Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
  2. // Version: 1.0
  3. // Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
  4. // Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
  5. // URL: http://www.orocos.org/kdl
  6. // This library is free software; you can redistribute it and/or
  7. // modify it under the terms of the GNU Lesser General Public
  8. // License as published by the Free Software Foundation; either
  9. // version 2.1 of the License, or (at your option) any later version.
  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. // You should have received a copy of the GNU Lesser General Public
  15. // License along with this library; if not, write to the Free Software
  16. // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
  17. #ifndef KDL_CHAINJNTTOJACSOLVER_HPP
  18. #define KDL_CHAINJNTTOJACSOLVER_HPP
  19. #include "frames.hpp"
  20. #include "jacobian.hpp"
  21. #include "jntarray.hpp"
  22. #include "chain.hpp"
  23. namespace KDL
  24. {
  25. /**
  26. * @brief Class to calculate the jacobian of a general
  27. * KDL::Chain, it is used by other solvers. It should not be used
  28. * outside of KDL.
  29. *
  30. *
  31. */
  32. class ChainJntToJacSolver
  33. {
  34. public:
  35. ChainJntToJacSolver(const Chain& chain);
  36. ~ChainJntToJacSolver();
  37. /**
  38. * Calculate the jacobian expressed in the base frame of the
  39. * chain, with reference point at the end effector of the
  40. * *chain. The alghoritm is similar to the one used in
  41. * KDL::ChainFkSolverVel_recursive
  42. *
  43. * @param q_in input joint positions
  44. * @param jac output jacobian
  45. *
  46. * @return always returns 0
  47. */
  48. int JntToJac(const JntArray& q_in,Jacobian& jac);
  49. private:
  50. const Chain chain;
  51. Twist t_local;
  52. Frame T_total;
  53. };
  54. }
  55. #endif