Class Multibody#
Defined in File Multibody.h
Inheritance Relationships#
Base Type#
public Karana::Dynamics::SubGraph(Class SubGraph)
Class Documentation#
-
class Multibody : public Karana::Dynamics::SubGraph#
Represents the multibody system class with physical bodies.
See the Physical bodies and hinges and Creating a tree multibody system sections for more discussion related to the Multibody class.
This is the class for containing the multibody system definition
Public Functions
-
Multibody(std::string_view name, kc::ks_ptr<kf::FrameContainer> fc)#
Constructs a Multibody.
- Parameters:
name – The name for the new Multibody instance
fc – The Karana::Frame::FrameContainer to use
-
void toUrdf(const std::filesystem::path &filename)#
This C++-only function will create a URDF file from a Multibody. This creates a Python interpreter under the hood and utilizes Python functions to do so. If creating from Python, just use
MultibodyDSdirectly. See the.Importing model data files section for more information.
- Parameters:
filename – - The name of the URDF file to create.
-
void toFullyAugmentedModel()#
Convert all PhysicalHinges into LoopConstraintCutJoints to create a fully augmented (FA) model.
The FA model consists of independent physical bodies, where the couple hinges are replaced with equivalent loop constraints. The FA model is also referred to as the absolute coordinates model. The main purpose of this method is to create FA models to compare and benchmark performance of absolute coordinate dynamics with the minimal coordinate methods. This method introduces constraints, and hence the TA algorithm must be used for dynamics computations for the FA model. See Multibody representations section for discussion of FA models.
-
virtual std::string dumpString(std::string_view prefix = "", const Karana::Core::Base::DumpOptions *options = nullptr) 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.
-
kc::ks_ptr<Node> getNodeAncestor(const kc::ks_ptr<kf::Frame> &frame) const#
Look up and return the closest Node ancestor for a Karana::Frame::Frame.
Return null if the Karana::Frame::Frame is not the descendant of a body Node. See Body nodes section for information on body nodes.
- Parameters:
frame – the input Karana::Frame::Frame
- Returns:
the ancestor Node for the Frame.
-
const kc::ks_ptr<kf::Frame> &getNewtonianFrame() const#
Return the Newtonian Karana::Frame::Frame.
See the Manual creation section for more information.
- Returns:
the Newtonian Frame instance
-
const kc::ks_ptr<kf::FrameContainer> &frameContainer() const#
Return the Karana::Frame::FrameContainer frame container for the multibody system.
See the Manual creation section for more information.
- Returns:
the Karana::Frame::FrameContainer instance
-
std::vector<kc::ks_ptr<BilateralConstraintBase>> constraints() const#
Return the list of existing constraint instances (enabled and disabled)
- Returns:
constraints list
-
kc::ks_ptr<BilateralConstraintBase> getConstraint(std::string_view name) const#
Look up a existing constraint by name (enabled or disabled) See.
Bilateral closure constraints section for more info on constraints.
- Parameters:
name – the constraint’s name
- Returns:
the CoordinateConstraint instance
-
void createStickParts(const StickPartsConfig &c = StickPartsConfig())#
Create stick parts for the multibody.
A Karana::Scene::ProxyScene scene must be registered with the Multibody first.
- Parameters:
c – Config that controls the look of the stick parts visualization.
-
void setScene(const kc::ks_ptr<ks::ProxyScene> &scene)#
Set the Karana::Scene::ProxyScene instance for the multibody system.
See ProxyScene section for more information on Karana::Scene::ProxyScene.
- Parameters:
scene – The scene instance
-
kc::ks_ptr<ks::ProxyScene> &getScene()#
Get the Karana::Scene::ProxyScene scene member for the multibody system See.
ProxyScene section for more information on Karana::Scene::ProxyScene.
- Returns:
The scene member
-
std::vector<kc::ks_ptr<PhysicalBody>> addPhysicalBodiesChain(const std::function<kc::ks_ptr<PhysicalBody>(std::string_view nm)> &create_body, std::string_view name, size_t nbodies, PhysicalBody &root, HingeBase::HingeType htype, const PhysicalBodyParams ¶ms)#
Add a serial chain of PhysicalBody instances to the multibody system.
Add a serial chain of 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. This helper method takes a body creation method as argument and can thus be used to create rigid PhysicalBody or deformable PhysicalModalBody bodies. See Procedural creation section for more discussion on procedural creation of multibody systems.
- Parameters:
create_body – Callback method to use to create a body
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 for the body hinges
params – body parameters
- Returns:
the list of new bodies
-
std::vector<kc::ks_ptr<PhysicalBody>> addPhysicalBodiesTree(const std::function<kc::ks_ptr<PhysicalBody>(std::string_view nm)> &create_body, std::string_view name, size_t branch_length, size_t nbranches, size_t depth, PhysicalBody &root, HingeBase::HingeType htype, const PhysicalBodyParams ¶ms)#
Add a sub-tree of PhysicalBody instances to the multibody system.
Add a sub-tree of 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. This helper method takes a body creation method as argument and can thus be used to create rigid or deformable bodies. See
Procedural creation section for more discussion on procedural creation of multibody systems.
- Parameters:
create_body – Callback method to use to create a body
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 for the body hinges
params – body parameters
- Returns:
the list of new bodies
Public Static Functions
-
static kc::ks_ptr<Multibody> create(std::string_view name, kc::ks_ptr<kf::FrameContainer> fc, kc::ks_ptr<kf::Frame> mbroot_frame = nullptr, kc::ks_ptr<kf::Frame> newtonian_frame = nullptr)#
Factory method to create a new Multibody instance.
The virtual root body is attached to the multibody root frame. If the multibody root frame is not specified, then the method uses the newtonian frame, and if that is unspecified as well, then the method uses the frame container’s root frame as the root frame.
- Parameters:
name – The name for the new Multibody instance
fc – The Karana::Frame::FrameContainer to use
mbroot_frame – The parent Karana::Frame::Frame for the virtual root body
newtonian_frame – The inertial Karana::Frame::FrameToFrame frame
- Returns:
a new Multibody instance
-
static kc::ks_ptr<Multibody> fromUrdf(const std::filesystem::path &filename, const kc::ks_ptr<kf::FrameContainer> &fc, const kc::ks_ptr<kf::Frame> &newtonian_frame = nullptr, const kc::ks_ptr<ks::ProxyScene> &scene = nullptr)#
This C++-only function will create and populate a Multibody from a URDF. This creates a Python interpreter under the hood and utilizes Python functions to do so. If creating from Python, just use
MultibodyDSdirectly. See.Importing model data files section for more information.
- Parameters:
filename – - The filename of the URDF to load from.
fc – - The FrameContainer to use for this Multibody.
newtonian_frame – - Pointer to a frame to use as the newtonian frame. If nullptr (the default), then the newtonian_frame will be the mbody virtual root.
scene – - Pointer to a ProxyScene. If nullptr, then no scene is present and geometry will not be loaded.
- Returns:
a new Multibody instance
Protected Functions
-
void _trackUsageCoordinateConstraint(kc::ks_ptr<CoordinateConstraint> c)#
Track the usage of the coordinate constraint.
- Parameters:
c – the coordinate constraint
-
void _trackUsagePhysicalBody(kc::ks_ptr<PhysicalBody> bd)#
Track the usage of a physical body.
- Parameters:
bd – the body
-
virtual void _makeHealthy() override#
Derived classes override this to define how to make themselves healthy.
-
virtual void _makeNotHealthy() override#
Tear down the internal topology _tree for the SubTree. While this method can only be called multiple times for the multibody SubTree to handle changes in configuration, it can only be called once for a lower level, nested SubTree.
-
virtual void _discardCmFrame() final override#
Discard the center of mass (CM) Karana::Frame::Frame frame.
Protected Attributes
-
kc::ks_ptr<kf::FrameContainer> _fc = nullptr#
Frame container.
-
kc::ks_ptr<kf::Frame> _newtonian_frame = nullptr#
The frame to use as the inertial, i.e. newtonian frame. By default this is the virtual root body, but can be set to a different frame.
-
kc::RegistryList<PhysicalBody> _physical_unsorted_bodies_list#
the raw unsorted list of physical bodies in the multibody system
-
kc::RegistryList<SubTree> _algorithmic_subtrees#
the forward/inverse etc methods that rely on gather/scatter recursions across the system. These recursions rely on data caches and their dependencies to be set up bespoke for the gather/scatter algorithms for the calling subtree. The following registry tracks the subtrees for whom data cache dependencies have been set up, Note that all of the algorithmic subtrees at any given time must have disjoint physical bodies.
-
kc::RegistryList<Node> _detached_nodes_list#
track nodes on the body
list of regular nodes that are not currently attached to a body
-
kc::RegistryList<ConstraintNode> _detached_constraint_nodes_list#
track nodes on the body
list of constraint nodes that are not currently attached to a body
-
kc::RegistryList<LoopConstraintBase> _existing_loop_constraints_list#
Master list of loop constraints that currently exist. The actual usage tracking is done at the f2f level as for hinges. This list is kept at the multibody level to keep track of the loop constraints and help with clean up at the end.
-
kc::ks_ptr<ks::ProxyScene> _scene = nullptr#
The scene for the multibody instance
-
kc::UsageTrackingMap<kc::id_t, CoordinateConstraint> _coordinate_constraint_usage_map#
usage map for coordinate constraints
-
kc::UsageTrackingMap<kc::id_t, LoopConstraintBase> _loop_constraint_base_usage_map#
usage map for loop constraints
-
Multibody(std::string_view name, kc::ks_ptr<kf::FrameContainer> fc)#