Robotics Library  0.6.2
Kinematic.h
Go to the documentation of this file.
1 //
2 // Copyright (c) 2009, Markus Rickert
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright notice,
11 // this list of conditions and the following disclaimer in the documentation
12 // and/or other materials provided with the distribution.
13 //
14 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
15 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
16 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
17 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
18 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
19 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
20 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
21 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
22 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
23 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
24 // POSSIBILITY OF SUCH DAMAGE.
25 //
26 
27 #ifndef _RL_MDL_KINEMATIC_H_
28 #define _RL_MDL_KINEMATIC_H_
29 
30 #include <rl/math/Matrix.h>
31 
32 #include "Metric.h"
33 
34 namespace rl
35 {
36  namespace mdl
37  {
38  class Kinematic : public Metric
39  {
40  public:
41  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
42 
43  Kinematic();
44 
45  virtual ~Kinematic();
46 
47  Model* clone() const;
48 
62  const ::std::size_t& leaf = 0,
63  const ::rl::math::Real& delta = ::std::numeric_limits< ::rl::math::Real >::infinity(),
64  const ::rl::math::Real& epsilon = 1.0e-3f,
65  const ::std::size_t& iterations = 1000
66  );
67 
68  void calculateJacobian();
69 
80 
82 
95 
96  void calculateJacobianInverse(const ::rl::math::Real& lambda = 0.0f, const bool& doSvd = true);
97 
103  void calculateJacobianInverse(const ::rl::math::Matrix& J, ::rl::math::Matrix& invJ, const ::rl::math::Real& lambda = 0.0f, const bool& doSvd = true) const;
104 
111 
113 
120  void forwardAcceleration();
121 
126  void forwardPosition();
127 
133  void forwardVelocity();
134 
136 
138 
140 
146  bool isSingular() const;
147 
149 
150  virtual void update();
151 
152  protected:
154 
156 
158 
159  private:
160 
161  };
162  }
163 }
164 
165 #endif // _RL_MDL_KINEMATIC_H_
rl::mdl::Kinematic::invJ
::rl::math::Matrix invJ
Definition: Kinematic.h:153
rl::mdl::Kinematic
Definition: Kinematic.h:39
rl::mdl::Kinematic::isSingular
bool isSingular() const
Check if current configuration is singular.
Definition: Kinematic.cpp:288
rl::mdl::Kinematic::~Kinematic
virtual ~Kinematic()
Definition: Kinematic.cpp:52
rl::mdl::Kinematic::J
::rl::math::Matrix J
Definition: Kinematic.h:155
rl::mdl::Kinematic::calculateJacobianInverse
void calculateJacobianInverse(const ::rl::math::Real &lambda=0.0f, const bool &doSvd=true)
Definition: Kinematic.cpp:190
rl::mdl::Kinematic::calculateInversePosition
bool calculateInversePosition(const ::rl::math::Transform &x, const ::std::size_t &leaf=0, const ::rl::math::Real &delta=::std::numeric_limits< ::rl::math::Real >::infinity(), const ::rl::math::Real &epsilon=1.0e-3f, const ::std::size_t &iterations=1000)
Resolved motion rate control.
Definition: Kinematic.cpp:57
rl::mdl::Kinematic::calculateJacobianDerivative
void calculateJacobianDerivative()
Definition: Kinematic.cpp:165
rl::mdl::Kinematic::Jdqd
::rl::math::Vector Jdqd
Definition: Kinematic.h:157
rl::mdl::Kinematic::forwardPosition
void forwardPosition()
Definition: Kinematic.cpp:252
rl::math::Matrix
::Eigen::Matrix< Real, ::Eigen::Dynamic, ::Eigen::Dynamic > Matrix
Definition: Matrix.h:41
rl::mdl::Kinematic::getJacobianDerivative
const ::rl::math::Vector & getJacobianDerivative() const
Definition: Kinematic.cpp:276
rl::mdl::Kinematic::getJacobianInverse
const ::rl::math::Matrix & getJacobianInverse() const
Definition: Kinematic.cpp:282
rl::mdl::Kinematic::forwardVelocity
void forwardVelocity()
Definition: Kinematic.cpp:261
rl::mdl::Model
Definition: Model.h:50
rl::mdl::Kinematic::calculateJacobian
void calculateJacobian()
Definition: Kinematic.cpp:131
Metric.h
rl::mdl::Metric
Definition: Metric.h:37
rl::mdl::Kinematic::update
virtual void update()
Definition: Kinematic.cpp:301
Matrix.h
rl::math::Transform
::Eigen::Transform< Real, 3, ::Eigen::Affine > Transform
Definition: Transform.h:42
rl::mdl::Kinematic::Kinematic
Kinematic()
Definition: Kinematic.cpp:44
rl::math::Vector
::Eigen::Matrix< Real, ::Eigen::Dynamic, 1 > Vector
Definition: Vector.h:41
rl::mdl::Kinematic::clone
Model * clone() const
Definition: Kinematic.cpp:237
rl::math::Real
double Real
Definition: Real.h:34
rl::mdl::Kinematic::getJacobian
const ::rl::math::Matrix & getJacobian() const
Definition: Kinematic.cpp:270
rl::mdl::Kinematic::calculateManipulabilityMeasure
::rl::math::Real calculateManipulabilityMeasure() const
Calculate manipulability measure.
Definition: Kinematic.cpp:225
rl::mdl::Kinematic::forwardAcceleration
void forwardAcceleration()
Definition: Kinematic.cpp:243
rl
Definition: Ati.cpp:35