Class CoordBase#

Nested Relationships#

Nested Types#

Inheritance Relationships#

Derived Types#

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(const std::string &nm, kc::id_t id)#

Constructs a CoordBase_T.

virtual ~CoordBase()#

Destructor.

std::string dumpString(const std::string &prefix, const kc::Base::dumpOptions *options) const#

Return string with information about the object.

Returns:

String with informational content.

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

std::optional<bool> isOriented(const kf::Frame2Frame &f2f) const#

Checks whether a CoordBase edge is oriented along the Karana::Frame::Frame2Frame 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.

inline virtual const std::string &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 const std::string &typeString() const noexcept = 0#

Returns the type string of the BodyBase.

Returns:

The type string.

virtual km::Mat jacobian(const kf::Frame &target, bool oriented = true) 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. If oriented is false, the return value is negated.

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

Parameters:
  • Frame – the target frame

  • bool – the orientation of the coordinates provider

Returns:

the Jacobian matrix

virtual km::Mat jacobianDot(const kf::Frame &target, bool oriented = true) 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. If oriented is false, the return value is negated.

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

See also

jacobian()

Parameters:
  • Frame – the target frame

  • bool – the orientation of the coordinates provider

Returns:

the Jacobian matrix time derivative

virtual bool isFinalized() const#

Check whether parameters have been set.

Returns:

True if the parameters have been set.

virtual km::Mat getATBIMatPsi() const = 0#

Get the ATBI matrix psi value.

Returns:

The ATBI matrix psi value for this subhinge.

virtual km::Mat getATBID() const = 0#
virtual km::Mat getATBIDinv() const = 0#
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.

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.

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).

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.

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

Check whether parameters have been set.

Set the Q coordinates.

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

Returns:

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

Parameters:

val – Array of values.

virtual void setQ(double fill_value)#

Set the Q coordinates to a constant value.

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

Parameters:

fill_value – Fill value.

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

Return the Q coordinates.

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

Returns:

Array of values.

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

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 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

km::Mat jacobianNumDiff(const kf::Frame2Frame &f2f)#

Return the relative Jacobian matrix for a Karana::Frame::Frame2Frame using numerical differencing.

This method uses numerical differencing to compute the 6xnU Jacobian for a Karana::Frame::Frame2Frame’s pframe wrt 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 The frames layer section for more information on frames, and Jacobians section for more on Jacobians.

Parameters:

f2f – the Karana::Frame::Frame2Frame defining the relative Jacobian from/to frames

Returns:

the Jacobian matrix

virtual km::Mat poseGradient(const kf::Frame2Frame &f2f, bool oriented = true) const#

Return the pose gradient matrix for a Karana::Frame::Frame2Frame.

Return the 6xnU gradient matrix for the pose of a Karana::Frame::Frame2Frame’s pframe wrt 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. If oriented is false, the returned value is negated first.

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

Parameters:
  • f2f – the Frame2Frame defining the relative from/to frames

  • oriented – the orientation of the coordinates provider

Returns:

the gradient matrix

km::Mat poseGradientNumDiff(const kf::Frame2Frame &f2f)#

Return the pose gradient matrix for a Karana::Frame::Frame2Frame using numerical differencing.

This method uses numerical differencing to compute the 6xnU pose gradient of a Karana::Frame::Frame2Frame’s pframe wrt to its oframe using numerical differencing. The primary purpose of this method is to cross-validate the analytical pose gradient computation.

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

Parameters:

f2f – the Frame2Frame defining the relative Jacobian from/to frames

Returns:

the pose gradient matrix

Protected Functions

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#

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

virtual km::Mat _oframe2pframePhi() const = 0#

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

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

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

void _resizeCoordBuffers(size_t nQ, size_t nU)#

Callback to update the coord map matrix value used for Hst in the ATBI computations

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.

std::string _name#
kc::id_t _id#
kc::ks_ptr<kc::DataCache<km::Vec>> _Q_cache = nullptr#

the (6*nbodies)xNU joint map matrix data cache

kc::ks_ptr<kc::DataCache<km::Vec>> _U_cache = nullptr#
kc::ks_ptr<kc::DataCache<km::Vec>> _Udot_cache = nullptr#
kc::ks_ptr<kc::DataCache<km::Vec>> _T_cache = nullptr#
kc::ks_ptr<kc::DataCache<km::Vec>> _Qdot_cache = nullptr#
kc::ks_ptr<ATBIMatrices> _atbi_matrices = nullptr#

Buffers for the generalized coordinates for this physical subhinge. We do these here because the coordinate buffers for compbound subhinges come from the CoordData associated with the embedded bodies. Additional such buffers will be available within the body class for for deformable bodies.

kc::ks_ptr<ATBIFilterVectors> _atbi_filter_vectors = nullptr#
size_t _nQ = 0#

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

size_t _nU = 0#
km::Vec _Q#

gen coords buffer

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 _U#

gen velocities buffer

km::Vec _Udot#

gen accels buffer

km::Vec _T#

gen forces buffer

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

inline virtual ~ATBIFilterVectors()#
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

inline virtual ~ATBIMatrices()#