33#ifndef DART_DYNAMICS_GENERICJOINT_HPP_
34#define DART_DYNAMICS_GENERICJOINT_HPP_
46template <
class ConfigSpaceT>
51 static constexpr std::size_t
NumDofs = ConfigSpaceT::NumDofs;
56 using Point =
typename ConfigSpaceT::Point;
58 using Vector =
typename ConfigSpaceT::Vector;
60 using Matrix =
typename ConfigSpaceT::Matrix;
442 const
Eigen::VectorXd& q2, const
Eigen::VectorXd& q1) const override;
505 const
Eigen::VectorXd& _positions) const override;
509 const
Vector& positions) const = 0;
550 Eigen::Vector6d& partialAcceleration,
551 const
Eigen::Vector6d& childVelocity) override;
561 Eigen::Matrix6d& parentArtInertia,
562 const
Eigen::Matrix6d& childArtInertia) override;
566 Eigen::Matrix6d& parentArtInertiaImplicit,
567 const
Eigen::Matrix6d& childArtInertiaImplicit) override;
574 const
Eigen::Matrix6d& artInertia,
double timeStep) override;
578 Eigen::Vector6d& parentBiasForce,
579 const
Eigen::Matrix6d& childArtInertia,
580 const
Eigen::Vector6d& childBiasForce,
581 const
Eigen::Vector6d& childPartialAcc) override;
585 Eigen::Vector6d& parentBiasImpulse,
586 const
Eigen::Matrix6d& childArtInertia,
587 const
Eigen::Vector6d& childBiasImpulse) override;
591 const
Eigen::Vector6d& bodyForce,
double timeStep) override;
601 const
Eigen::Matrix6d& artInertia,
602 const
Eigen::Vector6d& spatialAcc) override;
606 const
Eigen::Matrix6d& artInertia,
607 const
Eigen::Vector6d& velocityChange) override;
611 const
Eigen::Vector6d& bodyForce,
613 bool withDampingForces,
614 bool withSpringForces) override;
618 const
Eigen::Vector6d& bodyForce,
620 bool withDampingForcese,
621 bool withSpringForces) override;
640 Eigen::Vector6d& parentBiasForce,
641 const
Eigen::Matrix6d& childArtInertia,
642 const
Eigen::Vector6d& childBiasForce) override;
646 Eigen::Vector6d& parentBiasForce,
647 const
Eigen::Matrix6d& childArtInertia,
648 const
Eigen::Vector6d& childBiasForce) override;
652 const
Eigen::Vector6d& bodyForce) override;
656 Eigen::MatrixXd& invMassMat,
658 const
Eigen::Matrix6d& artInertia,
659 const
Eigen::Vector6d& spatialAcc) override;
663 Eigen::MatrixXd& invMassMat,
665 const
Eigen::Matrix6d& artInertia,
666 const
Eigen::Vector6d& spatialAcc) override;
673 const
Eigen::Vector6d& spatial) override;
744 Eigen::Matrix6d& parentArtInertia,
745 const
Eigen::Matrix6d& childArtInertia);
748 Eigen::Matrix6d& parentArtInertia,
749 const
Eigen::Matrix6d& childArtInertia);
752 Eigen::Matrix6d& parentArtInertia,
753 const
Eigen::Matrix6d& childArtInertia);
756 Eigen::Matrix6d& parentArtInertia,
757 const
Eigen::Matrix6d& childArtInertia);
764 const
Eigen::Matrix6d& artInertia,
double timeStep);
767 const
Eigen::Matrix6d& artInertia,
double timeStep);
770 Eigen::Vector6d& parentBiasForce,
771 const
Eigen::Matrix6d& childArtInertia,
772 const
Eigen::Vector6d& childBiasForce,
773 const
Eigen::Vector6d& childPartialAcc);
776 Eigen::Vector6d& parentBiasForce,
777 const
Eigen::Matrix6d& childArtInertia,
778 const
Eigen::Vector6d& childBiasForce,
779 const
Eigen::Vector6d& childPartialAcc);
782 Eigen::Vector6d& parentBiasImpulse,
783 const
Eigen::Matrix6d& childArtInertia,
784 const
Eigen::Vector6d& childBiasImpulse);
787 Eigen::Vector6d& parentBiasImpulse,
788 const
Eigen::Matrix6d& childArtInertia,
789 const
Eigen::Vector6d& childBiasImpulse);
792 const
Eigen::Vector6d& bodyForce,
double timeStep);
795 const
Eigen::Vector6d& bodyForce,
double timeStep);
802 const
Eigen::Matrix6d& artInertia, const
Eigen::Vector6d& spatialAcc);
805 const
Eigen::Matrix6d& artInertia, const
Eigen::Vector6d& spatialAcc);
808 const
Eigen::Matrix6d& artInertia, const
Eigen::Vector6d& velocityChange);
811 const
Eigen::Matrix6d& artInertia, const
Eigen::Vector6d& velocityChange);
823#include "dart/dynamics/detail/GenericJoint.hpp"
BodyPropPtr properties
Definition SdfParser.cpp:80
std::string * name
Definition SkelParser.cpp:1697
bool * preserveName
Definition SkelParser.cpp:1696
Eigen::VectorXd velocity
Definition SkelParser.cpp:109
Eigen::VectorXd force
Definition SkelParser.cpp:111
std::size_t index
Definition SkelParser.cpp:1672
Eigen::VectorXd acceleration
Definition SkelParser.cpp:110
double * friction
Definition SkelParser.cpp:1694
Eigen::VectorXd position
Definition SkelParser.cpp:108
This is an alternative to EmbedStateAndProperties which allows your class to also inherit other Compo...
Definition EmbeddedAspect.hpp:435
typename Impl::AspectState AspectState
Definition EmbeddedAspect.hpp:440
typename Impl::Aspect Aspect
Definition EmbeddedAspect.hpp:443
typename Impl::AspectProperties AspectProperties
Definition EmbeddedAspect.hpp:442
DegreeOfFreedom class is a proxy class for accessing single degrees of freedom (aka generalized coord...
Definition DegreeOfFreedom.hpp:56
Definition GenericJoint.hpp:49
void setAspectState(const AspectState &state)
Set the AspectState of this GenericJoint.
Definition GenericJoint.hpp:113
void setForceLowerLimits(const Eigen::VectorXd &lowerLimits) override
Definition GenericJoint.hpp:1239
double getCommand(std::size_t index) const override
Definition GenericJoint.hpp:389
typename ConfigSpaceT::Matrix Matrix
Definition GenericJoint.hpp:60
void addChildArtInertiaImplicitToKinematic(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia)
Definition GenericJoint.hpp:1840
Eigen::VectorXd getCommands() const override
Definition GenericJoint.hpp:475
void resetVelocities() override
Definition GenericJoint.hpp:945
const Vector & getPositionsStatic() const
Fixed-size version of getPositions()
Definition GenericJoint.hpp:733
void setAccelerationsStatic(const Vector &accels)
Fixed-size version of setAccelerations()
Definition GenericJoint.hpp:759
void copy(const ThisClass &otherJoint)
Copy the Properties of another GenericJoint.
Definition GenericJoint.hpp:158
void setForceUpperLimits(const Eigen::VectorXd &upperLimits) override
Definition GenericJoint.hpp:1286
void updateTotalImpulseKinematic(const Eigen::Vector6d &bodyImpulse)
Definition GenericJoint.hpp:2203
void setCoulombFriction(std::size_t index, double friction) override
Definition GenericJoint.hpp:1515
const JacobianMatrix & getRelativeJacobianTimeDerivStatic() const
Fixed-size version of getRelativeJacobianTimeDeriv()
Definition GenericJoint.hpp:1598
void setRestPosition(std::size_t index, double q0) override
Definition GenericJoint.hpp:1461
Vector mTotalForce
Total force projected on joint space.
Definition GenericJoint.hpp:723
void setAccelerations(const Eigen::VectorXd &accelerations) override
Definition GenericJoint.hpp:1035
Vector mInvM_a
Definition GenericJoint.hpp:733
void updateTotalImpulse(const Eigen::Vector6d &bodyImpulse) override
Definition GenericJoint.hpp:2169
void updateForceFD(const Eigen::Vector6d &bodyForce, double timeStep, bool withDampingForcese, bool withSpringForces) override
Definition GenericJoint.hpp:2350
const Matrix & getInvProjArtInertiaImplicit() const
Get the inverse of projected articulated inertia for implicit joint damping and spring forces.
Definition GenericJoint.hpp:1738
Eigen::VectorXd getPositionUpperLimits() const override
Definition GenericJoint.hpp:632
Vector mVelocityChanges
Change of generalized velocity.
Definition GenericJoint.hpp:686
void setVelocityUpperLimits(const Eigen::VectorXd &upperLimits) override
Definition GenericJoint.hpp:911
void updateForceID(const Eigen::Vector6d &bodyForce, double timeStep, bool withDampingForces, bool withSpringForces) override
Definition GenericJoint.hpp:2316
Eigen::VectorXd getAccelerationUpperLimits() const override
Definition GenericJoint.hpp:1147
void updateAccelerationKinematic(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc)
Definition GenericJoint.hpp:2258
void updateVelocityChangeDynamic(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &velocityChange)
Definition GenericJoint.hpp:2291
Eigen::VectorXd getVelocityLowerLimits() const override
Definition GenericJoint.hpp:877
void updateInvProjArtInertiaImplicit(const Eigen::Matrix6d &artInertia, double timeStep) override
Definition GenericJoint.hpp:1899
void setVelocityLowerLimits(const Eigen::VectorXd &lowerLimits) override
Definition GenericJoint.hpp:863
void updateConstrainedTermsDynamic(double timeStep)
Definition GenericJoint.hpp:2430
void setPositionLowerLimit(std::size_t index, double position) override
Definition GenericJoint.hpp:543
const GenericJoint< ConfigSpaceT >::JacobianMatrix & getRelativeJacobianStatic() const
Fixed-size version of getRelativeJacobian()
Definition GenericJoint.hpp:1568
void addChildArtInertiaToDynamic(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia)
Definition GenericJoint.hpp:1771
const math::Jacobian getRelativeJacobianTimeDeriv() const override
Definition GenericJoint.hpp:1589
void setVelocities(const Eigen::VectorXd &velocities) override
Definition GenericJoint.hpp:812
void addChildBiasImpulseToKinematic(Eigen::Vector6d &parentBiasImpulse, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasImpulse)
Definition GenericJoint.hpp:2088
void addChildArtInertiaImplicitTo(Eigen::Matrix6d &parentArtInertiaImplicit, const Eigen::Matrix6d &childArtInertiaImplicit) override
Definition GenericJoint.hpp:1799
void setPosition(std::size_t index, double position) override
Definition GenericJoint.hpp:489
void updateVelocityChange(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &velocityChange) override
Definition GenericJoint.hpp:2267
void setCommand(std::size_t index, double command) override
Definition GenericJoint.hpp:319
std::array< DegreeOfFreedom *, NumDofs > mDofs
Array of DegreeOfFreedom objects.
Definition GenericJoint.hpp:679
void setInitialPosition(std::size_t index, double initial) override
Definition GenericJoint.hpp:673
Eigen::VectorXd getForces() const override
Definition GenericJoint.hpp:1206
void resetCommands() override
Definition GenericJoint.hpp:482
void setVelocityChange(std::size_t index, double velocityChange) override
Definition GenericJoint.hpp:1317
typename Base::AspectState AspectState
Definition GenericJoint.hpp:64
void setAccelerationUpperLimits(const Eigen::VectorXd &upperLimits) override
Definition GenericJoint.hpp:1133
void setPartialAccelerationTo(Eigen::Vector6d &partialAcceleration, const Eigen::Vector6d &childVelocity) override
Definition GenericJoint.hpp:1690
double getVelocity(std::size_t index) const override
Definition GenericJoint.hpp:799
Eigen::Vector6d getBodyConstraintWrench() const override
Definition GenericJoint.hpp:1645
void addAccelerationTo(Eigen::Vector6d &acc) override
Definition GenericJoint.hpp:1704
void updateTotalImpulseDynamic(const Eigen::Vector6d &bodyImpulse)
Definition GenericJoint.hpp:2193
void setForce(std::size_t index, double force) override
Definition GenericJoint.hpp:1161
Vector mConstraintImpulses
Generalized constraint impulse.
Definition GenericJoint.hpp:692
void setInitialVelocity(std::size_t index, double initial) override
Definition GenericJoint.hpp:952
double getForce(std::size_t index) const override
Definition GenericJoint.hpp:1177
void setInitialVelocities(const Eigen::VectorXd &initial) override
Definition GenericJoint.hpp:979
void updateInvProjArtInertiaDynamic(const Eigen::Matrix6d &artInertia)
Definition GenericJoint.hpp:1875
void setPositionUpperLimit(std::size_t index, double position) override
Definition GenericJoint.hpp:591
void updateInvProjArtInertiaImplicitKinematic(const Eigen::Matrix6d &artInertia, double timeStep)
Definition GenericJoint.hpp:1944
const math::Jacobian getRelativeJacobian() const override
Definition GenericJoint.hpp:1560
std::size_t getNumDofs() const override
Definition GenericJoint.hpp:211
void resetForces() override
Definition GenericJoint.hpp:1307
DegreeOfFreedom * getDof(std::size_t index) override
void addChildArtInertiaTo(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia) override
Definition GenericJoint.hpp:1747
Eigen::VectorXd getPositionLowerLimits() const override
Definition GenericJoint.hpp:584
bool isDofNamePreserved(size_t index) const override
Definition GenericJoint.hpp:263
void addVelocityTo(Eigen::Vector6d &vel) override
Definition GenericJoint.hpp:1679
void preserveDofName(size_t index, bool preserve) override
Definition GenericJoint.hpp:250
double getVelocityUpperLimit(std::size_t index) const override
Definition GenericJoint.hpp:898
double getVelocityChange(std::size_t index) const override
Definition GenericJoint.hpp:1331
Vector mTotalImpulse
Total impluse projected on joint space.
Definition GenericJoint.hpp:726
void updateTotalForce(const Eigen::Vector6d &bodyForce, double timeStep) override
Definition GenericJoint.hpp:2101
void resetConstraintImpulses() override
Definition GenericJoint.hpp:1378
virtual Vector getPositionDifferencesStatic(const Vector &q2, const Vector &q1) const
Fixed-size version of getPositionDifferences()
Definition GenericJoint.hpp:1424
void setVelocity(std::size_t index, double velocity) override
Definition GenericJoint.hpp:778
double getRestPosition(std::size_t index) const override
Definition GenericJoint.hpp:1474
void updateConstrainedTerms(double timeStep) override
Definition GenericJoint.hpp:2407
void integrateVelocities(double dt) override
Definition GenericJoint.hpp:1397
Eigen::VectorXd getPositions() const override
Definition GenericJoint.hpp:536
void addChildBiasImpulseToDynamic(Eigen::Vector6d &parentBiasImpulse, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasImpulse)
Definition GenericJoint.hpp:2068
double getAcceleration(std::size_t index) const override
Definition GenericJoint.hpp:1022
Eigen::VectorXd getVelocities() const override
Definition GenericJoint.hpp:829
Eigen::VectorXd getInitialPositions() const override
Definition GenericJoint.hpp:714
Eigen::VectorXd getPositionDifferences(const Eigen::VectorXd &q2, const Eigen::VectorXd &q1) const override
Definition GenericJoint.hpp:1405
void setPositionLowerLimits(const Eigen::VectorXd &lowerLimits) override
Definition GenericJoint.hpp:570
double getAccelerationUpperLimit(std::size_t index) const override
Definition GenericJoint.hpp:1120
Matrix mInvProjArtInertia
Inverse of projected articulated inertia.
Definition GenericJoint.hpp:713
void setForceLowerLimit(size_t index, double force) override
Definition GenericJoint.hpp:1213
void setSpringStiffness(std::size_t index, double k) override
Definition GenericJoint.hpp:1433
void updateRelativePrimaryAcceleration() const override
Definition GenericJoint.hpp:1671
void setProperties(const Properties &properties)
Set the Properties of this GenericJoint.
Definition GenericJoint.hpp:97
double getForceLowerLimit(std::size_t index) const override
Definition GenericJoint.hpp:1226
static constexpr std::size_t NumDofs
Definition GenericJoint.hpp:51
const Vector & getVelocitiesStatic() const
Fixed-size version of getVelocities()
Definition GenericJoint.hpp:752
double getPositionUpperLimit(std::size_t index) const override
Definition GenericJoint.hpp:605
const std::string & getDofName(size_t index) const override
Definition GenericJoint.hpp:276
double computePotentialEnergy() const override
Definition GenericJoint.hpp:1544
double getSpringStiffness(std::size_t index) const override
Definition GenericJoint.hpp:1448
void setDampingCoefficient(std::size_t index, double coeff) override
Definition GenericJoint.hpp:1487
void updateInvProjArtInertia(const Eigen::Matrix6d &artInertia) override
Definition GenericJoint.hpp:1851
void resetVelocity(std::size_t index) override
Definition GenericJoint.hpp:932
JacobianMatrix mJacobianDeriv
Time derivative of spatial Jacobian expressed in the child body frame.
Definition GenericJoint.hpp:708
void setPositionsStatic(const Vector &positions)
Fixed-size version of setPositions()
Definition GenericJoint.hpp:721
void addChildBiasForceForInvAugMassMatrix(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce) override
Definition GenericJoint.hpp:2471
void updateConstrainedTermsKinematic(double timeStep)
Definition GenericJoint.hpp:2443
void setAccelerationLowerLimits(const Eigen::VectorXd &lowerLimits) override
Definition GenericJoint.hpp:1086
void setAspectProperties(const AspectProperties &properties)
Set the AspectProperties of this GenericJoint.
Definition GenericJoint.hpp:124
Eigen::VectorXd getForceUpperLimits() const override
Definition GenericJoint.hpp:1300
void updateImpulseFD(const Eigen::Vector6d &bodyImpulse) override
Definition GenericJoint.hpp:2384
void updateInvProjArtInertiaImplicitDynamic(const Eigen::Matrix6d &artInertia, double timeStep)
Definition GenericJoint.hpp:1923
void updateTotalForceKinematic(const Eigen::Vector6d &bodyForce, double timeStep)
Definition GenericJoint.hpp:2161
void resetTotalImpulses() override
Definition GenericJoint.hpp:2211
void integratePositions(double dt) override
Definition GenericJoint.hpp:1385
void setPositions(const Eigen::VectorXd &positions) override
Definition GenericJoint.hpp:523
void addChildBiasForceToDynamic(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce, const Eigen::Vector6d &childPartialAcc)
Definition GenericJoint.hpp:1981
Eigen::VectorXd getForceLowerLimits() const override
Definition GenericJoint.hpp:1253
double getInitialVelocity(std::size_t index) const override
Definition GenericJoint.hpp:966
Eigen::VectorXd getAccelerations() const override
Definition GenericJoint.hpp:1052
typename ConfigSpaceT::Vector Vector
Definition GenericJoint.hpp:58
void updateVelocityChangeKinematic(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &velocityChange)
Definition GenericJoint.hpp:2307
const Vector & getAccelerationsStatic() const
Fixed-size version of getAccelerations()
Definition GenericJoint.hpp:771
Eigen::VectorXd getInitialVelocities() const override
Definition GenericJoint.hpp:993
void setCommands(const Eigen::VectorXd &commands) override
Definition GenericJoint.hpp:402
Eigen::VectorXd getSpatialToGeneralized(const Eigen::Vector6d &spatial) override
Definition GenericJoint.hpp:2559
typename ConfigSpaceT::JacobianMatrix JacobianMatrix
Definition GenericJoint.hpp:59
void getInvAugMassMatrixSegment(Eigen::MatrixXd &invMassMat, const size_t col, const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) override
Definition GenericJoint.hpp:2526
double getVelocityLowerLimit(std::size_t index) const override
Definition GenericJoint.hpp:850
void updateImpulseID(const Eigen::Vector6d &bodyImpulse) override
Definition GenericJoint.hpp:2376
void setVelocityLowerLimit(std::size_t index, double velocity) override
Definition GenericJoint.hpp:836
double getInitialPosition(std::size_t index) const override
Definition GenericJoint.hpp:687
void updateAcceleration(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) override
Definition GenericJoint.hpp:2218
Vector mInvMassMatrixSegment
Definition GenericJoint.hpp:736
void addChildBiasForceToKinematic(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce, const Eigen::Vector6d &childPartialAcc)
Definition GenericJoint.hpp:2011
void setVelocityUpperLimit(std::size_t index, double velocity) override
Definition GenericJoint.hpp:884
typename ConfigSpaceT::Point Point
Definition GenericJoint.hpp:56
void updateInvProjArtInertiaKinematic(const Eigen::Matrix6d &artInertia)
Definition GenericJoint.hpp:1891
bool hasPositionLimit(std::size_t index) const override
Definition GenericJoint.hpp:639
JacobianMatrix mJacobian
Spatial Jacobian expressed in the child body frame.
Definition GenericJoint.hpp:702
void setInitialPositions(const Eigen::VectorXd &initial) override
Definition GenericJoint.hpp:700
void addChildBiasForceTo(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce, const Eigen::Vector6d &childPartialAcc) override
Definition GenericJoint.hpp:1952
double getCoulombFriction(std::size_t index) const override
Definition GenericJoint.hpp:1531
void addInvMassMatrixSegmentTo(Eigen::Vector6d &acc) override
Definition GenericJoint.hpp:2551
Vector mImpulses
Generalized impulse.
Definition GenericJoint.hpp:689
void setConstraintImpulse(std::size_t index, double impulse) override
Definition GenericJoint.hpp:1351
void resetPosition(std::size_t index) override
Definition GenericJoint.hpp:653
double getForceUpperLimit(size_t index) const override
Definition GenericJoint.hpp:1273
void registerDofs() override
Definition GenericJoint.hpp:1632
void addVelocityChangeTo(Eigen::Vector6d &velocityChange) override
Definition GenericJoint.hpp:1715
const std::string & setDofName(std::size_t index, const std::string &name, bool preserveName=true) override
Definition GenericJoint.hpp:218
void setAccelerationUpperLimit(std::size_t index, double acceleration) override
Definition GenericJoint.hpp:1107
double getDampingCoefficient(std::size_t index) const override
Definition GenericJoint.hpp:1502
typename Base::AspectProperties AspectProperties
Definition GenericJoint.hpp:65
Matrix mInvProjArtInertiaImplicit
Inverse of projected articulated inertia for implicit joint damping and spring forces.
Definition GenericJoint.hpp:720
void setPositionUpperLimits(const Eigen::VectorXd &upperLimits) override
Definition GenericJoint.hpp:618
Eigen::VectorXd getAccelerationLowerLimits() const override
Definition GenericJoint.hpp:1100
void updateTotalForceDynamic(const Eigen::Vector6d &bodyForce, double timeStep)
Definition GenericJoint.hpp:2140
void setVelocitiesStatic(const Vector &velocities)
Fixed-size version of setVelocities()
Definition GenericJoint.hpp:740
void updateRelativeSpatialAcceleration() const override
Definition GenericJoint.hpp:1662
void updateRelativeSpatialVelocity() const override
Definition GenericJoint.hpp:1654
void setForceUpperLimit(size_t index, double force) override
Definition GenericJoint.hpp:1260
size_t getIndexInTree(size_t index) const override
Definition GenericJoint.hpp:306
Eigen::VectorXd getVelocityUpperLimits() const override
Definition GenericJoint.hpp:925
void setAccelerationLowerLimit(size_t index, double acceleration) override
Definition GenericJoint.hpp:1059
double getPosition(std::size_t index) const override
Definition GenericJoint.hpp:510
void addChildArtInertiaImplicitToDynamic(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia)
Definition GenericJoint.hpp:1823
double getAccelerationLowerLimit(std::size_t index) const override
Definition GenericJoint.hpp:1073
void addChildBiasImpulseTo(Eigen::Vector6d &parentBiasImpulse, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasImpulse) override
Definition GenericJoint.hpp:2040
double getPositionLowerLimit(std::size_t index) const override
Definition GenericJoint.hpp:557
void updateAccelerationDynamic(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc)
Definition GenericJoint.hpp:2242
void resetPositions() override
Definition GenericJoint.hpp:666
void addChildBiasForceForInvMassMatrix(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce) override
Definition GenericJoint.hpp:2451
void getInvMassMatrixSegment(Eigen::MatrixXd &invMassMat, const size_t col, const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) override
Definition GenericJoint.hpp:2501
typename ConfigSpaceT::EuclideanPoint EuclideanPoint
Definition GenericJoint.hpp:57
Properties getGenericJointProperties() const
Get the Properties of this GenericJoint.
Definition GenericJoint.hpp:150
const Matrix & getInvProjArtInertia() const
Get the inverse of the projected articulated inertia.
Definition GenericJoint.hpp:1728
void setForces(const Eigen::VectorXd &forces) override
Definition GenericJoint.hpp:1190
void updateTotalForceForInvMassMatrix(const Eigen::Vector6d &bodyForce) override
Definition GenericJoint.hpp:2491
void resetAccelerations() override
Definition GenericJoint.hpp:1154
void setAcceleration(std::size_t index, double acceleration) override
Definition GenericJoint.hpp:1000
void addChildArtInertiaToKinematic(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia)
Definition GenericJoint.hpp:1788
double getConstraintImpulse(std::size_t index) const override
Definition GenericJoint.hpp:1365
size_t getIndexInSkeleton(size_t index) const override
Definition GenericJoint.hpp:293
void resetVelocityChanges() override
Definition GenericJoint.hpp:1344
#define DART_BAKE_SPECIALIZED_ASPECT_IRREGULAR(TypeName, AspectName)
Definition Composite.hpp:164
Definition Random-impl.hpp:92
Definition BulletCollisionDetector.cpp:60
Definition SharedLibraryManager.hpp:46
Definition GenericJointAspect.hpp:191
Definition GenericJointAspect.hpp:88