Class PhysicalBody

Contents

Class PhysicalBody#

Nested Relationships#

Nested Types#

Inheritance Relationships#

Base Types#

Derived Type#

Class Documentation#

class PhysicalBody : public Karana::Frame::Frame, public Karana::Dynamics::BodyBase#

Represents a rigid physical body.

This class is for rigid physical bodies. See the

Physical bodies and hinges section for more discussion on physical bodies.

Subclassed by Karana::Dynamics::PhysicalModalBody

Public Functions

PhysicalBody(std::string_view name, kc::ks_ptr<Multibody> mb)#

PhysicalBody constructor. The constructor is not meant to be called directly. Please use the create(…) method instead to create an instance.

Parameters:
virtual ~PhysicalBody()#

PhysicalBody destructor.

inline virtual std::string_view typeString() const noexcept override#

Returns the type string of Base.

Returns:

The type string.

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

Return the object’s id.

Returns:

The object’s id.

inline virtual std::string_view name() const override#

Needed to have a definition of BodyBase::name() method

virtual bool isRootBody() const override#

Return true is this PhysicalBody is the Multibody’s virtual root body.

Returns:

true if this is the virtual root body

virtual void setParams(const PhysicalBodyParams &params)#

Set the PhysicalBody parameters.

Parameters:

params – the parameters to set

void setSpatialInertia(const km::SpatialInertia &sp_i, const kc::ks_ptr<kf::Frame> &ref_frame = nullptr)#

Set the Karana::Math::SpatialInertia spatial inertia for the body in the specified reference Karana::Frame::Frame frame.

If no frame is specified, then the spatial inertia is assumed to be represented in and about the body frame

Parameters:
  • sp_i – the input spatial inertia

  • ref_frame – the reference frame for the input spatial inertia

const km::SpatialInertia &getSpatialInertia() const#

Return the body’s Karana::Math::SpatialInertia spatial inertia about the body frame.

Returns:

the spatial inertia

virtual void setBodyToJointTransform(const km::HomTran &T)#

Set the the body frame to body HingePnode pnode transform.

For a deformable body, this is the transform value in the undeformed configuration. This method should only be used for body pnodes. The Node::setBodyToNodeTransform() method should be used for all other nodes.

Parameters:

T – The input transform

virtual km::HomTran getBodyToJointTransform() const#

Return the body frame to body HingePnode pnode transform.

For a deformable body, this is the transform value in the undeformed configuration.

Returns:

the transform

const km::SpatialVector bodyObservedSpatialAccel() const#

Return the body frame observed spatial acceleration for the body with respect to the Newtonian frame.

Return the body frame observed spatial acceleration for the body with respect to inertial frame about and in the body frame. The returned value is in the body frame. Note that this is NOT the newtonian_frame.frameToFrame(body).relSpaAccel() which is the Newtonian frame observed spatial acceleration!

Returns:

the spatial acceleration

km::SpatialVector externalSpatialForce(bool with_constraints) const#

Return the overall spatial force on the body at its reference frame and in the body frame.

This method will accumulate the external spatial forces from all the force nodes (including active contact nodes) on the body. If with_constraints is true, then constraint spatial forces from the constraint nodes will also be accumulated in the returned value.

Parameters:

with_constraints – set to true to include constraint node contributions

Returns:

the overall spatial force on the body, at the body reference frame in the body frame

void splitSubhinges()#

Split up the parent hinge’s subhinges into sequence of hinges with single subhinges.

The resulting system will have equivalent dynamics to the current system.

This method is a no-op if the parent hinge has a single subhinge.

void insertDummyParentBody()#

Add a mass less and locked parent body between the current parent.

The resulting system will have equivalent dynamics to the current system.

This method is a no-op if the parent hinge has a single subhinge.

void reattach(PhysicalBody &new_parent, HingeBase::HingeType hinge_type = HingeBase::HingeType::FULL6DOF)#

Reattach the body to the specified parent PhysicalBody.

Reattach this PhysicalBody to the new parent PhysicalBody body via a hinge of the specified type. If the new hinge type is a 6-dof hinge, then the inertial pose, spatial velocity and spatial acceleration of the body are preserved after reattachment. For a non 6-dof hinge, no such pose preservation is done, and follow up steps to set the hinge parameters (e.g., axes) and initial state will be required.

See Multibody configuration changes section for information.

Parameters:
  • new_parent – The new parent body

  • hinge_type – The new hinge type

void detach()#

Reattach the body to the virtual root via a 6 dof hinge.

Reattach the body to the virtual root via a 6 dof hinge (while preserving the inertial pose, spatial velocity and spatial acceleration. See Multibody configuration changes section for information.

kc::ks_ptr<ks::ProxyScenePart> getScenePart(std::string_view nm) const#

Return the ScenePart with the specified name.

See ProxyScene section for proxy scene related discussion.

Returns:

The scene part with machine name, or nullptr if none found

const std::vector<kc::ks_ptr<ks::ProxyScenePart>> &getSceneParts() const#

Return the list of SceneParts created from Karana::Scene::ScenePartSpec values.

See ProxyScene section for proxy scene related discussion.

Returns:

The list of scene parts

const std::vector<ks::ScenePartSpec> &getScenePartSpecs() const#

Return the list of ScenePartSpecs.

See ProxyScene section for proxy scene related discussion.

Returns:

The list of scene part specs

kc::ks_ptr<LoopConstraintHinge> toLoopConstraint()#

Replace the parent hinge with an equivalent loop constraint.

The method removes the hinge between a parent/child body pair, and replaces it with an equivalent cut-joint LoopConstraintHinge between the bodies. The child body is attached to the virtual root via a 6 dof hinge. The parameters are set so that there is no change in the pose, velocities etc, and the new system is kinematically and dynamically equivalent - albeit one with redundant coordinates and constraints. See Multibody representations sec for discussion about the duality between PhysicalHinge and LoopConstraintHinge classes in Multibody representations.

Returns:

the new LoopConstraint instance

void shiftBaseBody()#

Convert this body into a floating base body.

Given a body with parent PhysicalBody body that is a 6-dof floating base body, reverse the connecting parent hinge to make this body into a 6-dof floating base body. This operation maintains the required tree structure for the multibody system. The new hinge has the same subhinges as the original hinge - but in reversed order. The subhinge parameters preserve the original params while taking into account the orientation reversals. The end result is that the poses of the bodies remains unaffected. See the

Multibody configuration changes for more on Multibody configuration changes.

const kc::ks_ptr<HingePnode> &pnode() const#

Return the pnode for the parent hinge.

See Connecting bodies via hinges section for more on body pnodes and onodes.

Returns:

the HingePnode instance

const kc::ks_ptr<HingeOnode> &onode() const#

Return the onode for the parent hinge.

See Connecting bodies via hinges section for more on body pnodes and onodes.

Returns:

the HingeOnode instance

virtual const kc::ks_ptr<PhysicalBody> &physicalParentBody() const override#

Return the PhysicalBody inboard parent body for the body.

For a PhysicalBody this is simply the inboard body connected to it via a PhysicalHinge. For a CompoundBody, this is the single PhysicalBody to which the base pnodes in the CompoundBody are connected to.

Returns:

the parent PhysicalBody body instance

virtual kc::ks_ptr<HingeBase> parentHinge() const override#

Return the parent hinge for the body.

For a PhysicalBody, parent hinge is a PhysicalHinge, while for a CompoundBody the parent hinge is a CompoundHinge

Returns:

The parent HingeBase instance

inline kc::ks_ptr<kf::OrientedChainedFrameToFrame> newtonianToBodyFrameToFrame() const#

Return the Karana::Frame::FrameToFrame from the Newtonian frame to the body frame.

Returns:

the Karana::Frame::FrameToFrame instance

const std::vector<kc::ks_ptr<Node>> &nodeList() const#

Get a list of the nodes on this body. This does not include pnodes or onodes.

Returns:

A list of nodes on the body, not including pnodes or onodes.

const std::vector<kc::ks_ptr<ConstraintNode>> &constraintNodeList() const#

Get a list of the constraint nodes on this body.

Returns:

A list of constraint nodes on the body

kc::ks_ptr<Node> getNode(std::string_view node_name)#

Retrieve the node with the specified name.

Return nullptr if there is no node with the specified name.

Parameters:

name – the node’s name

Returns:

The node on the body with the specified name.

kc::ks_ptr<ConstraintNode> getConstraintNode(std::string_view node_name)#

Retrieve the constraint node with the specified name.

Return nullptr if there is no constraint node with the specified name.

Parameters:

name – the node’s name

Returns:

The constraint node on the body with the specified name.

void setGravAccel(const km::Vec3 &g, const kc::ks_ptr<kf::Frame> &ref_frame = nullptr)#

Set the gravitational linear acceleration for the body represented in the specified frame.

If no frame is specified, then the linear acceleration is assumed to be represented in the body frame

Parameters:
  • g – the gravitational linear acceleration vector

  • ref_frame – the representation frame for the input gravity accel vector

void accumGravAccel(const km::Vec3 &g, const kc::ks_ptr<kf::Frame> &ref_frame = nullptr)#

Accumulate the gravitational linear acceleration for the body represented in the specified frame.

If no frame is specified, then the linear acceleration is assumed to be represented in the body frame

Parameters:
  • g – the gravitational linear acceleration vector

  • ref_frame – the representation frame for the input gravity accel vector

inline const km::Vec3 &getGravAccel()#

Return the gravity linear acceleration at the body in the body frame.

Returns:

the gravity acceleration vector

void setGravityGradient(const km::Vec3 &grav_gradient, const kc::ks_ptr<kf::Frame> &ref_frame = nullptr)#

Set the gravity gradient moment vector for the body represented in the specified frame.

If no frame is specified, then the moment is assumed to be represented in the body frame

Parameters:
  • grav_gradient – the gravity gradient vector

  • ref_frame – the representation frame for the input gravity accel vector

void accumGravityGradient(const km::Vec3 &grav_gradient, const kc::ks_ptr<kf::Frame> &ref_frame = nullptr)#

Accumulate the gravity gradient moment vector for the body represented in the specified frame.

If no frame is specified, then the moment is assumed to be represented in the body frame

Parameters:
  • grav_gradient – the gravity gradient vector

  • ref_frame – the representation frame for the input gravity accel vector

virtual km::Mat66 getNodeUpsilonFromPnode(const Node &nd)#

Return the 6x6 OSCM Upsilon matrix for a body node using the pnode Upsilon.

This method is used for the scatter step for onode Upsilon computation.

Parameters:

nd – the body node

Returns:

the OSCM Upsilon matrix

virtual km::Mat66 getNodeUpsilonFromBody(const Node &node)#

Return the 6x6 OSCM Upsilon matrix for a body node using the body’s Upsilon.

Their method is used to compute the child onode UpsilonPlus value after crossing the modal dofs.

Parameters:

node – the body node

Returns:

the OSCM Upsilon matrix

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

Return a formatted string containing information about this object.

Parameters:
  • prefix – String prefix to use for formatting.

  • options – Dump options (if null, defaults will be used).

Returns:

A string representation of the object.

virtual bool isFinalized() const override#

Checks is the params for the object have been initialized.

Returns:

True if the params have set up.

virtual double kineticEnergy() const#

Return the kinetic energy contribution for the body.

Returns:

the kinetic energy value

virtual km::SpatialVector spatialMomentum() const#

Return the spatial momentum contribution for the body.

Returns:

the spatial momentum vector

virtual km::Mat getUpsilonMatrix() override#

Compute the body frame referenced OSCM Upsilon matrix for the body.

This method is specialized by flex bodies as well. For a rigid body the value is a 6x6 matrix, but is larger by the number of modes for a deformable body.

Returns:

the OSCM Upsilon matrix

virtual kc::ks_ptr<kf::FrameToFrame> 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

void addScenePartSpec(const ks::ScenePartSpec &scene_part)#

Add a ScenePart description to the body to be realized whenever a ProxyScene is available.

The new scene part spec’s name must not conflict with the name of an existing scene part spec of scene part for the body.

Parameters:

scene_part – The ScenePart description

void discardAllNodes()#

Discard all nodes in the _nodes_usage_map.

Public Static Functions

static kc::ks_ptr<PhysicalBody> create(std::string_view name, kc::ks_ptr<Multibody> mb)#

Creates a new PhysicalBody with the given name.

Parameters:
  • name – The name of the frame to create.

  • mb – The Multibody instance.

Returns:

The created body.

static std::vector<kc::ks_ptr<PhysicalBody>> addSerialChain(std::string_view name, size_t nbodies, PhysicalBody &root, HingeBase::HingeType htype = HingeBase::HingeType::PIN, PhysicalBodyParams *params = nullptr)#

Add a serial chain of rigid PhysicalBody instances to the multibody system.

Add a serial chain of rigid 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. See Procedural creation section for more discussion on this topic.

Parameters:
  • name – prefix string to use for the new body names

  • nbodies – number of bodies

  • root – the parent body to attach the chain to

  • htype – the hinge type

  • params – the body params for each body

Returns:

the list of new rigid bodies

static std::vector<kc::ks_ptr<PhysicalBody>> addTree(std::string_view name, size_t branch_length, size_t nbranches, size_t depth, PhysicalBody &root, HingeBase::HingeType htype = HingeBase::HingeType::PIN, PhysicalBodyParams *params = nullptr)#

Add a sub-tree of rigid PhysicalBody instances to the multibody system.

Add a sub-tree of rigid 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. See the

Procedural creation section for more discussion on this topic.

Parameters:
  • name – prefix string to use for the new body names

  • branch_length – the number of bodies in a branch

  • nbranches – the number of children branches

  • depth – the number of branching levels to create

  • root – the parent body to attach the chain to

  • htype – the hinge type

  • params – the body params for each body

Returns:

the list of new rigid bodies

Protected Functions

inline GatherSweepFlags &_gatherSweepFlags()#

Get the struct with gather sweep flags

void _trackUsageNode(const kc::ks_ptr<Node>&)#
virtual void _moveNode(const kc::ks_ptr<Node> &node, const km::HomTran &T)#

Move the node to the location given by the transform T relative to the body frame.

This method should not be used to set a normal nodes value. It is intended to be used for contact force nodes. Normal user-defined force nodes, constraint nodes, etc. should have their values set on the node directly.

This moves the node so its transform is T relative to the body frame. Derived classes can specialize this method to set other values, such as those given in the deformation provider.

Parameters:
  • node – The node to move.

  • T – The transform of the node relative to the body frame.

kc::ks_ptr<PhysicalBody> _asSharedPtr()#
void _realizeScenePart(const ks::ScenePartSpec &scene_part)#

Create a ProxyScenePart from the ScenePartSpec and add it to the body.

Parameters:

scene_part – The ScenePartSpec to add.

virtual void _detachNode(kc::ks_ptr<Node> &nd)#

detach the node from the parent body

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

Discard the provided PhysicalBody.

Parameters:

base – - Base pointer to the PhysicalBody to discard.

virtual void _setupNode(Node &node, bool force_node)#

Helper method to create a node. This method is specialized by bodies that are deformable

void _processScenePartSpecs()#

Create the scene parts for the body from its list of ScenePartSpecs

virtual km::Mat66 _getPnodeMassMatrix() const#

For a rigid body, return the body spatial inertia mass properties transformed rigidly to the pnode as a 6x6 matrix. For a flex body, return the (nU+6) square body level mass matrix transformed to the pnode.

virtual void _getPnodeCRBInertiaMatrix(km::Mat &R)#

Propagate the child onode CRB inertia contributions to compute the CRB inertia for this body transformed to the pnode. For a rigid body, all of this is done with spatial inertias. For a flex body, we have to work with the (nU+6) size local body mass properties while taking into account the onode deformations.

virtual void _setBodyToNodeTransform(Node &node, const km::HomTran &t)#

Get/set the 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.

virtual km::HomTran _getBodyToNodeTransform(const Node &node) const#
virtual void _computeGyroscopicForce(km::SpatialVector&) const#

Data cache callback for updating the body’s gyroscopic spatial force. This gyroscopic term corresponds to rigid body equations of motion where the body frame derivatives are used for generalized accel, i.e. the accel corresponds to pframeObservedRelSpAccel(). The returned spatial force is about the and at the pnode frame.

virtual km::Mat66 _pnodeToChildNodeTransform(const Node &node)#

Return 6*6 matrix that is the pnode to child node part of the psi matrix to the child node. While for a rigid body this is simply phi(pnode, onode), for a flex body it includes the modal psi part in crossing modal dofs when going between the pnode and onode of the flex body, This method is used when computing the cross ATBI matrix between parent/child bodies when computing cross-Upsilon data. Return 6*6 matrix that is the pnode to child node psi matrix. While for a rigid body this is simply phi(pnode,

onode), for a flex body it includes the modal psi part in crossing modal dofs when going between the pnode and onode of the flex body. This method

DOES depend on ATBI quantities.

virtual km::Mat _bodyToChildNodeTransform(const Node &node, const kf::Frame &from_frame) const#

Return matrix that is the from frame to a child body node phi matrix. While for a rigid body this is simply phi(body,

node), for a flex body it includes the deformation contribution for the body’s node (this is the ‘A’ matrix). This method does

NOT depend on ATBI quantities.

virtual km::Mat _pnodeToBodyPsi() const#

Return matrix that is the pnode to body frame contribution to the psi matrix. While for a rigid body this is simply phi(pnode, body), for a flex body it includes the modal psi part in crossing modal dofs when going between the pnode and body frame for the flex body, This method is used when computing the cross ATBI matrix between parent/child bodies for computing cross-Upsilon data.This method DOES depend on ATBI quantities.

void _clearExternals()#

Zero out the external spatial forces, gravity accel and gravity gradient values for the body.

virtual kc::ks_ptr<HingePnode> _createPnode(bool floating_frame)#

Methods to create and discard nodes

virtual kc::ks_ptr<HingeOnode> _createOnode(std::string_view name)#
virtual void _discardHingePnode()#
virtual void _discardHingeOnode(kc::ks_ptr<HingeOnode> &onode)#
virtual void _registerChildOnode(kc::ks_ptr<HingeOnode> node)#
virtual void _unregisterChildOnode(kc::ks_ptr<HingeOnode> node)#
virtual km::SpatialVector _getPnodeATBIFilterZ()#
virtual km::Mat66 _getPnodeATBIMatricesP()#
virtual km::SpatialVector _getOnodeATBISmootherAlphaPlus(const HingeOnode &ond)#
virtual void _processPnodeATBISmootherVectors()#
virtual km::Mat66 _processPnodeUpsilonMatrices()#
virtual km::SpatialVector _getPnodeInvDynForcesF()#
virtual void _setupChildBodyCacheDependencies(const BodyBase &child_body) override#

Set up cache dependencies with a child body.

Parameters:

child_body – the child body

virtual void _setupChildPhysicalBodyCacheDependencies(const PhysicalBody &child_body, bool skip_scatter) override#

Set up cache dependencies with a PhysicalBody child body.

Parameters:
  • child_body – the PhysicalBody child body

  • skip_scatter – if true, skip dependencies for the scatter phase

virtual void _setupChildCompoundBodyCacheDependencies(const CompoundBody &child_body) override#

Set up cache dependencies with a CompoundBody child body.

Parameters:

child_body – the CompoundBody child body

virtual void _setupBaseBodyCacheDependencies() override#

Set up cache dependencies for a base body.

virtual void _teardownChildBodyCacheDependencies(const BodyBase &child_body) override#

Tear down cache dependencies with a child body.

Parameters:

child_body – the child body

virtual void _teardownChildPhysicalBodyCacheDependencies(const PhysicalBody &child_body, bool skip_scatter) override#

Tear down cache dependencies with a PhysicalBody child body.

Parameters:
  • child_body – the PhysicalBody child body

  • skip_scatter – if true, skip dependencies for the scatter phase

virtual void _teardownChildCompoundBodyCacheDependencies(const CompoundBody &child_body) override#

Tear down cache dependencies with a CompoundBody child body.

Parameters:

child_body – the CompoundBody child body

virtual void _teardownBaseBodyCacheDependencies() override#

Tear down cache dependencies for a base body.

Protected Attributes

km::SpatialInertia _spI#

the body’s spatial inertia at - and in - the body frame

km::Vec3 _grav_accel_body_frame#

the cached gravitational linear accel value for the body in the body frame

km::Vec3 _grav_gradient_body_frame#

the cached gravity gradient moment value for the body in the body frame

kc::ks_ptr<HingePnode> _parent_pnode = nullptr#

attachment pnode

kc::ks_ptr<kf::OrientedChainedFrameToFrame> _newtonian2body_f2f = nullptr#
GatherSweepFlags _gather_sweep_flags#
std::vector<ks::ScenePartSpec> _scene_part_specs#

list of scene_part_specs for the body

std::vector<kc::ks_ptr<ks::ProxyScenePart>> _scene_part_spec_parts#

list of scene parts created for the scene_part_specs for the body

kc::ks_ptr<kc::DataCache<km::SpatialInertia>> _spI_cache = nullptr#
kc::ks_ptr<kc::DataCache<km::Vec3>> _grav_accel_cache = nullptr#
kc::ks_ptr<kc::DataCache<km::SpatialVector>> _gyroscopic_force_cache = nullptr#
kc::RegistryList<HingeOnode> _child_onodes_list#

List of child body attachment onodes. For a physical body, this is the list of onodes for all the physical children bodies.

kc::RegistryList<Node> _nodes_list#

track nodes on the body

kc::RegistryList<Node> _external_force_nodes_list#

List of nodes that can apply forces.

kc::RegistryList<Node> _contact_force_nodes_list#

for the current dynamics calculation.

List of nodes that can apply forces

size_t _active_contact_force_node_index = 0#

In the _contact_force_nodes_list, values to the left of this (from begin() to begin() + index) are inactive and values to the right are active. Another way to say this is this index points to a node that is active, and it is the first active node in the list. Everything at this index and later is active.

kc::RegistryList<ConstraintNode> _constraint_nodes_list#

List of constraint nodes.

struct DumpOptions : public Karana::Frame::Frame::DumpOptions#

Options struct for dumpString.

Public Functions

inline DumpOptions &operator=(const DumpOptions &p)#

Assignment operator.

Parameters:

p – The DumpOptions to copy values from.

Returns:

A reference to the newly assigned DumpOptions.

struct GatherSweepFlags#

Struct of flags that can be used to turn on and off the inclusion of various contributions in the ATBI filter gather recursions. Handy for TA correction phase sweeps, and computing mass matrix etc.

Public Members

bool gravity = true#

flag that can be used to turn on and off the inclusion of gravity contributions in the ATBI filter gather recursions. Handy for TA correction phase sweeps

bool external_forces = true#

flag that can be used to turn on and off the inclusion of external force contributions in the gather recursions. Handy for TA correction phase sweeps

bool constraint_forces = true#

flag that can be used to turn on and off the inclusion of constraint force contributions in the gather recursions. Constraint nodes are however always on since we use them for the cut-joint hinge torque contributions as well

bool elastic_forces = true#

flag that can be used to turn on and off the inclusion of deformation elastic force contributions in the flex dynamics gather recursions. Handy to turn off for mass matrix and TA algorithm computations.

bool modal_gen_forces = false#

flag that can be used to turn on and off the inclusion of deformation generalized modal force contributions in the flex dynamics gather recursions. Handy to turn on for fwd dynamics based mass matrix inverse algorithm computations.

struct InvDynVectors#

Struct for inverse dynamics computations.

Public Members

km::SpatialVector f#

the inter-body spatial interaction force for the hinge at its onode and represented in the onode frame.