Class CECompoundSubhinge#
Defined in File CECompoundSubhinge.h
Inheritance Relationships#
Base Type#
public Karana::Dynamics::CompoundSubhinge(Class CompoundSubhinge)
Class Documentation#
-
class CECompoundSubhinge : public Karana::Dynamics::CompoundSubhinge#
Represents the articulation subhinge class for compound body subhinge with embedded constraints.
Public Functions
-
virtual ~CECompoundSubhinge()#
Destructor.
-
virtual void setQ(const Eigen::Ref<const km::Vec> &val) override#
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 setU(const Eigen::Ref<const km::Vec> &val) override#
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 const km::Vec &getQ() const override#
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 const km::Vec &getU() const override#
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) override#
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 const km::Vec &getT() const override#
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) override#
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 const km::Vec &getUdot() const override#
Return the Udot acceleration coordinates.
See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.
- Returns:
Array of values.
-
virtual const km::Vec &getQdot() const override#
Return the Qdot rate coordinates.
See Generalized Q, U etc coordinates section for discussion on Q, U etc coordinates.
- Returns:
Array of values.
-
CECompoundSubhinge(kc::ks_ptr<CompoundHinge> hge, size_t indep_n_u, size_t indep_n_q)#
Constructs a CECompoundSubhinge.
- Parameters:
hge – the parent compound hinge
indep_n_u – the number U velocity coordinates
indep_n_q – the number Q generalized coordinates
Protected Functions
-
virtual void _localChartSetQ(const Eigen::Ref<const km::Vec> &val) override#
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 override#
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.
-
virtual void _discard(Karana::Core::ks_ptr<Karana::Core::Base> &base) override#
Discard the the object. Derived classes should implement this with the logic required to discard themselves if applicable.
- Parameters:
base – - A pointer to the object to discard.
-
virtual km::Vec _getHingeXdotU(PhysicalHinge &hge) const override#
Return the XdotU vector for the specific embedded physical hinge.
This method returns a null vector for regular compound bodies. Its return value is non-null however for constraint-embedded compound bodies whose X matrix is configuration dependent.
- Parameters:
hge – the hinge
- Returns:
the a’ spatial acceleration value
-
virtual const km::Mat atbiCoordMapMatrix() const override#
Return the coordinate map matrix to be used for ATBI computations.
- Returns:
coordinate map matrix
-
virtual km::Mat _jacobian(const kf::FrameToFrame &f2f) const override#
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 override#
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
Protected Attributes
-
mutable km::Mat _dependent_coord_map_matrix#
local variable for the intermediate coord map matrix with columns for the dependent coordinates as well. This matrix is post multiplied by X to get the actual coord map matrix for this CE subhinge
-
size_t _dependents_nU = 0#
keep track of the size of the dependent coords nU
-
mutable km::Vec _getQ_min_cache#
Vector for storing getQ.
-
mutable km::Vec _getQdot_min_cache#
Vector for storing getQdot.
-
mutable km::Vec _getU_min_cache#
Vector for storing getU.
-
mutable km::Vec _getUdot_min_cache#
Vector for storing getUdot.
-
mutable km::Vec _getT_min_cache#
Vector for storing getT.
-
virtual ~CECompoundSubhinge()#