chainfksolver.hpp 3.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108
  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_CHAIN_FKSOLVER_HPP
  18. #define KDL_CHAIN_FKSOLVER_HPP
  19. #include "chain.hpp"
  20. #include "framevel.hpp"
  21. #include "frameacc.hpp"
  22. #include "jntarray.hpp"
  23. #include "jntarrayvel.hpp"
  24. #include "jntarrayacc.hpp"
  25. namespace KDL {
  26. /**
  27. * \brief This <strong>abstract</strong> class encapsulates a
  28. * solver for the forward position kinematics for a KDL::Chain.
  29. *
  30. * @ingroup KinematicFamily
  31. */
  32. //Forward definition
  33. class ChainFkSolverPos {
  34. public:
  35. /**
  36. * Calculate forward position kinematics for a KDL::Chain,
  37. * from joint coordinates to cartesian pose.
  38. *
  39. * @param q_in input joint coordinates
  40. * @param p_out reference to output cartesian pose
  41. *
  42. * @return if < 0 something went wrong
  43. */
  44. virtual int JntToCart(const JntArray& q_in, Frame& p_out,int segmentNr=-1)=0;
  45. virtual ~ChainFkSolverPos(){};
  46. };
  47. /**
  48. * \brief This <strong>abstract</strong> class encapsulates a solver
  49. * for the forward velocity kinematics for a KDL::Chain.
  50. *
  51. * @ingroup KinematicFamily
  52. */
  53. class ChainFkSolverVel {
  54. public:
  55. /**
  56. * Calculate forward position and velocity kinematics, from
  57. * joint coordinates to cartesian coordinates.
  58. *
  59. * @param q_in input joint coordinates (position and velocity)
  60. * @param out output cartesian coordinates (position and velocity)
  61. *
  62. * @return if < 0 something went wrong
  63. */
  64. virtual int JntToCart(const JntArrayVel& q_in, FrameVel& out,int segmentNr=-1)=0;
  65. virtual ~ChainFkSolverVel(){};
  66. };
  67. /**
  68. * \brief This <strong>abstract</strong> class encapsulates a solver
  69. * for the forward acceleration kinematics for a KDL::Chain.
  70. *
  71. * @ingroup KinematicFamily
  72. */
  73. class ChainFkSolverAcc {
  74. public:
  75. /**
  76. * Calculate forward position, velocity and accelaration
  77. * kinematics, from joint coordinates to cartesian coordinates
  78. *
  79. * @param q_in input joint coordinates (position, velocity and
  80. * acceleration
  81. @param out output cartesian coordinates (position, velocity
  82. * and acceleration
  83. *
  84. * @return if < 0 something went wrong
  85. */
  86. virtual int JntToCart(const JntArrayAcc& q_in, FrameAcc& out,int segmentNr=-1)=0;
  87. virtual ~ChainFkSolverAcc()=0;
  88. };
  89. }//end of namespace KDL
  90. #endif