Class CompoundSubhinge#

Nested Relationships#

Nested Types#

Inheritance Relationships#

Base Types#

Derived Type#

Class Documentation#

class CompoundSubhinge : public Karana::Core::LockingBase, public Karana::Dynamics::SubhingeBase#

Represents the articulation subhinge class for CompoundBody subhinges.

Subclassed by Karana::Dynamics::CECompoundSubhinge

Public Functions

virtual ~CompoundSubhinge()#

CompoundSubhinge destructor.

inline virtual const std::string &name() const override#

Return the object’s name.

Returns:

The object’s string name.

inline virtual const kc::id_t &id() const override#

Return the object’s id.

Returns:

The object’s id.

inline virtual const std::string &typeString() const noexcept override#

The number of generalized coords for the CompoundSubhinge.

The number of velocity coords for the CompoundSubhinge.

Returns:

the number of coordinates

Returns:

the number of velocity coordinates

inline virtual const km::Mat atbiCoordMapMatrix() const override#

Return the coordinate map matrix to be used for ATBI computations.

Returns:

coordinate map matrix

virtual SubhingeBase::SUBHINGE_TYPE subhingeType() const override#

Helper method to return the subhinge type.

Returns:

the subhinge type

virtual kc::ks_ptr<kf::Frame2Frame> f2f() const override#

Return the frame to frame for the CoordBase.

The returned f2f helps locate the CoordBase in the frames tree. Its transform etc data does not however represent the relative transformation changes from the changes to this object’s coordinates.

Returns:

Return the oframe Frame instance

virtual std::string dumpString(const std::string &prefix, const Karana::Core::Base::dumpOptions *options) const override#

Return information about the object.

Parameters:
  • prefix – A string to use as prefix for each output line

  • options – Struct with options to tailor the output

Returns:

String with the information about the object.

virtual void setQ(const Eigen::Ref<const km::Vec> &val) override#

Check whether parameters have been set.

Set the Q coordinates.

See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.

Returns:

True if the parameters have been set. Get/set methods for buffers for the generalized coordinates for this coordinate provider.

Parameters:

val – Array of values.

virtual void setQ(double fill_value) override#

Set the Q coordinates to a constant value.

See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.

Parameters:

fill_value – Fill value.

virtual const km::Vec &getQ() const override#

Return the Q coordinates.

See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.

Returns:

Array of values.

virtual void setU(const Eigen::Ref<const km::Vec> &val) override#

Set the U velocity coordinates.

See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.

Parameters:

val – Array of values.

virtual void setU(double fill_value) override#

Set the U velocity coordinates to a constant value.

See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.

Parameters:

fill_value – Fill value.

virtual const km::Vec &getU() const override#

Return the U velocity coordinates.

See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.

Returns:

Array of values.

virtual void setT(const Eigen::Ref<const km::Vec> &val) override#

Set the T generalized forces.

See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.

Parameters:

val – Array of values.

virtual void setT(double fill_value) override#

Set the T generalized forces to a constant value.

See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.

Parameters:

fill_value – Fill value.

virtual const km::Vec &getT() const override#

Return the T generalized forces.

See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.

Returns:

Array of values.

virtual void setUdot(const Eigen::Ref<const km::Vec> &val) override#

Set the Udot acceleration coordinates.

See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.

Parameters:

val – Array of values.

virtual void setUdot(double fill_value) override#

Set the Udot acceleration coordinates to a constant value.

See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.

Parameters:

fill_value – Fill value.

virtual const km::Vec &getUdot() const override#

Return the Udot acceleration coordinates.

See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.

Returns:

Array of values.

virtual const km::Vec &getQdot() const override#

Return the Qdot rate coordinates.

See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.

Returns:

Array of values.

CompoundSubhinge(kc::ks_ptr<CompoundHinge> hge)#

Constructs a CompoundSubhinge.

Protected Functions

inline virtual km::Mat getUpsilonMatrix() override#

The Upsilon at the pframe (after crossing the ATBI dofs). For a subhinge, pframe is the regular subhinge pframe, and for a flex body it is the body frame. For a subhinge, this is a nU size square matrix, while for a flex body it is a (nU+6) size square matrix.

km::SpatialVector aprimeAccel(kc::ks_ptr<PhysicalBody> bd) const#

Update and return the aprime Coriolis accel for an embedded physical body

inline virtual km::Mat jacobian(const kf::Frame&, bool) const override#

Return the analytical 6xnU Jacobian matrix for the subhinge to the target frame. The left side of the Jacobian is in the target frame. This method assumes that the target frame is outboard of the subhinge’s pframe.

Parameters:
  • target – the target frame whose Jacobian is computed

  • oriented – if true, the polarity of the subhinge is assumed to be aligned with the path to the target frame

Returns:

the Jacobian matrix

inline virtual km::Mat jacobianDot(const kf::Frame&, bool) const override#

Return the time derivative of the Jacobian matrix for the target Karana::Frame::Frame.

For this coordinates provider, return the 6xnU Jacobian matrix time derivative for the target Karana::Frame::Frame. If oriented is false, the return value is negated.

See The frames layer section for more information on frames, and Jacobians section for more on Jacobians.

See also

jacobian()

Parameters:
  • Frame – the target frame

  • bool – the orientation of the coordinates provider

Returns:

the Jacobian matrix time derivative

inline const km::Mat &getE_Phi_G() const#

The nbodies size row matrix with \phi(vroot_pnode, pnode) 6x6 matrix elements for the $\phi$ matrix from the physical virtual root body’s pnode to the pnode of each aggregated physical body. This is denoted A(p, G) = E_G A_G in Section 18.3.1.

void _computeATBICoordMapMatrix(km::Mat &val) const#

Callback to compute the (6nbodies + bd_nU) x (bd_nU + sh_nU) coord map matrix for the compound subhinge, where bd_nU denotes the overall deformation dofs for the embedded bodies, and sh_nU the overall subhinge generalized velocities for the embedded subhinges. This is in fact the Jacobian from the aggregated subhinges and modal coords to the pnodes and modal coords of the aggregated bodies. It is referred to as $\underbar H_{G}^* = \phi^* H_G$ as defined in Eq 18.4.

There is one block row per embedded body, with the size of the row being the number of body deformation coords plus 6, with the modal etadot coords coming first followed by the 6 rigid body spatial velocity elements. There is also one block column per embedded body, with the size of the column being the number of body deformation coords + the number of subhinge genvel coords. Again, the deformation coords come first.

void _discard(kc::ks_ptr<kc::Base> &base) override#

Discard the provided CompoundSubhinge.

Parameters:

base – - Base pointer to the CompoundSubhinge to discard.

km::Mat66 _getVrootPnodeATBIMatrixP()#

Method to compute the 6x6 ATBI P matrix at the physical parent body’s pnode

km::SpatialVector _getVrootPnodeATBIFilterZ()#

Method to compute the ATBI z spatial vector at the physical physical parent body’s pnode

km::SpatialVector _getVrootPnodeInvDynF()#
km::SpatialVector _getBaseOnodeATBIFilterZplus(kc::ks_ptr<HingeOnode> base_ond)#

Method to pull out the P ATBI matrix at a base onode from the Pplus matrix. This method is used in the callback by the base onode’s atbi_matrix cache.

void _computeATBIMatrices()#
void _computeATBIFilterVectors()#
void _computeATBISmootherVectors()#
void _computeUpsilonMatrices()#
km::SpatialVector _computeAprimeAccel(kc::ks_ptr<PhysicalBody> bd, kc::ks_ptr<PhysicalBody> prev_bd) const#

Get the coord data for the aggregation subtree for the compound body

inline virtual km::Mat getATBIMatPsi() const override#

Get the ATBI matrix psi value.

Returns:

The ATBI matrix psi value for this subhinge.

virtual km::Mat getATBID() const override#
virtual km::Mat getATBIDinv() const override#
inline virtual km::Mat getATBIG() const override#

The ATBI G matrix at the pframe. For a subhinge, pframe is the regular subhinge pframe, and for a flex body it is the body frame. This is different from _atbi_mats.G.

inline virtual km::Mat getATBITauper() const override#

The ATBI tauper matrix at the pframe. For a subhinge, pframe is the regular subhinge pframe, and for a flex body it is the body frame. This is different from _atbi_mats.tauper.

void _computeInvDynGenForce()#

Compute the subhinge’s generalized force value for inverse dynamics

void _computeE_Phi_G(km::Mat &val)#

Callback method to compute the (6 times 6*nbodies) size E_Ph_G matrix for the compound body

virtual km::Mat _oframe2pframePsi() const override#

for flex bodies returns 6x(nU+6) ATBI psi matrix, for subhinges the size is 6x6. For a flex body, the lhs is at the pnode, and the rhs at the body frame. For a subhinge, the lhs/rhs are the subhinge’s oframe and pframe pair.

virtual km::Mat _oframe2pframePhi() const override#

for flex bodies returns 6x(nU+6) phi matrix, for subhinges the size is 6x6. For a flex body, the lhs is at the pnode, and the rhs at the body frame. For a subhinge, the lhs/rhs are the subhinge’s oframe and pframe pair.

virtual km::Mat _pframe2otherPhi(const kf::Frame &other) const override#

for flex bodies returns (nU+6)x6 psi matrix, for subhinges the size is 6x6. For a flex body, the lhs is at the body frame, and the rhs at the other frame. For a subhinge, the lhs is the pframe, and the rhs at teh other frame.

Protected Attributes

kc::ks_ptr<CompoundBody> _parent_body = nullptr#
std::map<std::pair<kc::id_t, kc::id_t>, bool> _body_pnodes_orientation_map#

map with orientation values for every <pnode, coord element> prir for the bodies and phsyical coord data physical elements in the compound body. Thus for every <bd, coord element> preenst in the map, the true/false value indicates that the coord element is oriented/opposed in the virtual root/pnode path. A missing entry indicates that the coord element is not in the path from the virual root to the pnode, and hence does not contribute to its motion.

This map is used in assembling Jacobian from coord elements to frames in the multibody system.

std::unordered_map<kc::id_t, kc::ks_ptr<kc::DataCache<km::SpatialVector>>> _aprime_caches#

Data caches for evaluating the “aprime” Coriolis accel values in the ATBI forward dynamics algorithm for all the aggregated physical bodies. Each cache returns the a’ Coriolis accel value for the pnode of a physical body.

kc::ks_ptr<kc::DataCache<km::Mat>> _E_Phi_G_cache = nullptr#

Data cache for the nbodies size row matrix with \phi(vroot_pnode, pnode) 6x6 matrix elements for the $\phi$ matrix from the physical virtual root body’s pnode to the pnode of each aggregated physical body. This is denoted A(p, G) = E_G A_G in Section 18.3.1.

size_t _coord_map_rows = 0#

overall CoordData for the compound subhinge that combines the CoordData for the subhinges as well as the one for the embedded bodies that are deformable The number of rows for the coord map matrix. It is 6 times the number of physical bodies plus the sum of their deformation dofs

kc::ks_ptr<kc::DataCache<km::Mat>> _atbi_coord_map_matrix_cache = nullptr#

the (6*nbodies)xNU joint map matrix data cache for ATBI computations for the subhinge.

mutable km::Vec _getQ_cache#

Vector for storing getQ.

mutable km::Vec _getQdot_cache#

Vector for storing getQdot.

mutable km::Vec _getU_cache#

Vector for storing getU.

mutable km::Vec _getUdot_cache#

Vector for storing getUdot.

mutable km::Vec _getT_cache#

Vector for storing getT.

struct ATBIFilterVectors : public Karana::Dynamics::CoordBase::ATBIFilterVectors#

Public Functions

inline void resize(size_t hge_nU, size_t n_bodies)#

Public Members

km::Vec z#

the z ATBI spatial vector for the subhinge on the pframe side of the subhinge and represented in pframe

km::Vec zplus#

the zplus vector after crossing the subhinge about and expressed in the subhinge’s oframe.

km::Vec epsilon#

Residual hinge force (nU)

eps = T - H * (zR + PR*a)

km::Vec nu#

Residual hinge acceleration (nU)

nu = Dinv * eps

struct ATBIMatrices : public Karana::Dynamics::CoordBase::ATBIMatrices#

Overall struct for ATBI dynamics matrix quantities for an articulation subhinge which includes the fixed and subhinge dof size matrices.

Public Functions

inline void resize(size_t hge_nU, size_t n_bodies)#

Resize the matrix elements where hge_nU is the overal number of generalized velocities from all the aggregated physical subhinges, and n_bodies is the number of aggregated physical bodies.

Public Members

km::Mat P#

The (nbodies x nbodies) block diagonal matrix with 6x6 ATBI P matrix element contributions from each of the aggregated physical bodies about their pnodes. Each body’s contribution is expressed in the body’s pnode frame.

This is only true for rigid body matrices. For deformable bodies, each would be a (6+nmodes) matrix.

TODO - store the block diagonal matrix elements in a map container to save storage, or use sparse matrix class.

km::Mat Pplus#

The (nbodies x nbodies) Pplus block diagonal matrix with 6x6 matrix elements after crossing the compound subhinge. The block matrix entries are about the pnode for each of the aggregated physical bodies. Note that this matrix is NOT block diagonal

km::Mat HP#

HP = H*P (nU x body_nU)

For a subhinge the lhs is in the pframe, while it in the pnode deformed translational frame for a flex body.

km::Mat D#

D = H*P*HT (nU x nU)

km::Mat Dinv#

Dinv = inverse(D) (nU x nU)

km::Mat G#

G = P*H*Dinv (body_nU x nU)

For a subhinge the lhs is in the pframe, while it in the pnode deformed translational frame for a flex body.

km::Mat tauper#

tauper = I - GH (body_nU x body_nU)

For a subhinge the lhs is in the pframe, while it in the pnode deformed translational frame for a flex body.

km::Mat psi#

psi = phi * tauper (body_nU x body_nU)

For a subhinge, the left is in the oframe, right in the pframe. For a flex body, the lefts is in the pnode frame and the right in the body frame.