Class HingeBase#
Defined in File HingeBase.h
Nested Relationships#
Nested Types#
Inheritance Relationships#
Derived Types#
public Karana::Dynamics::CompoundHinge(Class CompoundHinge)public Karana::Dynamics::FramePairHinge(Class FramePairHinge)
Class Documentation#
-
class HingeBase#
Represents the base class for articulation hinges.
This is the abstract base class for hinge containers for PhysicalHinge and CompoundHinge classes that define articulation for bodies. See Connecting bodies via hinges section for more discussion on hinges.
Subclassed by Karana::Dynamics::CompoundHinge, Karana::Dynamics::FramePairHinge
Public Types
-
enum class HingeType#
Enums for the pre-defined and known hinge types.
Values:
-
enumerator LOCKED#
locked subhinge, no relative motion permitted
-
enumerator PIN#
1 dof hinge with a single SubhingeBase::SubhingeType::PIN subhinge
-
enumerator UJOINT#
2 dof hinge with 2 successive SubhingeBase::SubhingeType::PIN subhinges
-
enumerator GIMBAL#
3 dof hinge with 2 successive SubhingeBase::SubhingeType::PIN subhinges
-
enumerator BALL#
3 dof hinge with 1 SubhingeBase::SubhingeType::SPHERICAL subhinge
-
enumerator BALL_QUAT#
3 dof hinge with 1 SubhingeBase::SubhingeType::SPHERICAL_QUAT subhinge
-
enumerator SLIDER#
1 dof hinge with 1 SubhingeBase::SubhingeType::LINEAR subhinge
-
enumerator PLANAR#
2 dof hinge with 2 successive SubhingeBase::SubhingeType::LINEAR subhinges
-
enumerator TRANSLATIONAL#
3 dof hinge with 3 successive SubhingeBase::SubhingeType::LINEAR subhinges
-
enumerator FULL6DOF#
6 dof hinge with a SubhingeBase::SubhingeType::LINEAR3 subhinge followed by a
-
enumerator CYLINDRICAL#
2 dof hinge with a SubhingeBase::SubhingeType::LINEAR subhinge followed by a SubhingeBase::SubhingeType::PIN subhinge
-
enumerator HELICAL#
1 dof hinge with a single SubhingeBase::SubhingeType::SCREW subhinge
-
enumerator HOOKE#
2 dof hinge that keeps an outboard body frame’s Y-axis perpendicular to an inboard body frame’s X-axis. The subhinge sequence consists of a pair of SubhingeBase::SubhingeType::PIN subhinges. The hinge parameters can be computed using the HingeBase::getHookeHingeParams() method.
-
enumerator INLINE#
4 dof hinge that keeps an outboard body frame’s Z-axis constrained to translate along an inboard body frame’s Z-axis. The subhinge sequence consists of a SubhingeBase::SubhingeType::LINEAR subhinge followed by a SubhingeBase::SubhingeType::SPHERICAL subhinge The hinge parameters can be computed using the HingeBase::getInlineHingeParams() method.
-
enumerator INPLANE#
5 dof hinge that keeps an outboard body frame constrained to translate in an inboard body frame’s XY plane. The subhinge sequence consists of a pair of SubhingeBase::SubhingeType::LINEAR subhinges followed by a !< SubhingeBase::SubhingeType::SPHERICAL subhinge. The hinge parameters can be computed using the HingeBase::getInplaneHingeParams() method.
-
enumerator PERPENDICULAR#
5 dof hinge that keeps an outboard body frame’s Z-axis to remain perpendicular to an inboard body frame’s Z-axis. The subhinge sequence consists of a SubhingeBase::SubhingeType::LINEAR3 subhinge followed by a pair of SubhingeBase::SubhingeType::PIN subhinges. The hinge parameters can be computed using the HingeBase::getPerpendicularHingeParams() method.
-
enumerator PARALLEL#
4 dof hinge that keeps an outboard frame’s Z-axis to remain parallel to an inboard body frame’s Z-axis. The subhinge sequence consists of a SubhingeBase::SubhingeType::LINEAR3 subhinge followed by a SubhingeBase::SubhingeType::PIN subhinge. The hinge parameters can be computed using the HingeBase::getParallelHingeParams() method.
-
enumerator CUSTOM#
hinge with user specified sequence of subhinge types
-
enumerator COMPOUND#
hinge with a single SubhingeBase::SubhingeType::COMPOUND subhinge
-
enumerator LOCKED#
Public Functions
-
inline HingeBase(HingeBase::HingeType htype)#
Constructs a HingeBase.
- Parameters:
htype – the hinge type
-
virtual std::string_view typeString() const noexcept = 0#
Returns the type string of the HingeBase.
- Returns:
The type string.
-
virtual std::string_view name() const = 0#
Return the name of the hinge instance.
- Returns:
the hinge name
-
kc::ks_ptr<SubhingeBase> subhinge(size_t index) const#
Return the SubhingeBase subhinge instance at the specified index.
- Parameters:
index – the subhinge index
- Returns:
the subhinge object
-
inline size_t nSubhinges() const#
Return the number of subhinges in the hinge.
- Returns:
the number of subhinges
-
inline const kc::RegistryList<SubhingeBase> &subhinges() const#
Return the list of SubhingeBase subhinges.
- Returns:
the list of subhinges
-
virtual km::Mat pframeCoordMapMatrix() const = 0#
The overall pframe coordinate map matrix for the hinge.
Return the overall 6xnU() coord map matrix for the hinge in the pframe frame from all of its subhinges. Note that the matrix will be configuration dependent when there are multiple subhinges. This method is specialized by PhysicalHinge and CompoundHinge hinges.
- Returns:
the coordinate map matrix
-
km::Mat pframeCoordMapMatrixOrthoComplement() const#
Return the orthogonal complement for the pframeCoordMapMatrix() matrix.
Compute the orthogonal complement (OC) of the pframe coord map matrix computed by pframeCoordMapMatrix(). The product of this OC with the pframe coord map matrix is zero.
- Returns:
the orthogonal complement matrix
-
km::Mat oframeCoordMapMatrixOrthoComplement() const#
Return the orthogonal complement for the oframe coordinate map matrix.
Compute the orthogonal complement (OC) of the pframe coord map matrix. The product of the OC with the oframe coord map matrix is zero.
- Returns:
the orthogonal complement matrix
-
km::Vec pframeCoordMapSingularValues() const#
Return list of singular values for the hinge’s pframe coord map matrix.
This method is handy for monitoring potential loss in rank for hinges such as ujoint and gimbal hinges. For full rank, there should be nu() singular values.
- Returns:
Array of singular values.
-
size_t nU() const#
Return the total nU dofs from all the subhinges.
- Returns:
the total number of U coordinates across the subhinges
Public Static Functions
-
static std::vector<SubhingeBase::SubhingeType> getSubhingeTypes(HingeBase::HingeType htype)#
Return the list of SubhingeBase::SubhingeType subhinge types for a known hinge type.
A hinge is a container for a list of subhinges. This method returns the list of subhinge types for a known hinge type.
- Parameters:
htype – the hinge type
- Returns:
list of subhinge types
-
static std::string hingeTypeString(HingeType htype)#
Helper method to return the string name for a HingeType hinge type.
- Returns:
the hinge type as a string
-
static HingeParams getHookeHingeParams(const km::UnitQuaternion &ij_q)#
Helper method to compute the onode, pnode transform and axis params for a HingeType::HOOKE hinge.
For a HingeType::HOOKE joint, an outboard body’s frame’s Y-axis is constrained to remain perpendicular to an inboard body frame’s X-axis, and the pair of frames to remain co-located.
- Parameters:
ij_q – the inboard to outboard frames relative orientation unit quaternion
- Returns:
struct with the hinge onode, pnode and axis parameter values
-
static HingeParams getInlineHingeParams()#
Helper method to compute the onode, pnode transform and axis params for an HingeType::INLINE hinge.
For an HingeType::INLINE joint, an outboard body frame is constrained to translate only along an inboard body frame’s Z-axis
- Returns:
struct with the hinge onode, pnode and axis parameter values
-
static HingeParams getInplaneHingeParams()#
Helper method to compute the onode, pnode transform and axis params for an HingeType::INPLANE hinge.
For an HingeType::INPLANE joint, an outboard body frame is constrained to translate only within the inboard frame’s XY-plane
- Returns:
struct with the hinge onode, pnode and axis parameter values
-
static HingeParams getPerpendicularHingeParams(const km::UnitQuaternion &ij_q)#
Helper method to compute the onode, pnode transform and axis params for a HingeType::PERPENDICULAR hinge.
For a HingeType::PERPENDICULAR joint, an outboard body frame’s Z-axis is constrained to remain perpendicular to an inboard body frame’s Z-axis
- Parameters:
ij_q – the inboard to outboard frames relative orientation unit quaternion
- Returns:
struct with the hinge onode, pnode and axis parameter values
-
static HingeParams getParallelHingeParams()#
Helper method to compute the onode, pnode transform and axis params for a HingeType::PARALLEL hinge.
For a HingeType::PARALLEL joint, an outboard body frame’s Z-axis is constrained to remain parallel to an inboard body frame’s Z-axis. It is assumed that the outboard frame’s Z-axis is parallel to the inboard frame’s Z-axis to begin with.
- Returns:
struct with the hinge onode, pnode and axis parameter values
Protected Functions
-
inline virtual km::Mat oframeCoordMapMatrix() const#
Protected Attributes
-
kc::RegistryList<SubhingeBase> _subhinges_list#
ordered list of subhinges
-
std::vector<SubhingeBase::SubhingeType> _subhinge_types#
-
struct HingeParams#
Struct with hinge parameters for the HingeType::HOOKE, HingeType::INLINE etc hinge types defined by motion constraints between a pair of frames on the inboard and outboard bodies.
Public Members
-
km::UnitQuaternion i_to_onode_q = km::UnitQuaternion(0, 0, 0, 1)#
onode orientation with respect to the inboard frame
-
km::UnitQuaternion j_to_pnode_q = km::UnitQuaternion(0, 0, 0, 1)#
onode orientation with respect to the outboard frame
-
km::Mat axes#
3xm matrix with columns defining the 1-dof subhinge axes
-
km::UnitQuaternion i_to_onode_q = km::UnitQuaternion(0, 0, 0, 1)#
-
enum class HingeType#