Program Listing for File CoordBase.h#
↰ Return to documentation for file (include/Karana/SOADyn/CoordBase.h)
/*
*Copyright(c)2024-2025KaranaDynamicsPtyLtd.Allrightsreserved.
*
*NOTICETOUSER:
*
*Thissourcecodeand/ordocumentation(the"LicensedMaterials")is
*theconfidentialandproprietaryinformationofKaranaDynamicsInc.
*UseoftheseLicensedMaterialsisgovernedbythetermsandconditions
*ofaseparatesoftwarelicenseagreementbetweenKaranaDynamicsandthe
*Licensee("LicenseAgreement").Unlessexpresslypermittedunderthat
*agreement,anyreproduction,modification,distribution,ordisclosure
*oftheLicensedMaterials,inwholeorinpart,toanythirdparty
*withoutthepriorwrittenconsentofKaranaDynamicsisstrictlyprohibited.
*
*THELICENSEDMATERIALSAREPROVIDED"ASIS"WITHOUTWARRANTYOFANYKIND.
*KARANADYNAMICSDISCLAIMSALLWARRANTIES,EXPRESSORIMPLIED,INCLUDING
*BUTNOTLIMITEDTOWARRANTIESOFMERCHANTABILITY,NON-INFRINGEMENT,AND
*FITNESSFORAPARTICULARPURPOSE.
*
*INNOEVENTSHALLKARANADYNAMICSBELIABLEFORANYDAMAGESWHATSOEVER,
*INCLUDINGBUTNOTLIMITEDTOLOSSOFPROFITS,DATA,ORUSE,EVENIF
*ADVISEDOFTHEPOSSIBILITYOFSUCHDAMAGES,WHETHERINCONTRACT,TORT,
*OROTHERWISEARISINGOUTOFORINCONNECTIONWITHTHELICENSEDMATERIALS.
*
*U.S.GovernmentEndUsers:TheLicensedMaterialsarea"commercialitem"
*asdefinedat48C.F.R.2.101,andareprovidedtotheU.S.Government
*onlyasacommercialenditemunderthetermsofthislicense.
*
*AnyuseoftheLicensedMaterialsinindividualorcommercialsoftwaremust
*include,intheuserdocumentationandinternalsourcecodecomments,
*thisNotice,Disclaimer,andU.S.GovernmentUseProvision.
*/
#pragmaonce
#include<memory>
//#include"Karana/KCore/Allocator.h"
#include"Karana/Frame/Frame.h"
#include"Karana/Frame/Frame2Frame.h"
#include"Karana/KCore/Base.h"
#include"Karana/KCore/DataCache.h"
#include"Karana/Math/Defs.h"
#include"Karana/Math/SpatialVector.h"
namespaceKarana::Dynamics{
classHingeOnode;
namespacekc=Karana::Core;
namespacekm=Karana::Math;
namespacekf=Karana::Frame;
classCoordBase//:publickc::LockingBase
{
//foraccessto_newtonian_frame
friendclassF2FJacobianGenerator;
friendclassFramePairHinge;
//foraccessto_pframe2otherPhiandrelatedmethods
friendclassSubTree;
public:
CoordBase(conststd::string&nm,kc::id_tid);
virtual~CoordBase();//=default;
std::stringdumpString(conststd::string&prefix,
constkc::Base::dumpOptions*options)const;
virtualkc::ks_ptr<kf::Frame2Frame>f2f()const=0;
std::optional<bool>isOriented(constkf::Frame2Frame&f2f)const;
#if1
virtualconststd::string&name()const{return_name;};
virtualconstkc::id_t&id()const{return_id;}
virtualconststd::string&typeString()constnoexcept=0;
#endif
virtualkm::Matjacobian(constkf::Frame&target,booloriented=true)const=0;
virtualkm::MatjacobianDot(constkf::Frame&target,booloriented=true)const=0;
virtualboolisFinalized()const;//override;
virtualkm::MatgetATBIMatPsi()const=0;
virtualkm::MatgetATBID()const=0;
virtualkm::MatgetATBIDinv()const=0;
virtualkm::MatgetATBIG()const=0;
virtualkm::MatgetATBITauper()const=0;
virtualkm::MatpframeCoordMapMatrix()const{
//defaultdefintion
returnatbiCoordMapMatrix();
}
virtualconstkm::MatatbiCoordMapMatrix()const{returnkm::Mat();}
virtualkm::MatgetUpsilonMatrix()=0;
public:
//boolisFinalized()constoverride;
public:
virtualvoidsetQ(constEigen::Ref<constkm::Vec>&val);
virtualvoidsetQ(doublefill_value);
virtualconstkm::Vec&getQ()const;
virtualvoidsetU(constEigen::Ref<constkm::Vec>&val);
virtualvoidsetU(doublefill_value);
virtualconstkm::Vec&getU()const;
virtualvoidsetT(constEigen::Ref<constkm::Vec>&val);
virtualvoidsetT(doublefill_value);
virtualconstkm::Vec&getT()const;
virtualvoidsetUdot(constEigen::Ref<constkm::Vec>&val);
virtualvoidsetUdot(doublefill_value);
virtualconstkm::Vec&getUdot()const;
virtualconstkm::Vec&getQdot()const{returngetU();}
size_tnQ()const{return_nQ;};
size_tnU()const{return_nU;};
#if0
constkm::Mat&coordMapMatrix()const{return_coord_map_matrix_cache->get();}
#endif
km::MatjacobianNumDiff(constkf::Frame2Frame&f2f);
virtualkm::MatposeGradient(constkf::Frame2Frame&f2f,booloriented=true)const;
km::MatposeGradientNumDiff(constkf::Frame2Frame&f2f);
protected:
structATBIMatrices{
virtual~ATBIMatrices(){};
};
constATBIMatrices&atbiMatrices()const{return*_atbi_matrices;}
structATBIFilterVectors{
virtual~ATBIFilterVectors(){};
};
constATBIFilterVectors&atbiFilterVectors()const{return*_atbi_filter_vectors;}
protected:
virtualkm::Mat_oframe2pframePsi()const=0;
virtualkm::Mat_oframe2pframePhi()const=0;
virtualkm::Mat_pframe2otherPhi(constkf::Frame&other)const=0;
protected:
kc::ks_ptr<kf::Frame>_newtonian_frame=nullptr;
//virtualvoid_computeATBICoordMapMatrix(body_NU_NU_Mat&val)const=0;
//virtualvoid_computeATBICoordMapMatrix(km::Mat&val)const=0;
void_resizeCoordBuffers(size_tnQ,size_tnU);
protected:
std::string_name;
kc::id_t_id;
//kc::ks_ptr<kc::DataCache<km::Mat>>_coord_map_matrix_cache=nullptr;
kc::ks_ptr<kc::DataCache<km::Vec>>_Q_cache=nullptr;
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;
kc::ks_ptr<ATBIFilterVectors>_atbi_filter_vectors=nullptr;
//kc::ks_ptr<kc::DataCache<body_NU_NU_Mat>>_atbi_coord_map_matrix_cache=nullptr;
//kc::ks_ptr<kc::DataCache<km::Mat>>_atbi_coord_map_matrix_cache=nullptr;
size_t_nQ=0,_nU=0;
protected:
km::Vec_Q;
km::Vec_U;
km::Vec_Udot;
km::Vec_T;
};
}//namespaceKarana::Dynamics