Public Types | Public Member Functions | Protected Attributes

OpenTissue::mbd::HingeJoint< mbd_types > Class Template Reference

#include <mbd_hinge_joint.h>

Inheritance diagram for OpenTissue::mbd::HingeJoint< mbd_types >:
OpenTissue::mbd::JointInterface< mbd_types >

List of all members.

Public Types

typedef mbd_types::math_policy math_policy
typedef
mbd_types::math_policy::index_type 
size_type
typedef
mbd_types::math_policy::real_type 
real_type
typedef
mbd_types::math_policy::vector3_type 
vector3_type
typedef
mbd_types::math_policy::matrix3x3_type 
matrix3x3_type
typedef
mbd_types::math_policy::quaternion_type 
quaternion_type
typedef
mbd_types::math_policy::vector_range 
vector_range
typedef
mbd_types::math_policy::idx_vector_range 
idx_vector_range
typedef
mbd_types::math_policy::matrix_range 
matrix_range
typedef
mbd_types::math_policy::vector_type 
vector_type
typedef
mbd_types::math_policy::value_traits 
value_traits
typedef AngularJointLimit
< mbd_types > 
angular_limit_type
typedef AngularJointMotor
< mbd_types > 
angular_motor_type

Public Member Functions

real_type get_hinge_angle () const
real_type get_hinge_angle_rate () const
vector3_type get_hinge_axis_world () const
void set_limit (angular_limit_type const &limit)
void set_motor (angular_motor_type const &motor)
 HingeJoint ()
virtual ~HingeJoint ()
void evaluate ()
size_type get_number_of_jacobian_rows () const
void get_linear_jacobian_A (matrix_range &J) const
void get_linear_jacobian_B (matrix_range &J) const
void get_angular_jacobian_A (matrix_range &J) const
void get_angular_jacobian_B (matrix_range &J) const
void get_stabilization_term (vector_range &b_error) const
void get_low_limits (vector_range &lo) const
void get_high_limits (vector_range &hi) const
void get_dependency_indices (idx_vector_range &dep) const
void get_dependency_factors (vector_range &factors) const
void set_regularization (vector_range const &gamma)
void get_regularization (vector_range &gamma) const
void set_solution (vector_range const &solution)
void get_solution (vector_range &solution) const
void calibration ()

Protected Attributes

vector3_type m_s_A_wcs
 The joint axe wrt. to body A in WCS.
vector3_type m_s_B_wcs
 The joint axe wrt. to body B in WCS.
vector3_type m_t1
 A vector orthogonal to the joint axe (in WCS).
vector3_type m_t2
 Another vector orthogonal to the joint axe and t1 (in WCS).
vector3_type m_u
 Error correction rotation axe. Ie. if joint is misaligned this vector is used to determine an rotation axe which can be used to align the joint along.
matrix3x3_type m_star_anc_A
 The cross product operator of the anchor point wrt. to body A rotated (but not translated) into WCS.
matrix3x3_type m_star_anc_B
 The cross product operator of the anchor point wrt. to body B rotated (but not translated) into WCS.
vector3_type m_anc_A_wcs
 The anchor point wrt. to body A in WCS.
vector3_type m_anc_B_wcs
 The anchor point wrt. to body B in WCS.
quaternion_type m_Q_initial
 The initial relative orientation between the two bodies (wrt. WCS) i.e. the rotation that aligns body A with body B.
quaternion_type m_Q_initial_conj
 The conjugate of Q_initial.
angular_limit_typem_limit
angular_motor_typem_motor
size_type m_rows
size_type m_motor_offset
size_type m_limit_offset
vector_type m_gamma
 Local vector of constraint force mixing terms.
vector_type m_solution
 Local solution vector, ie. vector of lagrange multipliers.

template<typename mbd_types>
class OpenTissue::mbd::HingeJoint< mbd_types >


Member Typedef Documentation

template<typename mbd_types >
typedef AngularJointLimit<mbd_types> OpenTissue::mbd::HingeJoint< mbd_types >::angular_limit_type
template<typename mbd_types >
typedef AngularJointMotor<mbd_types> OpenTissue::mbd::HingeJoint< mbd_types >::angular_motor_type
template<typename mbd_types >
typedef mbd_types::math_policy::idx_vector_range OpenTissue::mbd::HingeJoint< mbd_types >::idx_vector_range
template<typename mbd_types >
typedef mbd_types::math_policy OpenTissue::mbd::HingeJoint< mbd_types >::math_policy
template<typename mbd_types >
typedef mbd_types::math_policy::matrix3x3_type OpenTissue::mbd::HingeJoint< mbd_types >::matrix3x3_type
template<typename mbd_types >
typedef mbd_types::math_policy::matrix_range OpenTissue::mbd::HingeJoint< mbd_types >::matrix_range
template<typename mbd_types >
typedef mbd_types::math_policy::quaternion_type OpenTissue::mbd::HingeJoint< mbd_types >::quaternion_type
template<typename mbd_types >
typedef mbd_types::math_policy::real_type OpenTissue::mbd::HingeJoint< mbd_types >::real_type
template<typename mbd_types >
typedef mbd_types::math_policy::index_type OpenTissue::mbd::HingeJoint< mbd_types >::size_type
template<typename mbd_types >
typedef mbd_types::math_policy::value_traits OpenTissue::mbd::HingeJoint< mbd_types >::value_traits
template<typename mbd_types >
typedef mbd_types::math_policy::vector3_type OpenTissue::mbd::HingeJoint< mbd_types >::vector3_type
template<typename mbd_types >
typedef mbd_types::math_policy::vector_range OpenTissue::mbd::HingeJoint< mbd_types >::vector_range
template<typename mbd_types >
typedef mbd_types::math_policy::vector_type OpenTissue::mbd::HingeJoint< mbd_types >::vector_type

Constructor & Destructor Documentation

template<typename mbd_types >
OpenTissue::mbd::HingeJoint< mbd_types >::HingeJoint (  )  [inline]
template<typename mbd_types >
virtual OpenTissue::mbd::HingeJoint< mbd_types >::~HingeJoint (  )  [inline, virtual]

Member Function Documentation

template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::calibration (  )  [inline, virtual]

joint_type Calibration Routine. This method is invoked implicitly whenever the joint connectivity is changed (alteration of anchor points or joint axes).

It can also be invoked directly by and end user if the incident body position and/or rotations is changed.

Implements OpenTissue::mbd::JointInterface< mbd_types >.

template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::evaluate (  )  [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::get_angular_jacobian_A ( matrix_range J  )  const [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::get_angular_jacobian_B ( matrix_range J  )  const [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::get_dependency_factors ( vector_range factors  )  const [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::get_dependency_indices ( idx_vector_range dep  )  const [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::get_high_limits ( vector_range hi  )  const [inline]
template<typename mbd_types >
real_type OpenTissue::mbd::HingeJoint< mbd_types >::get_hinge_angle (  )  const [inline]

Get Rotation Angle.

This angle tells how much body B have rotated around the joint axis (postive value means CCW, negative means CW) from its initial placement.

Think of it as if you have fixated body A so only body B is allowd to move.

Let BF_B' indicate the initial orientation of body B's body frame and BF_B the current orientation, now BF_A should be thought of as being immoveable ie. constant.

Q_initial : BF_A -> BF_B' Q_cur : BF_A -> BF_B

Now we must have the relation

Q_rel Q_initial = Q_cur

From which we deduce

Q_rel = Q_cur conj(Q_initial)

And we see that

Q_rel : BF_B' -> BF_B

That is how much the body frame of body B have rotated (measured with respect to the fixed body frame A).

Returns:
The angle in radians, which the joint have rotated around its joints axe away from its initial position (at calibration time).
template<typename mbd_types >
real_type OpenTissue::mbd::HingeJoint< mbd_types >::get_hinge_angle_rate (  )  const [inline]

Get Angle Rate. This method computes the (signed) speed by which the joint angle changes its radial position around the joint axe.

Returns:
The angle rate.
template<typename mbd_types >
vector3_type OpenTissue::mbd::HingeJoint< mbd_types >::get_hinge_axis_world (  )  const [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::get_linear_jacobian_A ( matrix_range J  )  const [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::get_linear_jacobian_B ( matrix_range J  )  const [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::get_low_limits ( vector_range lo  )  const [inline]
template<typename mbd_types >
size_type OpenTissue::mbd::HingeJoint< mbd_types >::get_number_of_jacobian_rows (  )  const [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::get_regularization ( vector_range gamma  )  const [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::get_solution ( vector_range solution  )  const [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::get_stabilization_term ( vector_range b_error  )  const [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::set_limit ( angular_limit_type const &  limit  )  [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::set_motor ( angular_motor_type const &  motor  )  [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::set_regularization ( vector_range const &  gamma  )  [inline]
template<typename mbd_types >
void OpenTissue::mbd::HingeJoint< mbd_types >::set_solution ( vector_range const &  solution  )  [inline]

Member Data Documentation

template<typename mbd_types >
vector3_type OpenTissue::mbd::HingeJoint< mbd_types >::m_anc_A_wcs [protected]

The anchor point wrt. to body A in WCS.

template<typename mbd_types >
vector3_type OpenTissue::mbd::HingeJoint< mbd_types >::m_anc_B_wcs [protected]

The anchor point wrt. to body B in WCS.

template<typename mbd_types >
vector_type OpenTissue::mbd::HingeJoint< mbd_types >::m_gamma [protected]

Local vector of constraint force mixing terms.

template<typename mbd_types >
angular_limit_type* OpenTissue::mbd::HingeJoint< mbd_types >::m_limit [protected]
template<typename mbd_types >
size_type OpenTissue::mbd::HingeJoint< mbd_types >::m_limit_offset [protected]
template<typename mbd_types >
angular_motor_type* OpenTissue::mbd::HingeJoint< mbd_types >::m_motor [protected]
template<typename mbd_types >
size_type OpenTissue::mbd::HingeJoint< mbd_types >::m_motor_offset [protected]
template<typename mbd_types >
quaternion_type OpenTissue::mbd::HingeJoint< mbd_types >::m_Q_initial [protected]

The initial relative orientation between the two bodies (wrt. WCS) i.e. the rotation that aligns body A with body B.

template<typename mbd_types >
quaternion_type OpenTissue::mbd::HingeJoint< mbd_types >::m_Q_initial_conj [protected]

The conjugate of Q_initial.

template<typename mbd_types >
size_type OpenTissue::mbd::HingeJoint< mbd_types >::m_rows [protected]
template<typename mbd_types >
vector3_type OpenTissue::mbd::HingeJoint< mbd_types >::m_s_A_wcs [protected]

The joint axe wrt. to body A in WCS.

template<typename mbd_types >
vector3_type OpenTissue::mbd::HingeJoint< mbd_types >::m_s_B_wcs [protected]

The joint axe wrt. to body B in WCS.

template<typename mbd_types >
vector_type OpenTissue::mbd::HingeJoint< mbd_types >::m_solution [protected]

Local solution vector, ie. vector of lagrange multipliers.

template<typename mbd_types >
matrix3x3_type OpenTissue::mbd::HingeJoint< mbd_types >::m_star_anc_A [protected]

The cross product operator of the anchor point wrt. to body A rotated (but not translated) into WCS.

template<typename mbd_types >
matrix3x3_type OpenTissue::mbd::HingeJoint< mbd_types >::m_star_anc_B [protected]

The cross product operator of the anchor point wrt. to body B rotated (but not translated) into WCS.

template<typename mbd_types >
vector3_type OpenTissue::mbd::HingeJoint< mbd_types >::m_t1 [protected]

A vector orthogonal to the joint axe (in WCS).

template<typename mbd_types >
vector3_type OpenTissue::mbd::HingeJoint< mbd_types >::m_t2 [protected]

Another vector orthogonal to the joint axe and t1 (in WCS).

template<typename mbd_types >
vector3_type OpenTissue::mbd::HingeJoint< mbd_types >::m_u [protected]

Error correction rotation axe. Ie. if joint is misaligned this vector is used to determine an rotation axe which can be used to align the joint along.


The documentation for this class was generated from the following file: