33 #ifndef DART_DYNAMICS_DETAIL_TEMPLATEDJACOBIAN_HPP_
34 #define DART_DYNAMICS_DETAIL_TEMPLATEDJACOBIAN_HPP_
42 template<
class NodeType>
45 const Frame* _inCoordinatesOf)
const
47 if(
this == _inCoordinatesOf)
48 return static_cast<const NodeType*
>(
this)->getJacobian();
49 else if(_inCoordinatesOf->
isWorld())
50 return static_cast<const NodeType*
>(
this)->getWorldJacobian();
53 static_cast<const NodeType*
>(
this)->getJacobian());
57 template<
class NodeType>
60 const Eigen::Vector3d& _offset)
const
62 math::Jacobian J =
static_cast<const NodeType*
>(
this)->getJacobian();
63 J.bottomRows<3>() += J.topRows<3>().colwise().cross(_offset);
69 template<
class NodeType>
72 const Eigen::Vector3d& _offset,
73 const Frame* _inCoordinatesOf)
const
75 if(
this == _inCoordinatesOf)
76 return getJacobian(_offset);
77 else if(_inCoordinatesOf->
isWorld())
78 return getWorldJacobian(_offset);
80 Eigen::Isometry3d T = getTransform(_inCoordinatesOf);
81 T.translation() = - T.linear() * _offset;
83 return math::AdTJac(T,
static_cast<const NodeType*
>(
this)->getJacobian());
87 template<
class NodeType>
90 const Eigen::Vector3d& _offset)
const
92 math::Jacobian J =
static_cast<const NodeType*
>(
this)->getWorldJacobian();
93 J.bottomRows<3>() += J.topRows<3>().colwise().cross(
94 getWorldTransform().linear() * _offset);
100 template<
class NodeType>
103 const Frame* _inCoordinatesOf)
const
105 if(
this == _inCoordinatesOf)
108 static_cast<const NodeType*
>(
this)->getJacobian();
110 return J.bottomRows<3>();
112 else if(_inCoordinatesOf->
isWorld())
115 static_cast<const NodeType*
>(
this)->getWorldJacobian();
117 return JWorld.bottomRows<3>();
121 static_cast<const NodeType*
>(
this)->getJacobian();
123 return getTransform(_inCoordinatesOf).linear() * J.bottomRows<3>();
127 template<
class NodeType>
130 const Eigen::Vector3d& _offset,
131 const Frame* _inCoordinatesOf)
const
134 static_cast<const NodeType*
>(
this)->getJacobian();
137 JLinear = J.bottomRows<3>() + J.topRows<3>().colwise().cross(_offset);
139 if(
this == _inCoordinatesOf)
142 return getTransform(_inCoordinatesOf).linear() * JLinear;
146 template<
class NodeType>
149 const Frame* _inCoordinatesOf)
const
151 if(
this == _inCoordinatesOf)
154 static_cast<const NodeType*
>(
this)->getJacobian();
155 return J.topRows<3>();
157 else if(_inCoordinatesOf->
isWorld())
160 static_cast<const NodeType*
>(
this)->getWorldJacobian();
161 return JWorld.topRows<3>();
165 static_cast<const NodeType*
>(
this)->getJacobian();
167 return getTransform(_inCoordinatesOf).linear() * J.topRows<3>();
171 template<
class NodeType>
174 const Frame* _inCoordinatesOf)
const
176 if(
this == _inCoordinatesOf)
177 return static_cast<const NodeType*
>(
this)->getJacobianSpatialDeriv();
180 static_cast<const NodeType*
>(
this)->getJacobianSpatialDeriv());
184 template<
class NodeType>
187 const Eigen::Vector3d& _offset)
const
190 static_cast<const NodeType*
>(
this)->getJacobianSpatialDeriv();
192 J_d.bottomRows<3>() += J_d.topRows<3>().colwise().cross(_offset);
198 template<
class NodeType>
201 const Eigen::Vector3d& _offset,
202 const Frame* _inCoordinatesOf)
const
204 if(
this == _inCoordinatesOf)
205 return getJacobianSpatialDeriv(_offset);
207 Eigen::Isometry3d T = getTransform(_inCoordinatesOf);
208 T.translation() = T.linear() * -_offset;
211 T,
static_cast<const NodeType*
>(
this)->getJacobianSpatialDeriv());
215 template<
class NodeType>
218 const Frame* _inCoordinatesOf)
const
220 if(_inCoordinatesOf->
isWorld())
221 return static_cast<const NodeType*
>(
this)->getJacobianClassicDeriv();
224 static_cast<const NodeType*
>(
this)->getJacobianClassicDeriv());
228 template<
class NodeType>
231 const Eigen::Vector3d& _offset,
232 const Frame* _inCoordinatesOf)
const
235 static_cast<const NodeType*
>(
this)->getJacobianClassicDeriv();
238 static_cast<const NodeType*
>(
this)->getWorldJacobian();
240 const Eigen::Vector3d& w = getAngularVelocity();
241 const Eigen::Vector3d& p = (getWorldTransform().linear() * _offset).eval();
243 J_d.bottomRows<3>() += J_d.topRows<3>().colwise().cross(p)
244 + J.topRows<3>().colwise().cross(w.cross(p));
246 if(_inCoordinatesOf->
isWorld())
253 template<
class NodeType>
256 const Frame* _inCoordinatesOf)
const
259 static_cast<const NodeType*
>(
this)->getJacobianClassicDeriv();
261 if(_inCoordinatesOf->
isWorld())
262 return J_d.bottomRows<3>();
265 * J_d.bottomRows<3>();
269 template<
class NodeType>
272 const Eigen::Vector3d& _offset,
273 const Frame* _inCoordinatesOf)
const
276 static_cast<const NodeType*
>(
this)->getJacobianClassicDeriv();
279 static_cast<const NodeType*
>(
this)->getWorldJacobian();
281 const Eigen::Vector3d& w = getAngularVelocity();
282 const Eigen::Vector3d& p = (getWorldTransform().linear() * _offset).eval();
284 if(_inCoordinatesOf->
isWorld())
285 return J_d.bottomRows<3>() + J_d.topRows<3>().colwise().cross(p)
286 + J.topRows<3>().colwise().cross(w.cross(p));
289 * (J_d.bottomRows<3>() + J_d.topRows<3>().colwise().cross(p)
290 + J.topRows<3>().colwise().cross(w.cross(p)));
294 template<
class NodeType>
297 const Frame* _inCoordinatesOf)
const
300 static_cast<const NodeType*
>(
this)->getJacobianClassicDeriv();
302 if(_inCoordinatesOf->
isWorld())
303 return J_d.topRows<3>();
310 template<
class NodeType>
BodyNode class represents a single node of the skeleton.
Definition: BodyNode.hpp:78
Entity class is a base class for any objects that exist in the kinematic tree structure of DART.
Definition: Entity.hpp:60
The Frame class serves as the backbone of DART's kinematic tree structure.
Definition: Frame.hpp:57
bool isWorld() const
Returns true if this Frame is the World Frame.
Definition: Frame.cpp:445
const Eigen::Isometry3d & getWorldTransform() const
Get the transform of this Frame with respect to the World Frame.
Definition: Frame.cpp:79
The JacobianNode class serves as a common interface for BodyNodes and EndEffectors to both be used as...
Definition: JacobianNode.hpp:54
virtual const math::Jacobian & getJacobian() const =0
Return the generalized Jacobian targeting the origin of this JacobianNode.
virtual const math::Jacobian & getJacobianClassicDeriv() const =0
Return the classical time derivative of the generalized Jacobian targeting the origin of this BodyNod...
virtual const math::Jacobian & getJacobianSpatialDeriv() const =0
Return the spatial time derivative of the generalized Jacobian targeting the origin of this BodyNode.
virtual const math::Jacobian & getWorldJacobian() const =0
Return the generalized Jacobian targeting the origin of this JacobianNode.
math::AngularJacobian getAngularJacobian(const Frame *_inCoordinatesOf=Frame::World()) const override final
Return the angular Jacobian targeting the origin of this BodyNode.
Definition: TemplatedJacobianNode.hpp:148
TemplatedJacobianNode(BodyNode *bn)
Constructor.
Definition: TemplatedJacobianNode.hpp:311
math::LinearJacobian getLinearJacobian(const Frame *_inCoordinatesOf=Frame::World()) const override final
Return the linear Jacobian targeting the origin of this BodyNode.
Definition: TemplatedJacobianNode.hpp:102
math::AngularJacobian getAngularJacobianDeriv(const Frame *_inCoordinatesOf=Frame::World()) const override final
Return the angular Jacobian time derivative, in terms of any coordinate Frame.
Definition: TemplatedJacobianNode.hpp:296
math::LinearJacobian getLinearJacobianDeriv(const Frame *_inCoordinatesOf=Frame::World()) const override final
Return the linear Jacobian (classical) time derivative, in terms of any coordinate Frame.
Definition: TemplatedJacobianNode.hpp:255
Derived::PlainObject AdRJac(const Eigen::Isometry3d &_T, const Eigen::MatrixBase< Derived > &_J)
Change coordinate Frame of a Jacobian.
Definition: Geometry.hpp:271
Eigen::Matrix< double, 6, Eigen::Dynamic > Jacobian
Definition: MathTypes.hpp:108
Eigen::Matrix< double, 3, Eigen::Dynamic > AngularJacobian
Definition: MathTypes.hpp:107
Derived::PlainObject AdRInvJac(const Eigen::Isometry3d &_T, const Eigen::MatrixBase< Derived > &_J)
Definition: Geometry.hpp:289
Eigen::Matrix< double, 3, Eigen::Dynamic > LinearJacobian
Definition: MathTypes.hpp:106
Derived::PlainObject AdTJac(const Eigen::Isometry3d &_T, const Eigen::MatrixBase< Derived > &_J)
Adjoint mapping for dynamic size Jacobian.
Definition: Geometry.hpp:216
Definition: BulletCollisionDetector.cpp:63