Program Listing for File PhysicalModalBody.h

Program Listing for File PhysicalModalBody.h#

Return to documentation for file (include/Karana/SOAFlexDyn/PhysicalModalBody.h)

/*
 * Copyright (c) 2024-2026 Karana Dynamics Pty Ltd. All rights reserved.
 *
 * NOTICE TO USER:
 *
 * This source code and/or documentation (the "Licensed Materials") is
 * the confidential and proprietary information of Karana Dynamics Inc.
 * Use of these Licensed Materials is governed by the terms and conditions
 * of a separate software license agreement between Karana Dynamics and the
 * Licensee ("License Agreement"). Unless expressly permitted under that
 * agreement, any reproduction, modification, distribution, or disclosure
 * of the Licensed Materials, in whole or in part, to any third party
 * without the prior written consent of Karana Dynamics is strictly prohibited.
 *
 * THE LICENSED MATERIALS ARE PROVIDED "AS IS" WITHOUT WARRANTY OF ANY KIND.
 * KARANA DYNAMICS DISCLAIMS ALL WARRANTIES, EXPRESS OR IMPLIED, INCLUDING
 * BUT NOT LIMITED TO WARRANTIES OF MERCHANTABILITY, NON-INFRINGEMENT, AND
 * FITNESS FOR A PARTICULAR PURPOSE.
 *
 * IN NO EVENT SHALL KARANA DYNAMICS BE LIABLE FOR ANY DAMAGES WHATSOEVER,
 * INCLUDING BUT NOT LIMITED TO LOSS OF PROFITS, DATA, OR USE, EVEN IF
 * ADVISED OF THE POSSIBILITY OF SUCH DAMAGES, WHETHER IN CONTRACT, TORT,
 * OR OTHERWISE ARISING OUT OF OR IN CONNECTION WITH THE LICENSED MATERIALS.
 *
 * U.S. Government End Users: The Licensed Materials are a "commercial item"
 * as defined at 48 C.F.R. 2.101, and are provided to the U.S. Government
 * only as a commercial end item under the terms of this license.
 *
 * Any use of the Licensed Materials in individual or commercial software must
 * include, in the user documentation and internal source code comments,
 * this Notice, Disclaimer, and U.S. Government Use Provision.
 */

/**
 * @file
 * @brief Contains the declarations for the PhysicalModalBody and ModalNodeDeformationProvider
 * classes.
 */

#pragma once

#include "Karana/SOADyn/HingeNode.h"
#include "Karana/SOADyn/Node.h"
#include "Karana/SOADyn/PhysicalBody.h"

namespace Karana::Dynamics {

    namespace kc = Karana::Core;

    /** Struct with parameters for a modal deformable body */
    struct PhysicalModalBodyParams : public PhysicalBodyParams {

        size_t nmodes = 4; //!< the number of deformation modes
        km::Vec stiffness = km::Vec::NullaryExpr(4, 1, [](int i, int j) {
            return .1 * (i + j + 1);
        }); //!< the stiffness vector (based on modal frequencies)
        km::Vec damping = km::Vec::NullaryExpr(
            4, 1, [](int i, int j) { return .01 * (i + j + 1); }); //!< the damping coefficients
        km::Mat pnode_nodal_matrix = km::Mat::NullaryExpr(6, 4, [](int i, int j) {
            return .1 * (i + j + 1);
        }); //!< the nodal matrix for the pnode
        km::Mat onode_nodal_matrix = km::Mat::NullaryExpr(6, 4, [](int i, int j) {
            return .2 * (i + j + 1); //!< the nodal matrix for the onode
        });                          //!< the nodal matrix for the onode

        /** @brief Assignment operator

            @param p the input param
            @return the output
         */
        PhysicalModalBodyParams &operator=(const PhysicalModalBodyParams &p) {
            if (this != &p) {
                PhysicalBodyParams::operator=(p);
                // Assign Derived-specific members here
                nmodes = p.nmodes;
                stiffness = p.stiffness;
                damping = p.damping;
                pnode_nodal_matrix = p.pnode_nodal_matrix;
                onode_nodal_matrix = p.onode_nodal_matrix;
            }

            return *this;
        }
    };

    /**
     * @class ModalNodeDeformationProvider
     * @brief Node deformation provider class for modeling small deformation via modal
     * representation
     *
     * See \sref{modal_flex_body_sec} section for more information of
     * deformation provider classes.
     *
     *
     */
    class ModalNodeDeformationProvider : public NodeDeformationProvider {

        // for access to _deformation_provider
        friend class PhysicalModalBody;

      public:
        /**
         * @brief Constructor
         *
         * @param name the assigned name
         * @param node the associated node
         */
        ModalNodeDeformationProvider(std::string_view name, kc::ks_ptr<Node> node);

        /**
         * @brief Destructor
         */
        ~ModalNodeDeformationProvider();

        /**
         * @brief Set the nodal deformation matrix
         * @param nodal_matrix the nodal matrix
         */
        void setNodalMatrix(const km::Mat &nodal_matrix);

        /**
         * @brief Return the nodal deformation matrix
         * @return  the nodal matrix
         */
        const km::Mat6n &getNodalMatrix() const { return _nodal_matrix; }

        /**
         * @brief Return the undeformed frame
         * @return  the undeformed Frame instance
         */
        kc::ks_ptr<kf::Frame> undeformedFrame() const { return _undeformed_frame; }

        /**
         * @brief Return the deformed translational frame
         * @return  the deformed translational Frame instance
         */
        kc::ks_ptr<kf::Frame> deformedTransFrame() const { return _deformed_trans_frame; }

        /**
         * @brief Return the deformed rotational frame
         * @return  the deformed rotational Frame instance
         */
        kc::ks_ptr<kf::Frame> deformedRotFrame() const { return _deformed_rot_frame; }

        // verify that the nodal matrix has been initialized
        bool isReady() const override;

        std::string dumpString(std::string_view prefix,
                               const Karana::Core::Base::DumpOptions *options) const override;

        /** Struct with modal deformation parameters for a node */
        struct DeformationParams : public NodeDeformationProvider::DeformationParams {
            km::Mat nodal_matrix; //!< the nodal matrix for the node

            DeformationParams() = default;

            /**
             * @brief Assignment operator.
             *
             * @param p DeformationParams to copy values from.
             * @return A reference to the newly assigned DeformationParams.
             */
            // Adding suppression, as CodeChecker complains this method has the same name as a
            // method in the base version. This is just a CodeChecker false positive.
            // codechecker_suppress [cppcheck-duplInheritedMember]
            DeformationParams &operator=(const NodeDeformationProvider::DeformationParams *p) {
                if (this != p) {
                    NodeDeformationProvider::DeformationParams::operator=(
                        p); // Call base class assignment operator
                    nodal_matrix = static_cast<const DeformationParams *>(p)->nodal_matrix;
                }

                return *this;
            }
        };

      protected:
        kc::ks_ptr<NodeDeformationProvider::DeformationParams> _getParams() const override;
        void _setParams(const NodeDeformationProvider::DeformationParams &params) override;

        /**
         * @brief Discard the provided ModalNodeDeformationProvider.
         * @param base - Base pointer to the ModalNodeDeformationProvider to discard.
         */
        void _discard(kc::ks_ptr<Base> &base) override;

        /** @brief Helper methods to compute the deformation quantities in the body
            frame for the node.

            For regular body nodes and onodes, these will
            essentially be the callbacks for the node's f2f edge. For a pnode,
            the undeformed frame is a child of the node, and the body a child
            of the undeformed frame. These helper methods will be used within
            the _undeformed frame's f2f edge's callbacks to compute the
            quantities.

            @return the relative transform
         */
        km::HomTran _transFrameRelTransformHelper() const;

        /** @brief Helper methods to compute the deformation quantities in the body
            frame for the node.

            For regular body nodes and onodes, these will
            essentially be the callbacks for the node's f2f edge. For a pnode,
            the undeformed frame is a child of the node, and the body a child
            of the undeformed frame. These helper methods will be used within
            the _undeformed frame's f2f edge's callbacks to compute the
            quantities.

            @return the relative spatial velocity
         */
        km::SpatialVector _transFrameRelSpVelHelper() const;

        /** @brief Helper methods to compute the deformation quantities in the body
            frame for the node.

            For regular body nodes and onodes, these will
            essentially be the callbacks for the node's f2f edge. For a pnode,
            the undeformed frame is a child of the node, and the body a child
            of the undeformed frame. These helper methods will be used within
            the _undeformed frame's f2f edge's callbacks to compute the
            quantities.

            @return the relative spatial acceleration
         */
        km::SpatialVector _transFrameRelSpAccelHelper() const;

        /** @brief Helper methods to compute the deformation quantities in the body
            frame for the node.

            For regular body nodes and onodes, these will
            essentially be the callbacks for the node's f2f edge. For a pnode,
            the undeformed frame is a child of the node, and the body a child
            of the undeformed frame. These helper methods will be used within
            the _undeformed frame's f2f edge's callbacks to compute the
            quantities.

            @return the relative transform
         */
        km::HomTran _rotFrameRelTransformHelper() const;

        /** @brief Helper methods to compute the deformation quantities in the body
            frame for the node.

            For regular body nodes and onodes, these will
            essentially be the callbacks for the node's f2f edge. For a pnode,
            the undeformed frame is a child of the node, and the body a child
            of the undeformed frame. These helper methods will be used within
            the _undeformed frame's f2f edge's callbacks to compute the
            quantities.

            @return the relative spatial velocity
         */
        km::SpatialVector _rotFrameRelSpVelHelper() const;

        /** @brief Helper methods to compute the deformation quantities in the body
            frame for the node.

            For regular body nodes and onodes, these will
            essentially be the callbacks for the node's f2f edge. For a pnode,
            the undeformed frame is a child of the node, and the body a child
            of the undeformed frame. These helper methods will be used within
            the _undeformed frame's f2f edge's callbacks to compute the
            quantities.

            @return the relative spatial acceleration
         */
        km::SpatialVector _rotFrameRelSpAccelHelper() const;

        /** @brief  the following helper methods are the pnode's deformation f2f
           callbacks. Because of the reversed connection for pnodes, we need to
           use the pframe versions of the regular node deformation callbacks


            @return the relative transform
           */
        km::HomTran _transFrameRelTransformReversedHelper() const;

        /** @brief  the following helper methods are the pnode's deformation f2f
           callbacks. Because of the reversed connection for pnodes, we need to
           use the pframe versions of the regular node deformation callbacks

            @return the relative spatial velocity
           */
        km::SpatialVector _transFrameRelSpVelReversedHelper() const;

        /** @brief  the following helper methods are the pnode's deformation f2f
            callbacks. Because of the reversed connection for pnodes, we need to
            use the pframe versions of the regular node deformation callbacks

           @return the relative spatial acceleration
         */
        km::SpatialVector _transFrameRelSpAccelReversedHelper() const;

        /** @brief  the following helper methods are the pnode's deformation f2f
           callbacks. Because of the reversed connection for pnodes, we need to
           use the pframe versions of the regular node deformation callbacks

            @return the relative transform
           */
        km::HomTran _rotFrameRelTransformReversedHelper() const;

        /** @brief  the following helper methods are the pnode's deformation f2f
           callbacks. Because of the reversed connection for pnodes, we need to
           use the pframe versions of the regular node deformation callbacks


            @return the relative spatial velocity
         */
        km::SpatialVector _rotFrameRelSpVelReversedHelper() const;

        /** @brief  the following helper methods are the pnode's deformation f2f
     callbacks. Because of the reversed connection for pnodes, we need to
     use the pframe versions of the regular node deformation callbacks

      @return the relative spatial acceleration
     */
        km::SpatialVector _rotFrameRelSpAccelReversedHelper() const;

      protected:
        /** the modal matrix for this node */
        km::Mat6n _nodal_matrix;

        /** Normally we have the following intermediate frames between the
           body's floating frame and a nodes frame to accommodate the
           deformations.

            Body  ->  undeformed  -> deformed_trans  -> deformed_rot  -> node

           The Body->undeformed frame transform is fixed and defines the
           location of the node in the undeformed configuration. The
           undeformed->deformed_trans transform consists of the
           translational deformation. Note that the body frame, the
           undeformed frame and the deformed_trans frame are all
           parallel. The deformed_trans->deformed_rot transform contains
           consists of the rotational deformation. The deformed_rot->node
           transform consists of the fixed rotational for the node mount.

           While this is the normal attachment sequence from the body
           frame to a node on the body, one exception is pnode for which
           the attachment sequence is reversed. However, the transforms
           for each of the edge have the same definition as for the other
           nodes.

           One of the reasons for separating out the trans/rot parts
           across two frames is that nodal equations of motion use node
           accelerations that are differentiated in the node's local
           deformed frame, while the mode shapes are defined in the body
           frame and independent of body deformation.
         */

        /** the undeformed frame for this node.   */
        kc::ks_ptr<kf::Frame> _undeformed_frame = nullptr;

        /** the "trans" deformed frame for this node. */
        kc::ks_ptr<kf::Frame> _deformed_trans_frame = nullptr;

        /** the "rot" deformed frame for this node. */
        kc::ks_ptr<kf::Frame> _deformed_rot_frame = nullptr;
    };

    /**
     * @class PhysicalModalBody
     * @brief Flexible body class supporting assumed modes based small deformation
     *
     * See the \sref{modal_flex_body_sec} section for more discussion on
     * flexible bodies.
     *
     */
    class PhysicalModalBody : public PhysicalBody {

        // For access to discard
        friend class ModalNodeDeformationProvider;

        // For access to pframe2otherPhi()
        friend class CompoundSubhinge;

      public:
        /**
         * @brief Factory method to create a PhysicalModalBody instance
         *
         * @param name the body's name
         * @param mbs the Multibody instance
         * @param nmodes the number of deformation modes
         * @return a new PhysicalModalBody instance
         */
        static kc::ks_ptr<PhysicalModalBody>
        create(std::string_view name, kc::ks_ptr<Multibody> mbs, size_t nmodes);

        /**
         * @brief PhysicalModalBody constructor. The constructor is not meant to be called directly.
         *        Please use the create(...) method instead to create an instance.
         *
         * @param name the body's name
         * @param mb the Multibody instance
         * @param nmodes the number of deformation modes
         */
        PhysicalModalBody(std::string_view name, kc::ks_ptr<Multibody> mb, size_t nmodes);

        /**
         * @brief Destructor
         */
        ~PhysicalModalBody();

        void setBodyToJointTransform(const km::HomTran &t) override;
        km::HomTran getBodyToJointTransform() const override;

        bool isReady() const override;

        /**
         * @brief Get the stiffness vector for the body.
         * @returns The stiffness vector for the body.
         */
        km::Vec getStiffnessVector() const;

        /**
         * @brief Set the stiffness vector for the body.
         * @param stiffness The new stiffness vector for the body.
         */
        void setStiffnessVector(const km::Vec &stiffness);

        /**
         * @brief Get the damping vector for the body.
         * @returns The new damping vector for the body.
         */
        km::Vec getDampingVector() const;

        /**
         * @brief Set the damping vector for the body.
         * @param damping The new damping vector for the body.
         */
        void setDampingVector(const km::Vec &damping);

        std::string dumpString(std::string_view prefix,
                               const Karana::Core::Base::DumpOptions *options) const override;

        void setParams(const PhysicalBodyParams &params) override;

        /**
         * @brief Add a serial chain of flexible physical bodies to the multibody system
         *
         * Add a serial chain of flexible bodies to the multibody system to the
         * specified root body with the specified mass properties, hinge
         * type and hinge connection properties. This method is mainly
         * used for procedurally generating large test systems.
         *
         * @param name prefix string to use for the new body names
         * @param nbodies number of bodies
         * @param root the parent body to attach the chain to
         * @param htype the hinge type
         * @param params the body params for each body
         * @return the list of new flexible bodies
         */
        static std::vector<kc::ks_ptr<PhysicalBody>>
        // Adding suppression, as CodeChecker complains this method has the same name as a method in
        // the base version. This is just a CodeChecker false positive.
        // codechecker_suppress [cppcheck-duplInheritedMember]
        addSerialChain(std::string_view name,
                       size_t nbodies,
                       PhysicalBody &root,
                       HingeType htype = HingeType::REVOLUTE,
                       PhysicalBodyParams *params = nullptr);

        /**
         * @brief Add a sub-tree of flexible physical bodies to the multibody system
         *
         * Add a sub-tree of flexible bodies to the multibody system to the
         * specified root body with the specified mass properties, hinge
         * type and hinge connection properties. This method is mainly
         * used for procedurally generating large test systems.
         *
         * @param name prefix string to use for the new body names
         * @param branch_length the number of bodies in a branch
         * @param nbranches the number of children branches
         * @param depth the number of branching levels to create
         * @param root the parent body to attach the chain to
         * @param htype the hinge type
         * @param params the body params for each body
         * @return the list of new rigid bodies
         */
        static std::vector<kc::ks_ptr<PhysicalBody>>
        // Adding suppression, as CodeChecker complains this method has the same name as a method in
        // the base version. This is just a CodeChecker false positive.
        // codechecker_suppress [cppcheck-duplInheritedMember]
        addTree(std::string_view name,
                size_t branch_length,
                size_t nbranches,
                size_t depth,
                PhysicalBody &root,
                HingeType htype = HingeType::REVOLUTE,
                PhysicalBodyParams *params = nullptr);

      public:
        const km::Mat atbiCoordMapMatrix() const override {
            return _atbi_coord_map_matrix_cache->get();
        }

        /** @brief Compute the body node's OSCM Upsilon matrix from the pnode's
           Upsilon matrix. Also used to compute the child onode
           UpsilonPlus value after crossing the modal dofs. The result
           lhs/rhs are in the node frame.

          @param node the body node
          @return the node Upsilon matrix
         */
        km::Mat66 getNodeUpsilonFromPnode(const Node &node) override;

        /** @brief Compute the body node's OSCM Upsilon matrix from the body's
           Upsilon matrix. Also used to compute the child onode
           UpsilonPlus value after crossing the modal dofs. The result4
           lhs/rhs are in the node frame.

          @param node the body node
          @return the node Upsilon matrix
         */
        km::Mat66 getNodeUpsilonFromBody(const Node &node) override;

        /** Get the (nU+6) square Upsilon matrix in the body frame after
            crossing the flex dofs

          @return the body Upsilon matrix
         */
        km::Mat getUpsilonMatrix() override;

      protected:
        km::Mat _jacobian(const kf::FrameToFrame &f2f) const override;

        /**
         * @brief The coordinate map matrix for ATBI computations
         *
         * @return the coordinate map matrix
         */
        const km::Mat &_atbiCoordMapMatrix() const { return _atbi_coord_map_matrix_cache->get(); }

        /** Overall struct for ATBI dynamics matrix quantities for a
            deformable body.

            HP (6, nU) - the lhs is in the pnode deformed translational frame
            G (6, nU) - the lhs is in the pnode deformed translational frame
            tauper (6, nU+6) - lhs is in the pnode deformed translational frame,
                     while the bottom part of the right is in the body frame

            psi  (6, nU+6) - lhs is in the pnode frame,
                     while the bottom part of the right is in the body frame

         */
        struct ATBIMatrices : public CoordBase::ATBIMatrices {

            /** the (nodes+6) size square P matrix before crossing the
               deformation dofs, at the pnode translation deformation frame */
            km::Mat P;

            /** the 6x6 rigid/rigid sub-block of the Pplus matrix after crossing the
               deformation dofs, at the pnode translation deformation frame */
            km::Mat66 Pplus_rr; // NOLINT(readability-identifier-naming)

            /** the 6x6 rigid/rigid sub-block of the Pplus matrix after
                crossing the deformation dofs, transformed to the pnode */
            km::Mat66 Pplus_rr_pnode; // NOLINT(readability-identifier-naming)

            /** HP = H*P (nU x body_nU)
             *
             * the rigid sub-block of the full HP, same as mu^*. the lhs
               & rhs are both in the pnode deformed translational frame.
             *
             */
            km::Mat HP; // NOLINT(readability-identifier-naming)

            /** D = H*P*HT  (nU x nU)
             *
             */
            km::Mat D;

            /** Dinv = inverse(D)  (nU x nU)
             *
             */
            km::Mat Dinv; // NOLINT(readability-identifier-naming)

            /** G = P*H*Dinv  (body_nU x nU)
             *
             * the rigid sub-rows of the full G. The lhs is in the
               pnode deformed translational frame.
             *
             */
            km::Mat G;

            /** tauper = I - GH  body_nU x (body_nU+nU)
             *
             * The rigid sub-rows of the full tauper. the lhs and rhs are in the
             * pnode deformed translational frame.
             *
             */
            km::Mat tauper;

            /** psi = phi * tauper (body_nU x body_nU)
             *
             * The rigid sub-rows of the full psi, the left is in the pnode frame
             * and the right in the pnode deformation frame.
             *
             */
            km::Mat psi;

            /**
             * @brief Resize the ATBI matrices
             * @param modal_n_u the modal dofs
             * @param body_n_u the rigid body dofs (6)
             */
            void resize(size_t modal_n_u, size_t body_n_u) {
                P.resize(modal_n_u + body_n_u, modal_n_u + body_n_u);
                P.setZero();

                HP.resize(modal_n_u, body_n_u);
                D.resize(modal_n_u, modal_n_u);
                Dinv.resize(modal_n_u, modal_n_u);
                G.resize(body_n_u, modal_n_u);
                tauper.resize(body_n_u, body_n_u + modal_n_u);
                psi.resize(body_n_u, body_n_u + modal_n_u);

                km::makeNotReady(HP);
                km::makeNotReady(D);
                km::makeNotReady(Dinv);
                km::makeNotReady(G);
                km::makeNotReady(tauper);
                km::makeNotReady(psi);
            }
        };

        /** Overall struct for ATBI dynamics filter quantities for an
            flexible body.
         */
        struct ATBIFilterVectors : public CoordBase::ATBIFilterVectors {

          public:
            /** the (nU+6) size ATBI z vector before crossing the
               deformation dofs - about and represented in the pnode
               translational deformation frame. */
            km::Vec z;

            /** the rigid sub-block of the full zplus ATBI spatial
               vector after crossing the deformation dofs - about and
               represented in the pnode translational deformation
               frame. */
            km::SpatialVector zplus_r;

            /** the rigid sub-block of the full zplus ATBI spatial vector after crossing the
               deformation dofs - about and represented in the pnode
               frame. */
            km::SpatialVector zplus_r_pnode;

            /** Residual hinge force  (nU)
             *
             * eps = T - H * (zR + PR*a)
             *
             */
            km::Vec epsilon;

            /** Residual hinge acceleration  (nU)
             *
             * nu  = Dinv * eps
             *
             */
            km::Vec nu;

            /**
             * @brief Resize the ATBI vectors
             * @param modal_n_u the modal dofs
             */
            void resize(size_t modal_n_u) {
                z.resize(modal_n_u + 6);

                epsilon.resize(modal_n_u);
                nu.resize(modal_n_u);
                km::makeNotReady(epsilon);
                km::makeNotReady(nu);
            }

            /**
             * @brief Dump the ATBI vector data
             *
             * @param indent prefix to apply
             */
            void dump(std::string_view indent) const;
        };

        /** Overall struct for ATBI dynamics smoother quantities for an
            flexible body.
         */
        struct ATBISmootherVectors {
            /** alpha+ vector at the onode and represented in the onode
                frame. */
            km::SpatialVector alpha_plus;
        };

      protected:
        /** matrices for computing the pnode to body node psi and
            Upsilon values for a flex body */
        struct SZNodeMatrices {
            km::Mat S;   //!< nUx6, the rhs is in the pnode deform translational frame
            km::Mat66 Z; //!< 6x6, the lhs & rhs are both in the pnode deform translational frame
        };

        /** struct for the modal Upsilon matrices */
        struct ModalUpsilonMatrices {

            /** OSI (nmodes+6) Upsilon matrix for the body about and
                  in the body frame */
            km::Mat Upsilon; // NOLINT(readability-identifier-naming)
        };

        /** @brief Same as the (6+nU, 6) _computeHst_Mfl(*this), so the lhs is
            in the body frame.
            @return the coord map matrix
         */
        km::Mat pframeCoordMapMatrix() const override;

        /** @brief Return the (6, nU+6) rigid sub-rows of the full psi
            transformation matrix between the pnode and the body.

            The lhs is in the pnode frame and the rhs in the body
            frame. This method should only be called for bodies whose
            pnode is not a floating frame. This method is used by both
            _oframe2pframePsi() and _oframe2pframePsi.

            @return the psi matrix
         */
        km::Mat getATBIMatPsi() const override;

        /** The ATBI D matrix
            @return the ATBI D nU square matrix
         */
        km::Mat getATBID() const override;

        /** @brief The ATBI Dinv matrix
            @return the ATBI Dinv nU square matrix
         */
        km::Mat getATBIDinv() const override;

        /** @brief  Return (nU+6)xnU matrix with upper rows padded in for Minv
            computations. lhs is in the body frame. Note that this
            differs from _atbi_mats.G whose lhs is in the pnode deformed
            translational frame. This version is used in the Minv
            computations.
          @return the ATBI G matrix
         */
        km::Mat getATBIG() const override;

        /** @brief Return (nU+6) square matrix with upper rows padded in
            for Minv computations. lhs is in the body frame and the
            bottom right in the pnode deformed translational frame. Note
            that this differs from _atbi_mats.tauper whose lhs is in the
            pnode deformed translational frame. This version is used in
            the Minv computations.

          @return the ATBI tauper matrix
         */
        km::Mat getATBITauper() const override;

        /* The (nU+6) P square matrix at the pnode deformed translational frame */
        km::Mat _getBodyP() const override;

        /* The (nU+6) z vector at the pnode deformed translational frame */
        km::Vec _getBodyZ() override;

        /* Return the a(k+1, k') Coriolis term (flex onode coriolis accel */
        km::SpatialVector _getChildOnodeCoriolis(const HingeOnode &ond) const override;

        /* @brief Return the a(k', k) Coriolis term (flex pnode coriolis accel

           @return the Coriolis accel (represented in the pnode frame */
        km::SpatialVector _getPnodeCoriolis() const override;

      protected:
        /** @brief  Returns the (6, nU+6) size pnode to body frame Psi

            @return the psi matrix
         */
        km::Mat _oframe2pframePsi() const override;

        /** @brief Returns the (6, nU+6) size pnode to body frame Phi

            @return the phi matrix
         */
        km::Mat _oframe2pframePhi() const override;

        /** @brief Returns the (nU+6, 6) size body frame to body node connected
            frame Phi

          @param other the other frame
          @return the phi matrix
         */
        km::Mat _pframe2otherPhi(const kf::Frame &other) const override;

        void _setupNode(Node &nd, bool force_node) override;

        /**
         * @brief Discard the provided node.
         * @param node The node to discard.
         */
        void _detachNode(kc::ks_ptr<Node> &node) override;

        /** @brief Get the (nU+6) size square body mass properties M matrix -
            value can vary with configuration when using modal
            integrals
            @return the body mass matrix
         */
        km::Mat _getM() const;

        /** @brief Get the nU size square flex/flex sub-block of the body's mass
            properties M - non-identity when using modal integrals
            @return the flex/flex block of the body mass matrix
         */
        km::Mat _getMff() const;

        /** @brief Get the nUx6 size flex/rigidly sub-block of the body's mass
            properties M - non-zero when using modal integrals
            @return the flex/rigid block of the body mass matrix
         */
        km::Mat _getMfr() const;

        /**
         * @brief Discard the node's deformation provider.
         * @param nd The node whose deformation provider we want to discard.
         */
        void _discardNodeDeformationProvider(kc::ks_ptr<Node> nd);

        /**
         * @brief Discard the pnode's deformation provider.
         */
        void _discardPnodeDeformationProvider();

      protected:
        /** @brief Compute the z ATBI filter spatial vector at the pnode after
            crossing the flex dofs
            @return the ATBI z spatial vector
         */
        km::SpatialVector _getPnodeATBIFilterZ() override;

        /** @brief Compute the P ATBI matrix at the pnode after crossing
            the flex dofs
            @return the ATBI P matrix
         */
        km::Mat66 _getPnodeATBIMatricesP() override;

        /** @brief Compute the alpha^+ ATBI smoothing spatial accel vector at the
            onode
            @param ond the onode
            @return the ATBI spatial acceleration
         */
        km::SpatialVector _getOnodeATBISmootherAlphaPlus(const HingeOnode &ond) override;

        /** @brief Compute the subhinge and modal accels as part of the ATBI smoothing step */
        void _processPnodeATBISmootherVectors() override;

        /** @brief Compute the modal accels as part of the ATBI smoothing
            step. TODO - remove override need. */
        void _processModalATBISmootherVectors() override;

        /** Compute the inter-body spatial force at the pnode from the
            inverse dynamics computations
            @return the inverse dynamics spatial force
         */
        km::SpatialVector _getPnodeInvDynForcesF() override;

        /** @brief Compute and cache the S (nUx6) and Z (6x6) matrices for
            computing pnode to body node transformations.
            @param node the node
            @return the SZ matrices for the node
         */
        SZNodeMatrices _computeSZMatrices(const Node &node);

        /** @brief Return the pnode to body node 6x6 transformation matrix - this
            takes into account Z matrix
            @param node the node
            @return the transform matrix
         */
        km::Mat66 _pnodeToChildNodeTransform(const Node &node) override;

        /** @brief Return the pnode translational deformation frame
            @return the frame
         */
        kc::ks_ptr<kf::Frame> _getPnodeDeformedTransFrame() const override;

        /** @brief Return the (nU+6)x(6) A_fl(node) matrix - transformed to the
               "from_frame" via phi(from_frame, body_frame). The A_fl(node)
               matrix by itself is

                   [Pi^* // phi(bd, node_trans)] * phi(node_trans, node)

              We apply the phi(from_frame, bd) to the bottom row to transform it
              to the from_frame.

              This also works for floating base systems (where the pnode is no
              longer a physical point) because we do not allow any offsets
              between the pnode and the body frame for such bodies. Otherwise, we
              would have to use phi(pnode, node_trans) because the P value is at
              the pnode, not the body frame.

              @param node the node
              @param from_frame the from frame
              @return the transform matrix
             */
        km::Mat _bodyToChildNodeTransform(const Node &node,
                                          const kf::Frame &from_frame) const override;

        /** @brief Cache callback to compute the full (_nU + 6)x(_nU + hge_nU)
           size Hst matrix for the flex body at the pnode frame

         * @param val the data buffer for the computed value
         */
        void _computeATBICoordMapMatrix(km::Mat &val) const;

        /** @brief Compute the (nU+6)xnU Hst_Mfl matrix transformed from the
            (lhs) pnode deformed trans frame to the specified (rhs)
            at_frame (often the body frame). This is the left block of
            the full Hst matrix when the "at_frame" is the body frame
            (per the book). Note however that the pnode is the at_frame
            when working with the full Hst matrix.

         * @param at_frame the at frame
         * @return the Hst matrix
         */
        km::Mat _computeHst_Mfl(const kf::Frame &at_frame) const;

        /** @brief Process the external spatial forces on the body force nodes
            and return the overall nU sized vector
            @return the modal external forces
         */
        const km::Vec _externalModalForces() const;

        /** @brief Process the constraint spatial forces on the body constraint
            nodes and return the overall nU sized vector
            @return the modal constraint forces
         */
        const km::Vec _constraintModalForces() const;

      protected:
        /**
         * @brief Helper method to set up the node deformation
         * @param nd the node
         */
        void _setupNodeDeformation(kc::ks_ptr<Node> nd);

        /**
         * @brief Helper method to set up the pnode deformation
         */
        void _setupPnodeDeformation();

        void _discardHingePnode() override;
        void _discardHingeOnode(kc::ks_ptr<HingeOnode> &onode) override;

        /** @brief Create a pnode with modal deformation with a nodal matrix and undeformed
            intermediate frame. The body will be a child of the pnode.
            @param floating_frame whether the body has a 6dof hinge or not
            @return the new pnode
         */
        kc::ks_ptr<HingePnode> _createPnode(bool floating_frame) override;

        /** @brief create a onode with modal deformation with a nodal matrix and undeformed
            intermediate frame.
            @param name the name
            @return the new onode
         */
        kc::ks_ptr<HingeOnode> _createOnode(std::string_view name) override;

        /** @brief Set the transform to a body node. For a deformable
            body, this is the transform value in the undeformed
            configuration. This method should be used for all nodes,
            except for the pnode for whom the
            get/setBodyToJointTransform() method should be used. These
            methods are protected to allow them to specialized for rigid
            and deformable bodies.
            @param node the node
            @param t the transform
         */
        void _setBodyToNodeTransform(Node &node, const km::HomTran &t) override;

        /** @brief Get the transform to a body node. For a deformable
            body, this is the transform value in the undeformed
            configuration. This method should be used for all nodes,
            except for the pnode for whom the
            get/setBodyToJointTransform() method should be used. These
            methods are protected to allow them to specialized for rigid
            and deformable bodies.
            @param node the node
            @return the transform
         */
        km::HomTran _getBodyToNodeTransform(const Node &node) const override;

        /** @brief transform the (nU+6)x(nU+6) body flex mass properties matrix
           from the body frame to the specified frame (usually pnode or
           pnode_trans
           @param frame the target frame
           @return the body mass matrix
         */
        km::Mat _getMassAtFrame(const kf::Frame &frame) const;

        /** @brief Update the full (nU+6)x(nU+6) flex input R matrix with
            contributions from the child onodes and the body itself
            transformed to the pnode.
         * @param R the data buffer for the computed value
         */
        void _getPnodeCRBInertiaMatrix(km::Mat &R) override;

      protected:
        /**
         * @brief Helper method to set up the data caches
         */
        void _oneTimeSetupDataCaches();

        /**
         * @brief Helper method to tear down the data caches
         */
        void _oneTimeTeardownDataCaches();

      protected:
        /** the deformation stiffness vector */
        km::Vec _stiffness_vector;

        /** the deformation damping vector */
        km::Vec _damping_vector;

        /** set to true if modal integrals have been set up for this
            body */
        bool _using_modal_integrals = false;

        /** the modal OSI Upsilon matrices */
        ModalUpsilonMatrices _modal_upsilon_matrices;

        /** the (6*nU)xNU joint map matrix data cache
            e for ATBI
            computations for the subhinge. */
        kc::ks_ptr<kc::DataCache<km::Mat>> _atbi_coord_map_matrix_cache = nullptr;
    };

} // namespace Karana::Dynamics