Robotics Library  0.7.0
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 
60  const ::std::size_t& leaf = 0,
61  const ::rl::math::Real& delta = ::std::numeric_limits< ::rl::math::Real>::infinity(),
62  const ::rl::math::Real& epsilon = 1.0e-3f,
63  const ::std::size_t& iterations = 1000
64  );
65 
76  void calculateJacobian(const bool& inWorldFrame = true);
77 
88  void calculateJacobian(::rl::math::Matrix& J, const bool& inWorldFrame = true);
89 
102  void calculateJacobianDerivative(const bool& inWorldFrame = true);
103 
116  void calculateJacobianDerivative(::rl::math::Vector& Jdqd, const bool& inWorldFrame = true);
117 
131  void calculateJacobianInverse(const ::rl::math::Real& lambda = 0.0f, const bool& doSvd = true);
132 
147  void calculateJacobianInverse(const ::rl::math::Matrix& J, ::rl::math::Matrix& invJ, const ::rl::math::Real& lambda = 0.0f, const bool& doSvd = true) const;
148 
160 
171 
178  void forwardAcceleration();
179 
184  void forwardPosition();
185 
191  void forwardVelocity();
192 
202 
213 
224 
230  bool isSingular() const;
231 
238 
239  virtual void update();
240 
241  protected:
252 
263 
274 
275  private:
276 
277  };
278  }
279 }
280 
281 #endif // RL_MDL_KINEMATIC_H
rl::math::Matrix
::Eigen::Matrix< Real, ::Eigen::Dynamic, ::Eigen::Dynamic > Matrix
Definition: Matrix.h:42
rl::mdl::Kinematic::calculateJacobian
void calculateJacobian(const bool &inWorldFrame=true)
Calculate Jacobian matrix.
Definition: Kinematic.cpp:102
rl::mdl::Kinematic::invJ
::rl::math::Matrix invJ
Jacobian matrix inverse.
Definition: Kinematic.h:251
rl::math::Transform
::Eigen::Transform< Real, 3, ::Eigen::Affine > Transform
Rigid transformation in 3D.
Definition: Transform.h:46
rl::mdl::Kinematic
Definition: Kinematic.h:39
rl::mdl::Kinematic::isSingular
bool isSingular() const
Check if current configuration is singular.
Definition: Kinematic.cpp:271
rl::mdl::Kinematic::~Kinematic
virtual ~Kinematic()
Definition: Kinematic.cpp:52
rl::math::Vector
::Eigen::Matrix< Real, ::Eigen::Dynamic, 1 > Vector
Definition: Vector.h:42
rl::mdl::Kinematic::J
::rl::math::Matrix J
Jacobian matrix.
Definition: Kinematic.h:262
Metric.h
rl::mdl::Kinematic::calculateJacobianInverse
void calculateJacobianInverse(const ::rl::math::Real &lambda=0.0f, const bool &doSvd=true)
Calculate Jacobian matrix inverse.
Definition: Kinematic.cpp:173
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::Jdqd
::rl::math::Vector Jdqd
Jacobian derivative vector.
Definition: Kinematic.h:273
rl::mdl::Kinematic::forwardPosition
void forwardPosition()
Definition: Kinematic.cpp:235
rl::mdl::Kinematic::getJacobianDerivative
const ::rl::math::Vector & getJacobianDerivative() const
Access calculated Jacobian derivative vector.
Definition: Kinematic.cpp:259
rl::mdl::Kinematic::getJacobianInverse
const ::rl::math::Matrix & getJacobianInverse() const
Access calculated Jacobian matrix inverse.
Definition: Kinematic.cpp:265
rl::mdl::Kinematic::forwardVelocity
void forwardVelocity()
Definition: Kinematic.cpp:244
rl::mdl::Model
Definition: Model.h:56
rl::mdl::Metric
Definition: Metric.h:37
rl::mdl::Kinematic::update
virtual void update()
Definition: Kinematic.cpp:284
rl::mdl::Kinematic::calculateJacobianDerivative
void calculateJacobianDerivative(const bool &inWorldFrame=true)
Calculate Jacobian derivative vector.
Definition: Kinematic.cpp:142
Matrix.h
rl::mdl::Kinematic::Kinematic
Kinematic()
Definition: Kinematic.cpp:44
rl::mdl::Kinematic::clone
Model * clone() const
Definition: Kinematic.cpp:220
rl::math::Real
double Real
Definition: Real.h:42
rl::mdl::Kinematic::getJacobian
const ::rl::math::Matrix & getJacobian() const
Access calculated Jacobian matrix.
Definition: Kinematic.cpp:253
rl::mdl::Kinematic::calculateManipulabilityMeasure
::rl::math::Real calculateManipulabilityMeasure() const
Calculate manipulability measure.
Definition: Kinematic.cpp:208
rl::mdl::Kinematic::forwardAcceleration
void forwardAcceleration()
Definition: Kinematic.cpp:226
rl
Robotics Library.
Definition: AnalogInput.cpp:30