Program Listing for File PinSubhinge.h

Program Listing for File PinSubhinge.h#

Return to documentation for file (include/Karana/SOADyn/PinSubhinge.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"Karana/SOADyn/PhysicalSubhinge.h"

namespaceKarana::Dynamics{

namespacekf=Karana::Frame;
namespacekm=Karana::Math;

classLockedSubhinge:publicPhysicalSubhinge_T<0,0>{

public:
LockedSubhinge(kc::ks_ptr<kf::Frame>oframe,
kc::ks_ptr<kf::Frame>pframe,
std::string_viewname,
kc::ks_ptr<FramePairHinge>hge);

virtual~LockedSubhinge();

std::string_viewtypeString()constnoexceptoverride{
staticstd::stringtype_string="Karana::Dynamics::LockedSubhinge";
returntype_string;
}

SubhingeBase::SubhingeTypesubhingeType()constoverride;

protected:
kc::ks_ptr<PhysicalSubhinge::PhysicalSubhingeParams>_getParams()constoverride;
void_setParams(constPhysicalSubhinge::PhysicalSubhingeParams&params)override;
};

classPhysical1DofSubhinge:publicPhysicalSubhinge_T<1,1>{

public:
Physical1DofSubhinge(kc::ks_ptr<kf::Frame>oframe,
kc::ks_ptr<kf::Frame>pframe,
std::string_viewname,
kc::ks_ptr<FramePairHinge>hge);

~Physical1DofSubhinge(){};

virtualvoidsetUnitAxis(constkm::Vec3&axis);

constkm::Vec3&getUnitAxis()const{return_unit_axis;}

voidsetJointLimits(constKarana::Math::Vec&limits);

km::VecgetJointLimits()const{return_joint_limits;}

voidsetGearRatio(doublegear_ratio);

doublegetGearRatio()const{return_gear_ratio;}

structPhysicalSubhingeParams:publicPhysicalSubhinge::PhysicalSubhingeParams{
km::Vec3unit_axis;

PhysicalSubhingeParams()=default;

PhysicalSubhingeParams&operator=(constPhysicalSubhinge::PhysicalSubhingeParams*p){
if(this!=p){
PhysicalSubhinge::PhysicalSubhingeParams::operator=(
*p);//Callbaseclassassignmentoperator
//AssignDerived-specificmembershere
unit_axis=static_cast<constPhysicalSubhingeParams*>(p)->unit_axis;
}

return*this;
}
};

boolisFinalized()constoverride;

protected:
kc::ks_ptr<PhysicalSubhinge::PhysicalSubhingeParams>_getParams()constoverride;
void_setParams(constPhysicalSubhinge::PhysicalSubhingeParams&params)override;

protected:
km::Vec_joint_limits=km::Vec(2);

double_gear_ratio=km::uninitializedNaN;

km::Vec3_unit_axis={0,0,0};
};

classPinSubhinge:publicPhysical1DofSubhinge{

//foraccesstoconstructor
//friendclassPinHinge;
friendclassPhysicalBody;

public:
virtual~PinSubhinge(){};

std::string_viewtypeString()constnoexceptoverride{
staticstd::stringtype_string="Karana::Dynamics::PinSubhinge";
returntype_string;
}

SubhingeBase::SubhingeTypesubhingeType()constoverride;

PinSubhinge(kc::ks_ptr<kf::Frame>oframe,
kc::ks_ptr<kf::Frame>pframe,
std::string_viewname,
kc::ks_ptr<FramePairHinge>hge);

voidsetUnitAxis(constkm::Vec3&axis)override;

protected:
void_computeTransform(km::HomTran&)override;

void_computeVelocity(km::SpatialVector&)override;

void_computeAccel(km::SpatialVector&)override;
};

classLinearSubhinge:publicPhysical1DofSubhinge{

public:
virtual~LinearSubhinge(){};

SubhingeBase::SubhingeTypesubhingeType()constoverride;

std::string_viewtypeString()constnoexceptoverride{
staticstd::stringtype_string="Karana::Dynamics::LinearSubhinge";
returntype_string;
}

voidsetUnitAxis(constkm::Vec3&axis)override;

LinearSubhinge(kc::ks_ptr<kf::Frame>oframe,
kc::ks_ptr<kf::Frame>pframe,
std::string_viewname,
kc::ks_ptr<FramePairHinge>hge);

protected:
void_computeTransform(km::HomTran&)override;

void_computeVelocity(km::SpatialVector&)override;

void_computeAccel(km::SpatialVector&)override;
};

classScrewSubhinge:publicPhysical1DofSubhinge{

public:
virtual~ScrewSubhinge(){};

std::string_viewtypeString()constnoexceptoverride{
staticstd::stringtype_string="Karana::Dynamics::ScrewSubhinge";
returntype_string;
}

SubhingeBase::SubhingeTypesubhingeType()constoverride;
voidsetUnitAxis(constkm::Vec3&axis)override;

boolisFinalized()constoverride;

voidsetPitch(doublepitch);

doublegetPitch()const{return_pitch;}

ScrewSubhinge(kc::ks_ptr<kf::Frame>oframe,
kc::ks_ptr<kf::Frame>pframe,
std::string_viewname,
kc::ks_ptr<FramePairHinge>hge);

protected:
void_computeTransform(km::HomTran&)override;

void_computeVelocity(km::SpatialVector&)override;

void_computeAccel(km::SpatialVector&)override;

structPhysicalSubhingeParams:publicPhysical1DofSubhinge::PhysicalSubhingeParams{

doublepitch;

//Addingsuppression,asCodeCheckercomplainsthismethodhasthesamenameasa
//methodinthebaseversion.ThisisjustaCodeCheckerfalsepositive.
//codechecker_suppress[cppcheck-duplInheritedMember]
PhysicalSubhingeParams&operator=(constPhysicalSubhinge::PhysicalSubhingeParams*p){
if(this!=p){
Physical1DofSubhinge::PhysicalSubhingeParams::operator=(
p);//Callbaseclassassignmentoperator
pitch=static_cast<constPhysicalSubhingeParams*>(p)->pitch;
}

return*this;
}
};

kc::ks_ptr<PhysicalSubhinge::PhysicalSubhingeParams>_getParams()constoverride;
void_setParams(constPhysicalSubhinge::PhysicalSubhingeParams&params)override;

private:
double_pitch;
};

classSphericalSubhinge:publicPhysicalSubhinge_T<3,3>{

public:
virtual~SphericalSubhinge();

std::string_viewtypeString()constnoexceptoverride{
staticstd::stringtype_string="Karana::Dynamics::SphericalSubhinge";
returntype_string;
}

SubhingeBase::SubhingeTypesubhingeType()constoverride;

SphericalSubhinge(kc::ks_ptr<kf::Frame>oframe,
kc::ks_ptr<kf::Frame>pframe,
std::string_viewname,
kc::ks_ptr<FramePairHinge>hge);

constkm::Vec&getQdot()constoverride;

voidsetU(constEigen::Ref<constkm::Vec>&val)override;

std::stringdumpString(std::string_viewprefix,
constKarana::Core::Base::DumpOptions*options)constoverride;

/*Reportthatthisisatypeofsubhingethathascoordinate
sanitizationneeds(forrecenteringthechart)*/
boolrequiresCoordSanitization()constoverride{returntrue;}

voidsetMaxChartAngle(doubleval){_max_chart_angle=val;}

doublegetMaxChartAngle()const{return_max_chart_angle;}

/*Recenterthelocalchartifthecoordinatesangleexceeds
theallowedmaxforthechart*/
boolsanitizeCoords()override;

constkm::UnitQuaternion&getChartOffset()const{return_chart_offset;}

voidresetChart()override{_chart_offset.setIdentity();}

constkm::Vec&getQ()constoverride;

voidsetQ(constEigen::Ref<constkm::Vec>&val)override;

protected:
void_computeTransform(km::HomTran&)override;

void_computeVelocity(km::SpatialVector&)override;

void_computeAccel(km::SpatialVector&)override;

void_computeQdot(km::Vec&)const;

km::MatposeGradient(constkf::FrameToFrame&f2f,booloriented)constoverride;

km::Mat33_genvelToQdotMap()const;

km::Mat33_qdotToGenvelMap()const;

structPhysicalSubhingeParams:PhysicalSubhinge::PhysicalSubhingeParams{
doublemax_chart_angle;

PhysicalSubhingeParams&operator=(constPhysicalSubhinge::PhysicalSubhingeParams*p){
if(this!=p){
PhysicalSubhinge::PhysicalSubhingeParams::operator=(
*p);//Callbaseclassassignmentoperator
//AssignDerived-specificmembershere
max_chart_angle=
static_cast<constPhysicalSubhingeParams*>(p)->max_chart_angle;
}

return*this;
}
};

kc::ks_ptr<PhysicalSubhinge::PhysicalSubhingeParams>_getParams()constoverride;
void_setParams(constPhysicalSubhinge::PhysicalSubhingeParams&params)override;

void_enableCoordChart(boolflag)override;//{_chart_enabled=flag;};

private:
double_max_chart_angle;

km::UnitQuaternion_chart_offset=km::UnitQuaternion(0,0,0,1,false,true);

mutablekm::Vec_global_Q;

bool_chart_enabled=true;
};

classSphericalQuatSubhinge:publicPhysicalSubhinge_T<4,3>{

public:
virtual~SphericalQuatSubhinge();

std::string_viewtypeString()constnoexceptoverride{
staticstd::stringtype_string="Karana::Dynamics::SphericalQuatSubhinge";
returntype_string;
}

SubhingeBase::SubhingeTypesubhingeType()constoverride;

SphericalQuatSubhinge(kc::ks_ptr<kf::Frame>oframe,
kc::ks_ptr<kf::Frame>pframe,
std::string_viewname,
kc::ks_ptr<FramePairHinge>hge);

voidsetU(constEigen::Ref<constkm::Vec>&val)override;

//voidsetQ(constEigen::Ref<constkm::Vec>&val)override;

constkm::Vec&getQdot()constoverride;

std::stringdumpString(std::string_viewprefix,
constKarana::Core::Base::DumpOptions*options)constoverride;

protected:
void_localChartSetQ(constEigen::Ref<constkm::Vec>&val)override;

void_computeTransform(km::HomTran&)override;

void_computeVelocity(km::SpatialVector&)override;

void_computeAccel(km::SpatialVector&)override;

void_computeQdot(km::Vec&)const;

km::MatposeGradient(constkf::FrameToFrame&f2f,booloriented)constoverride;

km::Mat_genvelToQdotMap()const;
km::Mat_qdotToGenvelMap()const;

kc::ks_ptr<PhysicalSubhingeParams>_getParams()constoverride;
};

classLinear3Subhinge:publicPhysicalSubhinge_T<3,3>{

public:
virtual~Linear3Subhinge();

std::string_viewtypeString()constnoexceptoverride{
staticstd::stringtype_string="Karana::Dynamics::Linear3Subhinge";
returntype_string;
}

SubhingeBase::SubhingeTypesubhingeType()constoverride;

Linear3Subhinge(kc::ks_ptr<kf::Frame>oframe,
kc::ks_ptr<kf::Frame>pframe,
std::string_viewname,
kc::ks_ptr<FramePairHinge>hge);

protected:
void_computeTransform(km::HomTran&)override;

void_computeVelocity(km::SpatialVector&)override;

void_computeAccel(km::SpatialVector&)override;

kc::ks_ptr<PhysicalSubhingeParams>_getParams()constoverride;
};

}//namespaceKarana::Dynamics