Class LoopConstraintHinge#
Defined in File LoopConstraintHinge.h
Inheritance Relationships#
Base Type#
public Karana::Dynamics::LoopConstraintBase(Class LoopConstraintBase)
Class Documentation#
-
class LoopConstraintHinge : public Karana::Dynamics::LoopConstraintBase#
Class for loop constraints that are based on a hinge to define the constraint See the.
Hinge loop-constraints section for more discussion on hinge loop constraints.
Public Functions
-
LoopConstraintHinge(kc::ks_ptr<Multibody> &mb, kc::ks_ptr<kf::Frame2Frame> constrainet_f2f, const std::string &name, HingeBase::HINGE_TYPE htype, const std::vector<SubhingeBase::SUBHINGE_TYPE> &subhinge_types = std::vector<SubhingeBase::SUBHINGE_TYPE>())#
Constructor.
-
inline virtual const std::string &typeString() const noexcept override#
Returns the type string of LockingBase.
- Returns:
The type string.
-
inline virtual bool hasHinge() const override#
Return true if the loop constraint is based on a hinge.
- Returns:
true if the loop constraint is based on a hinge
-
inline kc::ks_ptr<FramePairHinge> hinge() const#
Return the FramePairHinge hinge associated with this loop constraint.
When the constraint is satisfied, the relative configuration, velocity and accel values across the f2f are constrained to those satisfied by the associated constraint hinge
- Returns:
the FramePairHinge instance
-
inline kc::ks_ptr<kf::Frame2Frame> errorFrame2Frame() const#
the Karana::Frame::Frame2Frame that measures the constraint residual error
The constraint is fully satisfied only when this f2f relative transform, spatial velocity and acceleration values are zero, i.e. its oframe and pframe are coincident
- Returns:
the error Frame2Frame instance
-
void spExternalForceFromT(const km::Vec &T, bool no_accumulate = true)#
ApplyT generalized force at the constraint hinge as an external force.
This method is used to handle any generalized forces at cut-joints. Once the joint is cut, its generalized forces are no longer included in the normal dynamics. The workaround is to convert the cut-joint generalized forces into equivalent equal and opposite external forces at the constraint nodes for the cut-joint.
- Parameters:
T – the input generalized forces
no_accumulate – if true, then accumulate the input forces at the constraint nodes
-
virtual km::Vec poseError() const override#
Return the 6 size pose residual term for the constraint.
Used for computing the pose configuration kinematics
- Returns:
The pose residual eror
-
km::SpatialVector getTAInterBodyForce()#
Return the interbody spatial force at the source node for TA dynamics.
This method returns the interbody force at the source when doing TA dynamics for the loop constraint. The force has the sign as if acting on the target node (this is consistent with our general convention to book keep the pnode’s inter-body force at the onode). The term also includes contributions from any generalized forces at the cut-joint.
The method should only be called after TA forward dynamics has been called, since it expects the constraint forces to be set in the constraint nodes. Also this method assumes that the T value in the CoordData member is the cutjoint generalized force value.
- Returns:
the inter-body spatial force
-
inline virtual size_t nResiduals() const override#
Return the size of residuals for the constraint.
- Returns:
the residuals size for the constraint
-
virtual km::Vec velError() const override#
Return the current constraint spatial velocity error.
- Returns:
the spatial velocity error as a 6-vector
-
virtual km::Vec accelError() const override#
Return the current constraint spatial acceleration error.
- Returns:
the spatial acceleration error as a 6-vector
Public Static Functions
-
static const kc::ks_ptr<LoopConstraintHinge> create(kc::ks_ptr<Multibody> &mb, kc::ks_ptr<kf::Frame2Frame> constraint_f2f, const std::string &name, HingeBase::HINGE_TYPE htype, const std::vector<SubhingeBase::SUBHINGE_TYPE> &subhinge_types = std::vector<SubhingeBase::SUBHINGE_TYPE>())#
Factory method for creating a LoopConstraintHinge instance.
- Parameters:
mb – The Multibody instance
constraint_f2f – the Karana::Frame::Frame2Frame defining the constrained Frame pair
name – the name for the loop constraint instance
htype – the HingeBase::HINGE_TYPE defining the constraint type
subhinge_types – the list of SubhingeBase::SUBHINGE_TYPE subhinge types for a custom hinge type
- Returns:
a LoopConstraintHinge instance
-
static kc::ks_ptr<PhysicalHinge> toPhysicalHinge(const LoopConstraintHinge &lc, bool reverse)#
Convert this loop constraint into an inter-body PhysicalHinge.
Replaces the loop constraint with a hinge between the constraint nodes to make one body the child of the other. This method can only be called where the new child body (either of source or target) is a base body with a 6 dof hinge. This requirement allows us to preserve the system’s tree topology. If reverse false, the target node’s body is made the child of the source node’s body, and the reverse versa if reverse is true.
- Parameters:
lc – The loop constraint to replace with a hinge
reverse – If true, reverse the polarity of the hinge
- Returns:
the new hinge
Protected Functions
-
virtual km::Vec _accelResidual() const override#
Return the (6-nU) size accel residual term for the constraint.
Used for computing the lambda (Lagrnage multiplier) terms for the TA dynamics correction step
- Returns:
The acceleraton residual eror
-
void updateInvDynT()#
Update the generalized force values for the constraint hinge from the constraint forces. This is used when running inverse dynamics with loops, to recover the constraint hinge generalized forces from the constraint forces.
-
void _discard(kc::ks_ptr<Base> &base) override#
Discard the provided LoopConstraintHinge.
- Parameters:
base – - Base pointer to the LoopConstraintHinge to discard.
-
virtual void _computeQMats(QMats &val) override#
-
km::SpatialVector T2TargetConstraintSpForce(const km::Vec &T) const#
Get the full spatial force needed at the source and target constraint nodes for the generalized force being applied at the constraint hinge
-
km::SpatialVector T2SourceConstraintSpForce(const km::SpatialVector &tgt_f) const#
Protected Attributes
-
kc::ks_ptr<kf::Frame2Frame> _error_f2f#
the defining frame to frame for this constraint. The only motion allowed across this f2f is that permitted by the associated hinge
-
std::optional<HingeBase::HINGE_TYPE> _hinge_type = std::nullopt#
-
km::Mat _Q#
the constraint node of the physical body the source frame is attached to. if null, the source frame is not attached to a body the constraint node of the physical body the target frame is attached to. if null, the target frame is not attached to a body cache for computing the (6-NU)x6 the Q relaated orthogonal complement matrices for the constraint hinge coordinate matrix. The orthogonal complement for the hinge oframe coord map matrix (source frame). This is used to compute sourceQ and targetQ for the constraint
-
LoopConstraintHinge(kc::ks_ptr<Multibody> &mb, kc::ks_ptr<kf::Frame2Frame> constrainet_f2f, const std::string &name, HingeBase::HINGE_TYPE htype, const std::vector<SubhingeBase::SUBHINGE_TYPE> &subhinge_types = std::vector<SubhingeBase::SUBHINGE_TYPE>())#