chainiksolvervel_pinv_nso.hpp
Go to the documentation of this file.
1 // Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
2 
3 // Version: 1.0
4 // Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
5 // Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
6 // URL: http://www.orocos.org/kdl
7 
8 // This library is free software; you can redistribute it and/or
9 // modify it under the terms of the GNU Lesser General Public
10 // License as published by the Free Software Foundation; either
11 // version 2.1 of the License, or (at your option) any later version.
12 
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 
18 // You should have received a copy of the GNU Lesser General Public
19 // License along with this library; if not, write to the Free Software
20 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
21 
22 #ifndef KDL_CHAIN_IKSOLVERVEL_PINV_NSO_HPP
23 #define KDL_CHAIN_IKSOLVERVEL_PINV_NSO_HPP
24 
25 #include "chainiksolver.hpp"
26 #include "chainjnttojacsolver.hpp"
27 #include <Eigen/Core>
28 
29 namespace KDL
30 {
47  {
48  public:
63  ChainIkSolverVel_pinv_nso(const Chain& chain, const JntArray& opt_pos, const JntArray& weights, double eps=0.00001,int maxiter=150, double alpha = 0.25);
64  explicit ChainIkSolverVel_pinv_nso(const Chain& chain, double eps=0.00001,int maxiter=150, double alpha = 0.25);
66 
67  virtual int CartToJnt(const JntArray& q_in, const Twist& v_in, JntArray& qdot_out);
72  virtual int CartToJnt(const JntArray& /*q_init*/, const FrameVel& /*v_in*/, JntArrayVel& /*q_out*/){return -1;};
73 
80  const JntArray& getWeights()const
81  {
82  return weights;
83  }
84 
91  const JntArray& getOptPos()const
92  {
93  return opt_pos;
94  }
95 
102  const double& getAlpha()const
103  {
104  return alpha;
105  }
106 
113  virtual int setWeights(const JntArray &weights);
114 
121  virtual int setOptPos(const JntArray &opt_pos);
122 
129  virtual int setAlpha(const double alpha);
130 
135  int getSVDResult()const {return svdResult;};
136 
138  virtual void updateInternalDataStructures();
139 
140  private:
141  const Chain& chain;
143  unsigned int nj;
145  Eigen::MatrixXd U;
146  Eigen::VectorXd S;
147  Eigen::VectorXd Sinv;
148  Eigen::MatrixXd V;
149  Eigen::VectorXd tmp;
150  Eigen::VectorXd tmp2;
151  double eps;
152  int maxiter;
154  double alpha;
157  };
158 }
159 #endif
160 
virtual int CartToJnt(const JntArray &, const FrameVel &, JntArrayVel &)
This class encapsulates a serial kinematic interconnection structure. It is built out of segments...
Definition: chain.hpp:35
virtual int CartToJnt(const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)
This class represents an fixed size array containing joint values of a KDL::Chain.
Definition: jntarray.hpp:69
Class to calculate the jacobian of a general KDL::Chain, it is used by other solvers.
ChainIkSolverVel_pinv_nso(const Chain &chain, const JntArray &opt_pos, const JntArray &weights, double eps=0.00001, int maxiter=150, double alpha=0.25)
represents both translational and rotational velocities.
Definition: frames.hpp:720
virtual int setAlpha(const double alpha)
virtual int setOptPos(const JntArray &opt_pos)
virtual int setWeights(const JntArray &weights)
This abstract class encapsulates the inverse velocity solver for a KDL::Chain.


orocos_kdl
Author(s):
autogenerated on Fri Mar 12 2021 03:05:43