Class CoordBase#
Defined in File CoordBase.h
Nested Relationships#
Nested Types#
Inheritance Relationships#
Derived Types#
public Karana::Dynamics::BodyBase(Class BodyBase)public Karana::Dynamics::SubhingeBase(Class SubhingeBase)
Class Documentation#
-
class CoordBase#
Represents the base class for Q, U etc coordinate data providers.
This class is the base class for subhinges, compound subhinges, and bodies that can contribute motion degrees of freedom to the system. These degrees of freedom are associated with coordinates designated Q, U etc.
See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.
Subclassed by Karana::Dynamics::BodyBase, Karana::Dynamics::SubhingeBase
Public Functions
-
CoordBase(std::string_view nm, kc::id_t id)#
Constructs a CoordBase.
- Parameters:
nm – instance name
id – instance id
-
virtual ~CoordBase()#
Destructor.
-
std::string dumpString(std::string_view prefix, const kc::Base::DumpOptions *options) const#
Return string with information about the object.
- Parameters:
prefix – the prefix to apply to each output line
options – options to control dump output
- Returns:
String with informational content.
-
inline virtual std::string_view name() const#
Return the object’s name.
- Returns:
The object’s string name.
-
inline virtual const kc::id_t &id() const#
Return the object’s id.
- Returns:
The object’s id.
-
virtual std::string_view typeString(bool brief = true) const noexcept = 0#
Returns the type string of the BodyBase.
- Parameters:
brief – if true, return the short form of the class type name, else the full type name
- Returns:
The type string.
-
virtual bool isReady() const#
Check whether parameters have been set.
- Returns:
True if the parameters have been set.
-
virtual km::Mat getATBIMatPsi() const = 0#
Get the ATBI psi matrix value.
- Returns:
The ATBI psi matrix value for this subhinge.
-
virtual km::Mat getATBID() const = 0#
Get the ATBI D matrix value.
- Returns:
The ATBI D matrix value for this subhinge.
-
virtual km::Mat getATBIDinv() const = 0#
Get the ATBI D inverse matrix value.
- Returns:
The ATBI D inverse matrix value for this subhinge.
-
virtual km::Mat getATBIG() const = 0#
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.
- Returns:
The ATBI G matrix value for this subhinge.
-
virtual km::Mat getATBITauper() const = 0#
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.
- Returns:
The ATBI tauper matrix value for this subhinge.
-
inline virtual km::Mat pframeCoordMapMatrix() const#
The coord map matrix with the lhs in the pframe. 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 (6,nU) size matrix, while for a flex body its size is (nU+6, nU).
- Returns:
The pframe referenced subhinge coordinate map matrix value for this subhinge.
-
inline virtual const km::Mat atbiCoordMapMatrix() const#
Return the coordinate map matrix to be used for ATBI computations.
- Returns:
coordinate map matrix
-
virtual km::Mat getUpsilonMatrix() = 0#
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.
- Returns:
The ATBI Upsilon matrix value for this subhinge.
-
virtual void setQ(const Eigen::Ref<const km::Vec> &val)#
Set the global (chart) Q coordinates.
Get/set methods for buffers for the generalized coordinates for this coordinate provider.
See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.
- Parameters:
val – Array of values.
-
virtual void setQ(double fill_value)#
Set the global (chart) 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#
Return the global (chart) 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)#
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)#
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#
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)#
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)#
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#
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)#
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)#
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#
Return the Udot acceleration coordinates.
See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.
- Returns:
Array of values.
-
inline virtual const km::Vec &getQdot() const#
Return the Qdot rate coordinates.
See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.
- Returns:
Array of values.
-
inline size_t nQ() const#
The number of generalized coords for the CoordBase.
See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.
- Returns:
the number of generalized coordinates
-
inline size_t nU() const#
The number of velocity coords for the CoordBase_T.
See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.
- Returns:
the number of velocity coordinates
Protected Functions
-
virtual kc::ks_ptr<kf::FrameToFrame> f2f() const = 0#
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::optional<bool> isOriented(const kf::FrameToFrame &f2f) const#
Checks whether a CoordBase edge is oriented along the Karana::Frame::FrameToFrame path.
- Parameters:
f2f – The f2f.
- Returns:
std::nullopt if the coord edge is not on the f2f path std::optional(true) if the coord edge is oriented along the f2f path. std::optional(false) if the coord edge is oriented opposed to the f2f path.
-
virtual km::Mat _jacobian(const kf::FrameToFrame &f2f) const = 0#
Return the Jacobian matrix for the target Karana::Frame::Frame.
For this coordinates provider, return the 6xnU Jacobian matrix for the target frame that maps generalized velocities U to the target Karana::Frame::Frame’s spatial velocity (and represented in the target Karana::Frame::Frame). The Jacobian is useful for velocity space kinematics, computing force reflection and for mass matrix and operational space inertia related computations.
See Coordinate Frames section for more information on frames, and Jacobians section for more on Jacobians.
Note that this, and the methods following it do not check whether the dependency of the target frame’s pose on the coordinates, and assume instead that the target frame is rigid attached to the oframe.
- Parameters:
f2f – the f2f whose pframe is the target frame for the Jacobian
- Returns:
the Jacobian matrix
-
virtual km::Mat _jacobianDot(const kf::FrameToFrame &f2f) const = 0#
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.
See Coordinate Frames section for more information on frames, and Jacobians section for more on Jacobians.
See also
jacobian()
- Parameters:
f2f – the f2f whose pframe is the target frame for the Jacobian
- Returns:
the Jacobian matrix time derivative
-
km::Mat _jacobianNumDiff(const kf::FrameToFrame &f2f)#
Return the relative Jacobian matrix for a Karana::Frame::FrameToFrame using numerical differencing.
This method uses numerical differencing to compute the 6xnU Jacobian for a Karana::Frame::FrameToFrame’s pframe with respect to its oframe. The primary purpose of this method is to cross-validate the analytical jacobian computation, where the f2f pframe is the target frame.
See Coordinate Frames section for more information on frames, and Jacobians section for more on Jacobians.
- Parameters:
f2f – the Karana::Frame::FrameToFrame defining the relative Jacobian from/to frames
- Returns:
the Jacobian matrix
-
km::Mat _jacobianDotNumDiff(const kf::FrameToFrame &f2f, kc::ks_ptr<Multibody> mb)#
Return the relative JacobianDot matrix for a Karana::Frame::FrameToFrame using numerical differencing.
This method uses numerical differencing to compute the 6xnU JacobianDot for a Karana::Frame::FrameToFrame’s pframe with respect to its oframe. The primary purpose of this method is to cross-validate the analytical jacobianDot computation, where the f2f pframe is the target frame.
The multibody argument is required when analytical is false, since a total time derivative of the Jacobian needs to be computed, and this requires that all the multibody coordinates be perturbed (and not just the ones for the CoordBase).
See Coordinate Frames section for more information on frames, and Jacobians section for more on Jacobians.
- Parameters:
f2f – the Karana::Frame::FrameToFrame defining the relative Jacobian from/to frames
mb – the multibody system
- Returns:
the JacobianDot matrix
-
virtual km::Mat _poseGradient(const kf::FrameToFrame &f_to_f) const#
Return the pose gradient matrix for a Karana::Frame::FrameToFrame.
Return the 6xnU gradient matrix for the pose of a Karana::Frame::FrameToFrame’s pframe with respect to its oframe with respect to the generalized coordinates Q using analytical methods. The relative orientation is expressed using RotationVectors for a minimal coordinates representation. Though closely related to the Jacobian, the gradient matrix is a coordinate space mapping, while the Jacobian is a velocity space mapping. The gradient matrix is handy for inverse kinematics computations.
See Coordinate Frames section for more information on frames, and Jacobians section for more on Jacobians.
- Parameters:
f_to_f – the FrameToFrame defining the relative from/to frames
- Returns:
the gradient matrix
-
km::Mat _poseGradientNumDiff(const kf::FrameToFrame &f2f)#
Return the pose gradient matrix for a Karana::Frame::FrameToFrame using numerical differencing.
This method uses numerical differencing to compute the 6xnU pose gradient of a Karana::Frame::FrameToFrame’s pframe with respect to its oframe using numerical differencing. The primary purpose of this method is to cross-validate the analytical pose gradient computation.
See Coordinate Frames section for more information on frames, and Jacobians section for more on Jacobians.
- Parameters:
f2f – the FrameToFrame defining the relative Jacobian from/to frames
- Returns:
the pose gradient matrix
-
inline const ATBIMatrices &_atbiMatrices() const#
Return the ATBI matrices.
- Returns:
the ATBIMatrices struct
-
inline const ATBIFilterVectors &_atbiFilterVectors() const#
Return the ATBI filter vectors.
- Returns:
the ATBIFilterVectors struct
-
virtual km::Mat _oframe2pframePsi() const = 0#
Return the oframe to pframe Psi() matrix for this CoordBase.
For
a flex body this is a 6x(nU+6) psi matrix, the lhs is at the pnode, and the rhs at the body frame.
For a subhinge this is a 6x6 psi matrix, the lhs/rhs are the subhinge’s oframe and pframe pair.
a compound subhinge this is the 6x(nbodies*(6+nU)) psi matrix, the lhs is at the physical parent, and the rhs at the embedded bodies.
- Returns:
the Psi() matrix
-
virtual km::Mat _oframe2pframePhi() const = 0#
Return the oframe to pframe Phi() matrix for this CoordBase.
For
a flex body this is a 6x(nU+6) phi matrix, the lhs is at the pnode, and the rhs at the body frame.
a subhinge this is a 6x6 phi matrix, the lhs/rhs are the subhinge’s oframe and pframe pair.
a compound subhinge this is the 6x(nbodies*(6+nU)) E_Phi_G matrix, the lhs is at the physical parent, and the rhs at the embedded bodies.
- Returns:
the Phi() matrix
-
virtual km::Mat _pframe2otherPhi(const kf::Frame &other) const = 0#
Return the pframe to other frame Phi() matrix for this CoordBase.
For
a flex body this is a (nU+6)x6 phi matrix - the lhs is at the body frame, and the rhs at the other frame.
a subhinge this is a 6x6 matrix - the lhs is the pframe, and the rhs at the other frame.
a compound subhinge this is the (nbodies*(6+nU))x6 matrix, the lhs is at the embedded body frames, and the rhs at the other frame.
- Parameters:
other – the other to frame
- Returns:
the Phi() matrix
-
virtual void _localChartSetQ(const Eigen::Ref<const km::Vec> &val)#
Set the local chart Q coordinates.
See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.
- Parameters:
val – Array of values.
-
virtual const km::Vec &_localChartGetQ() const#
Return the local chart Q coordinates - without sanitizing coordinates.
See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.
- Returns:
Array of values.
Protected Attributes
-
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::ks_ptr<kc::DataCache<km::Vec>> _cache_Q = nullptr#
the data cache for the Q coordinates
-
kc::ks_ptr<kc::DataCache<km::Vec>> _cache_U = nullptr#
the data cache for the U coordinates
-
kc::ks_ptr<kc::DataCache<km::Vec>> _cache_Udot = nullptr#
the data cache for the Udot coordinates
-
kc::ks_ptr<kc::DataCache<km::Vec>> _cache_T = nullptr#
the data cache for the T coordinates
-
kc::ks_ptr<kc::DataCache<km::Vec>> _cache_Qdot = nullptr#
the data cache for the Qdot coordinates
-
kc::ks_ptr<ATBIMatrices> _atbi_matrices = nullptr#
member for the ATBI matrices for this CoordBase
-
kc::ks_ptr<ATBIFilterVectors> _atbi_filter_vectors = nullptr#
member for the ATBI filter vectors for this CoordBase
-
km::Vec _buf_Q#
gen coords buffer
Buffers for the generalized coordinates for this physical subhinge. We do these here because the coordinate buffers for compound subhinges come from the CoordData associated with the embedded bodies. Additional such buffers will be available within the body class for for deformable bodies.
We use these buffers to allow the user to directly set these values using the get/set methods. The actual data is managed by the associated caches
-
km::Vec _buf_U#
gen velocities buffer
-
km::Vec _buf_Udot#
gen accels buffer
-
km::Vec _buf_T#
gen forces buffer
-
struct ATBIMatrices#
Overall struct for ATBI dynamics matrix quantities for a coordinates provider (subhinge or deformable bodies).
Subclassed by Karana::Dynamics::CompoundSubhinge::ATBIMatrices, Karana::Dynamics::PhysicalModalBody::ATBIMatrices, Karana::Dynamics::PhysicalSubhinge_T< NQ, NU >::ATBIMatrices
Public Functions
-
ATBIMatrices() = default#
Constructor.
-
ATBIMatrices(const ATBIMatrices&) = default#
Copy constructor.
-
inline virtual ~ATBIMatrices()#
-
ATBIMatrices() = default#
-
struct ATBIFilterVectors#
Overall struct for ATBI dynamics vector quantities for a coordinates provider (subhinge or deformable bodies).
Subclassed by Karana::Dynamics::CompoundSubhinge::ATBIFilterVectors, Karana::Dynamics::PhysicalModalBody::ATBIFilterVectors, Karana::Dynamics::PhysicalSubhinge_T< NQ, NU >::ATBIFilterVectors
Public Functions
-
ATBIFilterVectors() = default#
Constructor.
-
ATBIFilterVectors(const ATBIFilterVectors&) = default#
Copy constructor.
-
inline virtual ~ATBIFilterVectors()#
-
ATBIFilterVectors() = default#
-
CoordBase(std::string_view nm, kc::id_t id)#