DART
6.10.1
|
#include <BallJoint.hpp>
Classes | |
struct | Properties |
Public Types | |
using | Base = GenericJoint< math::SO3Space > |
using | ThisClass = GenericJoint< math::SO3Space > |
using | Point = typename ConfigSpaceT::Point |
using | EuclideanPoint = typename ConfigSpaceT::EuclideanPoint |
using | Vector = typename ConfigSpaceT::Vector |
using | JacobianMatrix = typename ConfigSpaceT::JacobianMatrix |
using | Matrix = typename ConfigSpaceT::Matrix |
using | UniqueProperties = detail::GenericJointUniqueProperties< math::SO3Space > |
using | Properties = detail::GenericJointProperties< math::SO3Space > |
using | AspectState = typename Base::AspectState |
using | AspectProperties = typename Base::AspectProperties |
using | Impl = EmbedStateAndProperties< DerivedT, StateDataT, PropertiesDataT > |
using | Derived = typename Impl::Derived |
using | AspectStateData = typename Impl::AspectStateData |
using | AspectPropertiesData = typename Impl::AspectPropertiesData |
using | Aspect = typename Impl::Aspect |
Public Member Functions | |
virtual | ~BallJoint () |
Destructor. More... | |
const std::string & | getType () const override |
bool | isCyclic (std::size_t _index) const override |
Properties | getBallJointProperties () const |
Get the Properties of this BallJoint. More... | |
Eigen::Matrix< double, 6, 3 > | getRelativeJacobianStatic (const Eigen::Vector3d &_positions) const override |
Eigen::Vector3d | getPositionDifferencesStatic (const Eigen::Vector3d &_q2, const Eigen::Vector3d &_q1) const override |
bool | hasGenericJointAspect () const |
Check if this Composite currently has GenericJointAspect . More... | |
ThisClass::Aspect * | getGenericJointAspect () |
Get a(an) GenericJointAspect from this Composite. More... | |
const ThisClass::Aspect * | getGenericJointAspect () const |
Get a(an) GenericJointAspect from this Composite. More... | |
ThisClass::Aspect * | getGenericJointAspect (const bool createIfNull) |
Get a(an) GenericJointAspect from this Composite. More... | |
void | setGenericJointAspect (const typename ThisClass::Aspect *aspect) |
Make a clone of GenericJointAspect and place the clone into this Composite. More... | |
void | setGenericJointAspect (std::unique_ptr< typename ThisClass::Aspect > &&aspect) |
Use move semantics to place GenericJointAspect into this Composite. More... | |
ThisClass::Aspect * | createGenericJointAspect (Args &&... args) |
Construct a(an) GenericJointAspect inside of this Composite. More... | |
void | removeGenericJointAspect () |
Remove a(an) GenericJointAspect from this Composite. More... | |
std::unique_ptr< typename ThisClass::Aspect > | releaseGenericJointAspect () |
Remove a(an) GenericJointAspect from this Composite, but return its unique_ptr instead of letting it be deleted. More... | |
void | setProperties (const Properties &properties) |
Set the Properties of this GenericJoint. More... | |
void | setProperties (const UniqueProperties &properties) |
Set the Properties of this GenericJoint. More... | |
void | setAspectState (const AspectState &state) |
Set the AspectState of this GenericJoint. More... | |
void | setAspectProperties (const AspectProperties &properties) |
Set the AspectProperties of this GenericJoint. More... | |
Properties | getGenericJointProperties () const |
Get the Properties of this GenericJoint. More... | |
void | copy (const ThisClass &otherJoint) |
Copy the Properties of another GenericJoint. More... | |
void | copy (const ThisClass *otherJoint) |
Copy the Properties of another GenericJoint. More... | |
Eigen::Vector6d | getBodyConstraintWrench () const override |
const AspectProperties & | getAspectProperties () const |
const AspectState & | getAspectState () const |
Interface for generalized coordinates | |
DegreeOfFreedom * | getDof (std::size_t index) override |
const DegreeOfFreedom * | getDof (std::size_t _index) const override |
std::size_t | getNumDofs () const override |
const std::string & | setDofName (std::size_t index, const std::string &name, bool preserveName=true) override |
void | preserveDofName (size_t index, bool preserve) override |
bool | isDofNamePreserved (size_t index) const override |
const std::string & | getDofName (size_t index) const override |
size_t | getIndexInSkeleton (size_t index) const override |
size_t | getIndexInTree (size_t index) const override |
Command | |
void | setCommand (std::size_t index, double command) override |
double | getCommand (std::size_t index) const override |
void | setCommands (const Eigen::VectorXd &commands) override |
Eigen::VectorXd | getCommands () const override |
void | resetCommands () override |
Position | |
void | setPosition (std::size_t index, double position) override |
double | getPosition (std::size_t index) const override |
void | setPositions (const Eigen::VectorXd &positions) override |
Eigen::VectorXd | getPositions () const override |
void | setPositionLowerLimit (std::size_t index, double position) override |
double | getPositionLowerLimit (std::size_t index) const override |
void | setPositionLowerLimits (const Eigen::VectorXd &lowerLimits) override |
Eigen::VectorXd | getPositionLowerLimits () const override |
void | setPositionUpperLimit (std::size_t index, double position) override |
double | getPositionUpperLimit (std::size_t index) const override |
void | setPositionUpperLimits (const Eigen::VectorXd &upperLimits) override |
Eigen::VectorXd | getPositionUpperLimits () const override |
bool | hasPositionLimit (std::size_t index) const override |
void | resetPosition (std::size_t index) override |
void | resetPositions () override |
void | setInitialPosition (std::size_t index, double initial) override |
double | getInitialPosition (std::size_t index) const override |
void | setInitialPositions (const Eigen::VectorXd &initial) override |
Eigen::VectorXd | getInitialPositions () const override |
Fixed-size mutators and accessors | |
void | setPositionsStatic (const Vector &positions) |
Fixed-size version of setPositions() More... | |
const Vector & | getPositionsStatic () const |
Fixed-size version of getPositions() More... | |
void | setVelocitiesStatic (const Vector &velocities) |
Fixed-size version of setVelocities() More... | |
const Vector & | getVelocitiesStatic () const |
Fixed-size version of getVelocities() More... | |
void | setAccelerationsStatic (const Vector &accels) |
Fixed-size version of setAccelerations() More... | |
const Vector & | getAccelerationsStatic () const |
Fixed-size version of getAccelerations() More... | |
Velocity | |
void | setVelocity (std::size_t index, double velocity) override |
double | getVelocity (std::size_t index) const override |
void | setVelocities (const Eigen::VectorXd &velocities) override |
Eigen::VectorXd | getVelocities () const override |
void | setVelocityLowerLimit (std::size_t index, double velocity) override |
double | getVelocityLowerLimit (std::size_t index) const override |
void | setVelocityLowerLimits (const Eigen::VectorXd &lowerLimits) override |
Eigen::VectorXd | getVelocityLowerLimits () const override |
void | setVelocityUpperLimit (std::size_t index, double velocity) override |
double | getVelocityUpperLimit (std::size_t index) const override |
void | setVelocityUpperLimits (const Eigen::VectorXd &upperLimits) override |
Eigen::VectorXd | getVelocityUpperLimits () const override |
void | resetVelocity (std::size_t index) override |
void | resetVelocities () override |
void | setInitialVelocity (std::size_t index, double initial) override |
double | getInitialVelocity (std::size_t index) const override |
void | setInitialVelocities (const Eigen::VectorXd &initial) override |
Eigen::VectorXd | getInitialVelocities () const override |
Acceleration | |
void | setAcceleration (std::size_t index, double acceleration) override |
double | getAcceleration (std::size_t index) const override |
void | setAccelerations (const Eigen::VectorXd &accelerations) override |
Eigen::VectorXd | getAccelerations () const override |
void | setAccelerationLowerLimit (size_t index, double acceleration) override |
double | getAccelerationLowerLimit (std::size_t index) const override |
void | setAccelerationLowerLimits (const Eigen::VectorXd &lowerLimits) override |
Eigen::VectorXd | getAccelerationLowerLimits () const override |
void | setAccelerationUpperLimit (std::size_t index, double acceleration) override |
double | getAccelerationUpperLimit (std::size_t index) const override |
void | setAccelerationUpperLimits (const Eigen::VectorXd &upperLimits) override |
Eigen::VectorXd | getAccelerationUpperLimits () const override |
void | resetAccelerations () override |
Force | |
void | setForce (std::size_t index, double force) override |
double | getForce (std::size_t index) const override |
void | setForces (const Eigen::VectorXd &forces) override |
Eigen::VectorXd | getForces () const override |
void | setForceLowerLimit (size_t index, double force) override |
double | getForceLowerLimit (std::size_t index) const override |
void | setForceLowerLimits (const Eigen::VectorXd &lowerLimits) override |
Eigen::VectorXd | getForceLowerLimits () const override |
void | setForceUpperLimit (size_t index, double force) override |
double | getForceUpperLimit (size_t index) const override |
void | setForceUpperLimits (const Eigen::VectorXd &upperLimits) override |
Eigen::VectorXd | getForceUpperLimits () const override |
void | resetForces () override |
Velocity change | |
void | setVelocityChange (std::size_t index, double velocityChange) override |
double | getVelocityChange (std::size_t index) const override |
void | resetVelocityChanges () override |
Constraint impulse | |
void | setConstraintImpulse (std::size_t index, double impulse) override |
double | getConstraintImpulse (std::size_t index) const override |
void | resetConstraintImpulses () override |
Integration and finite difference | |
void | integrateVelocities (double dt) override |
Eigen::VectorXd | getPositionDifferences (const Eigen::VectorXd &q2, const Eigen::VectorXd &q1) const override |
virtual Vector | getPositionDifferencesStatic (const Vector &q2, const Vector &q1) const |
Fixed-size version of getPositionDifferences() More... | |
Passive forces - spring, viscous friction, Coulomb friction | |
void | setSpringStiffness (std::size_t index, double k) override |
double | getSpringStiffness (std::size_t index) const override |
void | setRestPosition (std::size_t index, double q0) override |
double | getRestPosition (std::size_t index) const override |
void | setDampingCoefficient (std::size_t index, double coeff) override |
double | getDampingCoefficient (std::size_t index) const override |
void | setCoulombFriction (std::size_t index, double friction) override |
double | getCoulombFriction (std::size_t index) const override |
Energy | |
double | computePotentialEnergy () const override |
Jacobians | |
const math::Jacobian | getRelativeJacobian () const override |
math::Jacobian | getRelativeJacobian (const Eigen::VectorXd &_positions) const override |
const GenericJoint< math::SO3Space >::JacobianMatrix & | getRelativeJacobianStatic () const |
Fixed-size version of getRelativeJacobian() More... | |
virtual JacobianMatrix | getRelativeJacobianStatic (const Vector &positions) const=0 |
Fixed-size version of getRelativeJacobian(positions) More... | |
const math::Jacobian | getRelativeJacobianTimeDeriv () const override |
const JacobianMatrix & | getRelativeJacobianTimeDerivStatic () const |
Fixed-size version of getRelativeJacobianTimeDeriv() More... | |
Static Public Member Functions | |
static const std::string & | getStaticType () |
Get joint type for this class. More... | |
template<typename RotationType > | |
static Eigen::Vector3d | convertToPositions (const RotationType &_rotation) |
Convert a rotation into a 3D vector that can be used to set the positions of a BallJoint. More... | |
static Eigen::Isometry3d | convertToTransform (const Eigen::Vector3d &_positions) |
Convert a BallJoint-style position vector into a transform. More... | |
static Eigen::Matrix3d | convertToRotation (const Eigen::Vector3d &_positions) |
Convert a BallJoint-style position vector into a rotation matrix. More... | |
Static Public Attributes | |
static constexpr std::size_t | NumDofs |
Protected Member Functions | |
BallJoint (const Properties &properties) | |
Constructor called by Skeleton class. More... | |
Joint * | clone () const override |
void | integratePositions (double _dt) override |
void | updateDegreeOfFreedomNames () override |
void | updateRelativeTransform () const override |
void | updateRelativeJacobian (bool _mandatory=true) const override |
void | updateRelativeJacobianTimeDeriv () const override |
const Eigen::Isometry3d & | getR () const |
Access mR, which is an auto-updating variable. More... | |
void | registerDofs () override |
Recursive algorithm routines for equations of motion | |
void | addChildBiasForceForInvMassMatrix (Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce) override |
void | addChildBiasForceForInvAugMassMatrix (Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce) override |
void | updateTotalForceForInvMassMatrix (const Eigen::Vector6d &bodyForce) override |
void | getInvMassMatrixSegment (Eigen::MatrixXd &invMassMat, const size_t col, const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) override |
void | getInvAugMassMatrixSegment (Eigen::MatrixXd &invMassMat, const size_t col, const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) override |
void | addInvMassMatrixSegmentTo (Eigen::Vector6d &acc) override |
Eigen::VectorXd | getSpatialToGeneralized (const Eigen::Vector6d &spatial) override |
Protected Attributes | |
Eigen::Isometry3d | mR |
Rotation matrix dependent on the generalized coordinates. More... | |
std::array< DegreeOfFreedom *, NumDofs > | mDofs |
Array of DegreeOfFreedom objects. More... | |
Vector | mVelocityChanges |
Change of generalized velocity. More... | |
Vector | mImpulses |
Generalized impulse. More... | |
Vector | mConstraintImpulses |
Generalized constraint impulse. More... | |
JacobianMatrix | mJacobian |
Spatial Jacobian expressed in the child body frame. More... | |
JacobianMatrix | mJacobianDeriv |
Time derivative of spatial Jacobian expressed in the child body frame. More... | |
Matrix | mInvProjArtInertia |
Inverse of projected articulated inertia. More... | |
Matrix | mInvProjArtInertiaImplicit |
Inverse of projected articulated inertia for implicit joint damping and spring forces. More... | |
Vector | mTotalForce |
Total force projected on joint space. More... | |
Vector | mTotalImpulse |
Total impluse projected on joint space. More... | |
Vector | mInvM_a |
Vector | mInvMassMatrixSegment |
AspectProperties | mAspectProperties |
Aspect::Properties data, directly accessible to your derived class. More... | |
AspectState | mAspectState |
Aspect::State data, directly accessible to your derived class. More... | |
Friends | |
class | Skeleton |
Recursive dynamics routines | |
const Matrix & | getInvProjArtInertia () const |
Get the inverse of the projected articulated inertia. More... | |
const Matrix & | getInvProjArtInertiaImplicit () const |
Get the inverse of projected articulated inertia for implicit joint damping and spring forces. More... | |
void | updateRelativeSpatialVelocity () const override |
void | updateRelativeSpatialAcceleration () const override |
void | updateRelativePrimaryAcceleration () const override |
void | addVelocityTo (Eigen::Vector6d &vel) override |
void | setPartialAccelerationTo (Eigen::Vector6d &partialAcceleration, const Eigen::Vector6d &childVelocity) override |
void | addAccelerationTo (Eigen::Vector6d &acc) override |
void | addVelocityChangeTo (Eigen::Vector6d &velocityChange) override |
void | addChildArtInertiaTo (Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia) override |
void | addChildArtInertiaImplicitTo (Eigen::Matrix6d &parentArtInertiaImplicit, const Eigen::Matrix6d &childArtInertiaImplicit) override |
void | updateInvProjArtInertia (const Eigen::Matrix6d &artInertia) override |
void | updateInvProjArtInertiaImplicit (const Eigen::Matrix6d &artInertia, double timeStep) override |
void | addChildBiasForceTo (Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce, const Eigen::Vector6d &childPartialAcc) override |
void | addChildBiasImpulseTo (Eigen::Vector6d &parentBiasImpulse, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasImpulse) override |
void | updateTotalForce (const Eigen::Vector6d &bodyForce, double timeStep) override |
void | updateTotalImpulse (const Eigen::Vector6d &bodyImpulse) override |
void | resetTotalImpulses () override |
void | updateAcceleration (const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) override |
void | updateVelocityChange (const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &velocityChange) override |
void | updateForceID (const Eigen::Vector6d &bodyForce, double timeStep, bool withDampingForces, bool withSpringForces) override |
void | updateForceFD (const Eigen::Vector6d &bodyForce, double timeStep, bool withDampingForcese, bool withSpringForces) override |
void | updateImpulseID (const Eigen::Vector6d &bodyImpulse) override |
void | updateImpulseFD (const Eigen::Vector6d &bodyImpulse) override |
void | updateConstrainedTerms (double timeStep) override |
void | addChildArtInertiaToDynamic (Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia) |
void | addChildArtInertiaToKinematic (Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia) |
void | addChildArtInertiaImplicitToDynamic (Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia) |
void | addChildArtInertiaImplicitToKinematic (Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia) |
void | updateInvProjArtInertiaDynamic (const Eigen::Matrix6d &artInertia) |
void | updateInvProjArtInertiaKinematic (const Eigen::Matrix6d &artInertia) |
void | updateInvProjArtInertiaImplicitDynamic (const Eigen::Matrix6d &artInertia, double timeStep) |
void | updateInvProjArtInertiaImplicitKinematic (const Eigen::Matrix6d &artInertia, double timeStep) |
void | addChildBiasForceToDynamic (Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce, const Eigen::Vector6d &childPartialAcc) |
void | addChildBiasForceToKinematic (Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce, const Eigen::Vector6d &childPartialAcc) |
void | addChildBiasImpulseToDynamic (Eigen::Vector6d &parentBiasImpulse, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasImpulse) |
void | addChildBiasImpulseToKinematic (Eigen::Vector6d &parentBiasImpulse, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasImpulse) |
void | updateTotalForceDynamic (const Eigen::Vector6d &bodyForce, double timeStep) |
void | updateTotalForceKinematic (const Eigen::Vector6d &bodyForce, double timeStep) |
void | updateTotalImpulseDynamic (const Eigen::Vector6d &bodyImpulse) |
void | updateTotalImpulseKinematic (const Eigen::Vector6d &bodyImpulse) |
void | updateAccelerationDynamic (const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) |
void | updateAccelerationKinematic (const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) |
void | updateVelocityChangeDynamic (const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &velocityChange) |
void | updateVelocityChangeKinematic (const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &velocityChange) |
void | updateConstrainedTermsDynamic (double timeStep) |
void | updateConstrainedTermsKinematic (double timeStep) |
class BallJoint
|
inherited |
|
inherited |
|
inherited |
|
inherited |
|
inherited |
|
inherited |
|
inherited |
|
inherited |
|
inherited |
|
inherited |
|
inherited |
|
inherited |
|
inherited |
|
inherited |
|
inherited |
|
virtual |
Destructor.
|
protected |
Constructor called by Skeleton class.
|
overrideprotectedinherited |
|
overrideprotectedinherited |
|
privateinherited |
|
privateinherited |
|
overrideprotectedinherited |
|
privateinherited |
|
privateinherited |
|
overrideprotectedinherited |
|
overrideprotectedinherited |
|
overrideprotectedinherited |
|
privateinherited |
|
privateinherited |
|
overrideprotectedinherited |
|
privateinherited |
|
privateinherited |
|
overrideprotectedinherited |
|
overrideprotectedinherited |
|
overrideprotectedinherited |
|
overrideprotected |
|
overrideinherited |
|
inlinestatic |
Convert a rotation into a 3D vector that can be used to set the positions of a BallJoint.
The positions returned by this function will result in a relative transform of getTransformFromParentBodyNode() * _rotation * getTransformFromChildBodyNode().inverse() between the parent BodyNode and the child BodyNode frames when applied to a BallJoint.
|
static |
Convert a BallJoint-style position vector into a rotation matrix.
|
static |
Convert a BallJoint-style position vector into a transform.
|
inherited |
Copy the Properties of another GenericJoint.
|
inherited |
Copy the Properties of another GenericJoint.
|
inlineinherited |
Construct a(an) GenericJointAspect inside of this Composite.
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
inherited |
Fixed-size version of getAccelerations()
|
overrideinherited |
|
overrideinherited |
|
inlineinherited |
|
inlineinherited |
BallJoint::Properties dart::dynamics::BallJoint::getBallJointProperties | ( | ) | const |
Get the Properties of this BallJoint.
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
inlineinherited |
Get a(an) GenericJointAspect from this Composite.
|
inlineinherited |
Get a(an) GenericJointAspect from this Composite.
|
inlineinherited |
Get a(an) GenericJointAspect from this Composite.
If _createIfNull is true, then a(an) GenericJointAspect will be generated if one does not already exist.
|
inherited |
Get the Properties of this GenericJoint.
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideprotectedinherited |
|
overrideprotectedinherited |
|
protectedinherited |
Get the inverse of the projected articulated inertia.
|
protectedinherited |
Get the inverse of projected articulated inertia for implicit joint damping and spring forces.
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
override |
|
virtualinherited |
Fixed-size version of getPositionDifferences()
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
inherited |
Fixed-size version of getPositions()
|
overrideinherited |
|
overrideinherited |
|
protected |
Access mR, which is an auto-updating variable.
|
overrideinherited |
|
overrideinherited |
|
inherited |
Fixed-size version of getRelativeJacobian()
|
override |
|
pure virtualinherited |
Fixed-size version of getRelativeJacobian(positions)
|
overrideinherited |
|
inherited |
Fixed-size version of getRelativeJacobianTimeDeriv()
|
overrideinherited |
|
overrideprotectedinherited |
|
overrideinherited |
|
static |
Get joint type for this class.
|
override |
|
overrideinherited |
|
inherited |
Fixed-size version of getVelocities()
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
inlineinherited |
Check if this Composite currently has GenericJointAspect .
|
overrideinherited |
|
overrideprotected |
|
overrideinherited |
|
override |
|
overrideinherited |
|
overrideinherited |
|
overrideprotectedinherited |
|
inlineinherited |
Remove a(an) GenericJointAspect from this Composite, but return its unique_ptr instead of letting it be deleted.
This allows you to safely use move semantics to transfer a(an) GenericJointAspect between two Composites.
|
inlineinherited |
Remove a(an) GenericJointAspect from this Composite.
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideprotectedinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
inherited |
Fixed-size version of setAccelerations()
|
overrideinherited |
|
overrideinherited |
|
inherited |
Set the AspectProperties of this GenericJoint.
|
inherited |
Set the AspectState of this GenericJoint.
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
inlineinherited |
Make a clone of GenericJointAspect and place the clone into this Composite.
If a(an) GenericJointAspect already exists in this Composite, the existing GenericJointAspect will be destroyed.
|
inlineinherited |
Use move semantics to place GenericJointAspect into this Composite.
If a(an) GenericJointAspect already exists in this Composite, the existing GenericJointAspect will be destroyed.
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideprotectedinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
inherited |
Fixed-size version of setPositions()
|
overrideinherited |
|
overrideinherited |
|
inherited |
Set the Properties of this GenericJoint.
|
inherited |
Set the Properties of this GenericJoint.
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
inherited |
Fixed-size version of setVelocities()
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideinherited |
|
overrideprotectedinherited |
|
privateinherited |
|
privateinherited |
|
overrideprotectedinherited |
|
privateinherited |
|
privateinherited |
|
overrideprotected |
|
overrideprotectedinherited |
|
overrideprotectedinherited |
|
overrideprotectedinherited |
|
overrideprotectedinherited |
|
overrideprotectedinherited |
|
privateinherited |
|
overrideprotectedinherited |
|
privateinherited |
|
privateinherited |
|
privateinherited |
|
overrideprotected |
|
overrideprotected |
|
overrideprotectedinherited |
|
overrideprotectedinherited |
|
overrideprotectedinherited |
|
overrideprotected |
|
overrideprotectedinherited |
|
privateinherited |
|
overrideprotectedinherited |
|
privateinherited |
|
overrideprotectedinherited |
|
privateinherited |
|
privateinherited |
|
overrideprotectedinherited |
|
privateinherited |
|
privateinherited |
|
friend |
|
protectedinherited |
Aspect::Properties data, directly accessible to your derived class.
|
protectedinherited |
Aspect::State data, directly accessible to your derived class.
|
protectedinherited |
Generalized constraint impulse.
|
protectedinherited |
Array of DegreeOfFreedom objects.
|
protectedinherited |
Generalized impulse.
|
protectedinherited |
|
protectedinherited |
|
mutableprotectedinherited |
Inverse of projected articulated inertia.
Do not use directly! Use getInvProjArtInertia() to get this quantity
|
mutableprotectedinherited |
Inverse of projected articulated inertia for implicit joint damping and spring forces.
Do not use directly! Use getInvProjArtInertiaImplicit() to access this quantity
|
mutableprotectedinherited |
Spatial Jacobian expressed in the child body frame.
Do not use directly! Use getRelativeJacobianStatic() to access this quantity
|
mutableprotectedinherited |
Time derivative of spatial Jacobian expressed in the child body frame.
Do not use directly! Use getRelativeJacobianTimeDerivStatic() to access this quantity
|
mutableprotected |
Rotation matrix dependent on the generalized coordinates.
Do not use directly! Use getR() to access this
|
protectedinherited |
Total force projected on joint space.
|
protectedinherited |
Total impluse projected on joint space.
|
protectedinherited |
Change of generalized velocity.
|
staticconstexprinherited |