DART 6.10.1
Loading...
Searching...
No Matches
Joint.hpp
Go to the documentation of this file.
1/*
2 * Copyright (c) 2011-2021, The DART development contributors
3 * All rights reserved.
4 *
5 * The list of contributors can be found at:
6 * https://github.com/dartsim/dart/blob/master/LICENSE
7 *
8 * This file is provided under the following "BSD-style" License:
9 * Redistribution and use in source and binary forms, with or
10 * without modification, are permitted provided that the following
11 * conditions are met:
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19 * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20 * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21 * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26 * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30 * POSSIBILITY OF SUCH DAMAGE.
31 */
32
33#ifndef DART_DYNAMICS_JOINT_HPP_
34#define DART_DYNAMICS_JOINT_HPP_
35
36#include <memory>
37#include <string>
38#include <vector>
39
47
48namespace dart {
49namespace dynamics {
50
51class BodyNode;
52class Skeleton;
53class DegreeOfFreedom;
54
57class Joint : public virtual common::Subject,
58 public virtual common::VersionCounter,
59 public common::EmbedProperties<Joint, detail::JointProperties>
60{
61public:
64
66 static constexpr ActuatorType FORCE = detail::FORCE;
68 static constexpr ActuatorType SERVO = detail::SERVO;
69 static constexpr ActuatorType MIMIC = detail::MIMIC;
73
75
77 {
80 const Properties& standardProperties = Properties(),
81 const CompositeProperties& aspectProperties = CompositeProperties());
82
85 Properties&& standardProperties,
86 CompositeProperties&& aspectProperties);
87
90 };
91
94
95 Joint(const Joint&) = delete;
96
98 virtual ~Joint();
99
102
105
107 const Properties& getJointProperties() const;
108
110 void copy(const Joint& _otherJoint);
111
113 void copy(const Joint* _otherJoint);
114
116 Joint& operator=(const Joint& _otherJoint);
117
125 const std::string& setName(const std::string& _name, bool _renameDofs = true);
126
128 const std::string& getName() const;
129
131 virtual const std::string& getType() const = 0;
132
134 void setActuatorType(ActuatorType _actuatorType);
135
138
140 void setMimicJoint(
141 const Joint* _mimicJoint,
142 double _mimicMultiplier = 1.0,
143 double _mimicOffset = 0.0);
144
146 const Joint* getMimicJoint() const;
147
149 double getMimicMultiplier() const;
150
152 double getMimicOffset() const;
153
160 bool isKinematic() const;
161
163 bool isDynamic() const;
164
167
169 const BodyNode* getChildBodyNode() const;
170
173
175 const BodyNode* getParentBodyNode() const;
176
179
181 std::shared_ptr<const Skeleton> getSkeleton() const;
182
184 virtual void setTransformFromParentBodyNode(const Eigen::Isometry3d& _T);
185
187 virtual void setTransformFromChildBodyNode(const Eigen::Isometry3d& _T);
188
190 const Eigen::Isometry3d& getTransformFromParentBodyNode() const;
191
193 const Eigen::Isometry3d& getTransformFromChildBodyNode() const;
194
204 DART_DEPRECATED(6.10)
205 void setPositionLimitEnforced(bool enforced);
206
213 void setLimitEnforcement(bool enforced);
214
224 DART_DEPRECATED(6.10)
225 bool isPositionLimitEnforced() const;
226
233 bool areLimitsEnforced() const;
234
236 virtual std::size_t getIndexInSkeleton(std::size_t _index) const = 0;
237
240 virtual std::size_t getIndexInTree(std::size_t _index) const = 0;
241
243 std::size_t getJointIndexInSkeleton() const;
244
246 std::size_t getJointIndexInTree() const;
247
249 std::size_t getTreeIndex() const;
250
253 virtual DegreeOfFreedom* getDof(std::size_t _index) = 0;
254
257 virtual const DegreeOfFreedom* getDof(std::size_t _index) const = 0;
258
260 virtual const std::string& setDofName(
261 std::size_t _index, const std::string& _name, bool _preserveName = true)
262 = 0;
263
265 virtual void preserveDofName(std::size_t _index, bool _preserve) = 0;
266
268 virtual bool isDofNamePreserved(std::size_t _index) const = 0;
269
271 virtual const std::string& getDofName(std::size_t _index) const = 0;
272
274 virtual std::size_t getNumDofs() const = 0;
275
276 //----------------------------------------------------------------------------
278 //----------------------------------------------------------------------------
279
281 virtual void setCommand(std::size_t _index, double _command) = 0;
282
284 virtual double getCommand(std::size_t _index) const = 0;
285
287 virtual void setCommands(const Eigen::VectorXd& _commands) = 0;
288
290 virtual Eigen::VectorXd getCommands() const = 0;
291
293 virtual void resetCommands() = 0;
294
296
297 //----------------------------------------------------------------------------
299 //----------------------------------------------------------------------------
300
302 virtual void setPosition(std::size_t _index, double _position) = 0;
303
305 virtual double getPosition(std::size_t _index) const = 0;
306
308 virtual void setPositions(const Eigen::VectorXd& _positions) = 0;
309
311 virtual Eigen::VectorXd getPositions() const = 0;
312
314 virtual void setPositionLowerLimit(std::size_t _index, double _position) = 0;
315
317 virtual double getPositionLowerLimit(std::size_t _index) const = 0;
318
320 virtual void setPositionLowerLimits(const Eigen::VectorXd& lowerLimits) = 0;
321
323 virtual Eigen::VectorXd getPositionLowerLimits() const = 0;
324
326 virtual void setPositionUpperLimit(std::size_t _index, double _position) = 0;
327
329 virtual double getPositionUpperLimit(std::size_t _index) const = 0;
330
332 virtual void setPositionUpperLimits(const Eigen::VectorXd& upperLimits) = 0;
333
335 virtual Eigen::VectorXd getPositionUpperLimits() const = 0;
336
342 virtual bool isCyclic(std::size_t _index) const = 0;
343
345 virtual bool hasPositionLimit(std::size_t _index) const = 0;
346
348 virtual void resetPosition(std::size_t _index) = 0;
349
352 virtual void resetPositions() = 0;
353
355 virtual void setInitialPosition(std::size_t _index, double _initial) = 0;
356
358 virtual double getInitialPosition(std::size_t _index) const = 0;
359
362 virtual void setInitialPositions(const Eigen::VectorXd& _initial) = 0;
363
366 virtual Eigen::VectorXd getInitialPositions() const = 0;
367
369
370 //----------------------------------------------------------------------------
372 //----------------------------------------------------------------------------
373
375 virtual void setVelocity(std::size_t _index, double _velocity) = 0;
376
378 virtual double getVelocity(std::size_t _index) const = 0;
379
381 virtual void setVelocities(const Eigen::VectorXd& _velocities) = 0;
382
384 virtual Eigen::VectorXd getVelocities() const = 0;
385
387 virtual void setVelocityLowerLimit(std::size_t _index, double _velocity) = 0;
388
390 virtual double getVelocityLowerLimit(std::size_t _index) const = 0;
391
393 virtual void setVelocityLowerLimits(const Eigen::VectorXd& lowerLimits) = 0;
394
396 virtual Eigen::VectorXd getVelocityLowerLimits() const = 0;
397
399 virtual void setVelocityUpperLimit(std::size_t _index, double _velocity) = 0;
400
402 virtual double getVelocityUpperLimit(std::size_t _index) const = 0;
403
405 virtual void setVelocityUpperLimits(const Eigen::VectorXd& upperLimits) = 0;
406
408 virtual Eigen::VectorXd getVelocityUpperLimits() const = 0;
409
412 virtual void resetVelocity(std::size_t _index) = 0;
413
416 virtual void resetVelocities() = 0;
417
419 virtual void setInitialVelocity(std::size_t _index, double _initial) = 0;
420
422 virtual double getInitialVelocity(std::size_t _index) const = 0;
423
426 virtual void setInitialVelocities(const Eigen::VectorXd& _initial) = 0;
427
430 virtual Eigen::VectorXd getInitialVelocities() const = 0;
431
433
434 //----------------------------------------------------------------------------
436 //----------------------------------------------------------------------------
437
439 virtual void setAcceleration(std::size_t _index, double _acceleration) = 0;
440
442 virtual double getAcceleration(std::size_t _index) const = 0;
443
445 virtual void setAccelerations(const Eigen::VectorXd& _accelerations) = 0;
446
448 virtual Eigen::VectorXd getAccelerations() const = 0;
449
451 virtual void resetAccelerations() = 0;
452
455 std::size_t _index, double _acceleration)
456 = 0;
457
459 virtual double getAccelerationLowerLimit(std::size_t _index) const = 0;
460
462 virtual void setAccelerationLowerLimits(const Eigen::VectorXd& lowerLimits)
463 = 0;
464
466 virtual Eigen::VectorXd getAccelerationLowerLimits() const = 0;
467
470 std::size_t _index, double _acceleration)
471 = 0;
472
474 virtual double getAccelerationUpperLimit(std::size_t _index) const = 0;
475
477 virtual void setAccelerationUpperLimits(const Eigen::VectorXd& upperLimits)
478 = 0;
479
481 virtual Eigen::VectorXd getAccelerationUpperLimits() const = 0;
482
484
485 //----------------------------------------------------------------------------
487 //----------------------------------------------------------------------------
488
490 virtual void setForce(std::size_t _index, double _force) = 0;
491
493 virtual double getForce(std::size_t _index) const = 0;
494
496 virtual void setForces(const Eigen::VectorXd& _forces) = 0;
497
499 virtual Eigen::VectorXd getForces() const = 0;
500
502 virtual void resetForces() = 0;
503
505 virtual void setForceLowerLimit(std::size_t _index, double _force) = 0;
506
508 virtual double getForceLowerLimit(std::size_t _index) const = 0;
509
511 virtual void setForceLowerLimits(const Eigen::VectorXd& lowerLimits) = 0;
512
514 virtual Eigen::VectorXd getForceLowerLimits() const = 0;
515
517 virtual void setForceUpperLimit(std::size_t _index, double _force) = 0;
518
520 virtual double getForceUpperLimit(std::size_t _index) const = 0;
521
523 virtual void setForceUpperLimits(const Eigen::VectorXd& upperLimits) = 0;
524
526 virtual Eigen::VectorXd getForceUpperLimits() const = 0;
527
529
530 //----------------------------------------------------------------------------
532 //----------------------------------------------------------------------------
533
536 // TODO: Consider extending this to a more comprehensive sanity check
537 bool checkSanity(bool _printWarnings = true) const;
538
539 //----------------------------------------------------------------------------
541 //----------------------------------------------------------------------------
542
544 virtual void setVelocityChange(std::size_t _index, double _velocityChange)
545 = 0;
546
548 virtual double getVelocityChange(std::size_t _index) const = 0;
549
551 virtual void resetVelocityChanges() = 0;
552
554
555 //----------------------------------------------------------------------------
557 //----------------------------------------------------------------------------
558
560 virtual void setConstraintImpulse(std::size_t _index, double _impulse) = 0;
561
563 virtual double getConstraintImpulse(std::size_t _index) const = 0;
564
566 virtual void resetConstraintImpulses() = 0;
567
569
570 //----------------------------------------------------------------------------
572 //----------------------------------------------------------------------------
573
575 virtual void integratePositions(double _dt) = 0;
576
578 virtual void integrateVelocities(double _dt) = 0;
579
582 virtual Eigen::VectorXd getPositionDifferences(
583 const Eigen::VectorXd& _q2, const Eigen::VectorXd& _q1) const = 0;
584
586
587 //----------------------------------------------------------------------------
589 //----------------------------------------------------------------------------
590
594 virtual void setSpringStiffness(std::size_t _index, double _k) = 0;
595
598 virtual double getSpringStiffness(std::size_t _index) const = 0;
599
603 virtual void setRestPosition(std::size_t _index, double _q0) = 0;
604
608 virtual double getRestPosition(std::size_t _index) const = 0;
609
613 virtual void setDampingCoefficient(std::size_t _index, double _coeff) = 0;
614
617 virtual double getDampingCoefficient(std::size_t _index) const = 0;
618
622 virtual void setCoulombFriction(std::size_t _index, double _friction) = 0;
623
626 virtual double getCoulombFriction(std::size_t _index) const = 0;
627
629
630 //----------------------------------------------------------------------------
631
633 DART_DEPRECATED(6.1)
634 double getPotentialEnergy() const;
635
637 virtual double computePotentialEnergy() const = 0;
638
639 //----------------------------------------------------------------------------
640
642 DART_DEPRECATED(6.0)
643 const Eigen::Isometry3d& getLocalTransform() const;
644
646 DART_DEPRECATED(6.0)
647 const Eigen::Vector6d& getLocalSpatialVelocity() const;
648
650 DART_DEPRECATED(6.0)
651 const Eigen::Vector6d& getLocalSpatialAcceleration() const;
652
654 DART_DEPRECATED(6.0)
655 const Eigen::Vector6d& getLocalPrimaryAcceleration() const;
656
658 DART_DEPRECATED(6.0)
659 const math::Jacobian getLocalJacobian() const;
660
662 DART_DEPRECATED(6.0)
663 math::Jacobian getLocalJacobian(const Eigen::VectorXd& positions) const;
664
666 DART_DEPRECATED(6.0)
667 const math::Jacobian getLocalJacobianTimeDeriv() const;
668
671 const Eigen::Isometry3d& getRelativeTransform() const;
672
675 const Eigen::Vector6d& getRelativeSpatialVelocity() const;
676
679 const Eigen::Vector6d& getRelativeSpatialAcceleration() const;
680
682 const Eigen::Vector6d& getRelativePrimaryAcceleration() const;
683
686 virtual const math::Jacobian getRelativeJacobian() const = 0;
687
690 virtual math::Jacobian getRelativeJacobian(
691 const Eigen::VectorXd& positions) const = 0;
692
695 virtual const math::Jacobian getRelativeJacobianTimeDeriv() const = 0;
696
698 virtual Eigen::Vector6d getBodyConstraintWrench() const = 0;
699 // TODO: Need more informative name.
700
714 // Eigen::VectorXd getSpringForces(double _timeStep) const;
715
726 // Eigen::VectorXd getDampingForces() const;
727
728 //----------------------------------------------------------------------------
730 //----------------------------------------------------------------------------
731
733 DART_DEPRECATED(6.2)
735
738
740 DART_DEPRECATED(6.2)
742
745
747 DART_DEPRECATED(6.2)
749
752
754
755 //----------------------------------------------------------------------------
756 // Friendship
757 //----------------------------------------------------------------------------
758
759 friend class BodyNode;
760 friend class SoftBodyNode;
761 friend class Skeleton;
762
763protected:
765 Joint();
766
769 virtual Joint* clone() const = 0;
770
772 virtual void registerDofs() = 0;
773
781 DegreeOfFreedom* createDofPointer(std::size_t _indexInJoint);
782
785 virtual void updateDegreeOfFreedomNames() = 0;
786
787 //----------------------------------------------------------------------------
789 //----------------------------------------------------------------------------
790
792 DART_DEPRECATED(6.0)
793 void updateLocalTransform() const;
794
796 DART_DEPRECATED(6.0)
797 void updateLocalSpatialVelocity() const;
798
800 DART_DEPRECATED(6.0)
802
804 DART_DEPRECATED(6.0)
806
808 DART_DEPRECATED(6.0)
809 void updateLocalJacobian(bool mandatory = true) const;
810
812 DART_DEPRECATED(6.0)
813 void updateLocalJacobianTimeDeriv() const;
814
817 virtual void updateRelativeTransform() const = 0;
818
821 virtual void updateRelativeSpatialVelocity() const = 0;
822
825 virtual void updateRelativeSpatialAcceleration() const = 0;
826
828 virtual void updateRelativePrimaryAcceleration() const = 0;
829
837 virtual void updateRelativeJacobian(bool mandatory = true) const = 0;
838
844 virtual void updateRelativeJacobianTimeDeriv() const = 0;
845
847 void updateArticulatedInertia() const;
848
850 virtual void addVelocityTo(Eigen::Vector6d& _vel) = 0;
851
854 Eigen::Vector6d& _partialAcceleration,
855 const Eigen::Vector6d& _childVelocity)
856 = 0;
857 // TODO(JS): Rename with more informative name
858
860 virtual void addAccelerationTo(Eigen::Vector6d& _acc) = 0;
861
863 virtual void addVelocityChangeTo(Eigen::Vector6d& _velocityChange) = 0;
864
867 Eigen::Matrix6d& _parentArtInertia,
868 const Eigen::Matrix6d& _childArtInertia)
869 = 0;
870
873 Eigen::Matrix6d& _parentArtInertiaImplicit,
874 const Eigen::Matrix6d& _childArtInertiaImplicit)
875 = 0;
876 // TODO(JS): rename to updateAInertiaChildAInertia()
877
879 virtual void updateInvProjArtInertia(const Eigen::Matrix6d& _artInertia) = 0;
880
883 const Eigen::Matrix6d& _artInertia, double _timeStep)
884 = 0;
885 // TODO(JS): rename to updateAInertiaPsi()
886
889 Eigen::Vector6d& _parentBiasForce,
890 const Eigen::Matrix6d& _childArtInertia,
891 const Eigen::Vector6d& _childBiasForce,
892 const Eigen::Vector6d& _childPartialAcc)
893 = 0;
894
897 Eigen::Vector6d& _parentBiasImpulse,
898 const Eigen::Matrix6d& _childArtInertia,
899 const Eigen::Vector6d& _childBiasImpulse)
900 = 0;
901
903 virtual void updateTotalForce(
904 const Eigen::Vector6d& _bodyForce, double _timeStep)
905 = 0;
906 // TODO: rename
907
909 virtual void updateTotalImpulse(const Eigen::Vector6d& _bodyImpulse) = 0;
910 // TODO: rename
911
913 virtual void resetTotalImpulses() = 0;
914
916 virtual void updateAcceleration(
917 const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc)
918 = 0;
919
924 const Eigen::Matrix6d& _artInertia,
925 const Eigen::Vector6d& _velocityChange)
926 = 0;
927
935 virtual void updateForceID(
936 const Eigen::Vector6d& _bodyForce,
937 double _timeStep,
938 bool _withDampingForces,
939 bool _withSpringForces)
940 = 0;
941
949 virtual void updateForceFD(
950 const Eigen::Vector6d& _bodyForce,
951 double _timeStep,
952 bool _withDampingForces,
953 bool _withSpringForces)
954 = 0;
955
957 virtual void updateImpulseID(const Eigen::Vector6d& _bodyImpulse) = 0;
958
960 virtual void updateImpulseFD(const Eigen::Vector6d& _bodyImpulse) = 0;
961
963 virtual void updateConstrainedTerms(double _timeStep) = 0;
964
966
967 //----------------------------------------------------------------------------
969 //----------------------------------------------------------------------------
970
973 Eigen::Vector6d& _parentBiasForce,
974 const Eigen::Matrix6d& _childArtInertia,
975 const Eigen::Vector6d& _childBiasForce)
976 = 0;
977
980 Eigen::Vector6d& _parentBiasForce,
981 const Eigen::Matrix6d& _childArtInertia,
982 const Eigen::Vector6d& _childBiasForce)
983 = 0;
984
987 const Eigen::Vector6d& _bodyForce)
988 = 0;
989
992 Eigen::MatrixXd& _invMassMat,
993 const std::size_t _col,
994 const Eigen::Matrix6d& _artInertia,
995 const Eigen::Vector6d& _spatialAcc)
996 = 0;
997
1000 Eigen::MatrixXd& _invMassMat,
1001 const std::size_t _col,
1002 const Eigen::Matrix6d& _artInertia,
1003 const Eigen::Vector6d& _spatialAcc)
1004 = 0;
1005
1007 virtual void addInvMassMatrixSegmentTo(Eigen::Vector6d& _acc) = 0;
1008
1011 const Eigen::Vector6d& _spatial)
1012 = 0;
1013
1015
1016protected:
1019
1024 mutable Eigen::Isometry3d mT;
1025
1030 mutable Eigen::Vector6d mSpatialVelocity;
1031
1036 mutable Eigen::Vector6d mSpatialAcceleration;
1037
1041 mutable Eigen::Vector6d mPrimaryAcceleration;
1042
1046 // TODO(JS): Rename this to mIsTransformDirty in DART 7
1047
1051 // TODO(JS): Rename this to mIsSpatialVelocityDirty in DART 7
1052
1056 // TODO(JS): Rename this to mIsSpatialAccelerationDirty in DART 7
1057
1061 // TODO(JS): Rename this to mIsPrimaryAccelerationDirty in DART 7
1062
1066
1070
1071public:
1072 // To get byte-aligned Eigen vectors
1073 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1074};
1076
1077} // namespace dynamics
1078} // namespace dart
1079
1080#endif // DART_DYNAMICS_JOINT_HPP_
#define DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_END
Definition ClassWithVirtualBase.hpp:44
#define DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN
Definition ClassWithVirtualBase.hpp:43
#define DART_DEPRECATED(version)
Definition Deprecated.hpp:51
BodyPropPtr properties
Definition SdfParser.cpp:80
detail::CompositeProperties Properties
Definition Composite.hpp:56
Inherit this class to embed Properties into your Composite object.
Definition EmbeddedAspect.hpp:204
typename Aspect::Properties AspectProperties
Definition EmbeddedAspect.hpp:208
This is the implementation of a standard embedded-properties Aspect.
Definition EmbeddedAspect.hpp:164
The Subject class is a base class for any object that wants to report when it gets destroyed.
Definition Subject.hpp:58
VersionCounter is an interface for objects that count their versions.
Definition VersionCounter.hpp:43
Definition CompositeData.hpp:107
BodyNode class represents a single node of the skeleton.
Definition BodyNode.hpp:79
DegreeOfFreedom class is a proxy class for accessing single degrees of freedom (aka generalized coord...
Definition DegreeOfFreedom.hpp:55
class Joint
Definition Joint.hpp:60
virtual void updateInvProjArtInertia(const Eigen::Matrix6d &_artInertia)=0
Update inverse of projected articulated body inertia.
virtual const std::string & getType() const =0
Gets a string representing the joint type.
bool mNeedSpatialAccelerationUpdate
True iff this joint's position, velocity, or acceleration has changed since the last call to getRelat...
Definition Joint.hpp:1055
virtual double getVelocityLowerLimit(std::size_t _index) const =0
Get lower limit for velocity.
virtual void updateForceID(const Eigen::Vector6d &_bodyForce, double _timeStep, bool _withDampingForces, bool _withSpringForces)=0
Update joint force for inverse dynamics.
virtual void updateTotalForceForInvMassMatrix(const Eigen::Vector6d &_bodyForce)=0
virtual double getDampingCoefficient(std::size_t _index) const =0
Get coefficient of joint damping (viscous friction) force.
virtual double getInitialPosition(std::size_t _index) const =0
Get the position that resetPosition() will give to this coordinate.
virtual void setTransformFromChildBodyNode(const Eigen::Isometry3d &_T)
Set transformation from child body node to this joint.
Definition Joint.cpp:498
virtual void updateImpulseFD(const Eigen::Vector6d &_bodyImpulse)=0
Update joint impulses for forward dynamics.
virtual Eigen::VectorXd getForces() const =0
Get the forces of all generalized coordinates in this Joint.
virtual Eigen::VectorXd getSpatialToGeneralized(const Eigen::Vector6d &_spatial)=0
virtual void updateTotalImpulse(const Eigen::Vector6d &_bodyImpulse)=0
Update joint total impulse.
virtual double getVelocityUpperLimit(std::size_t _index) const =0
Get upper limit for velocity.
void setActuatorType(ActuatorType _actuatorType)
Set actuator type.
Definition Joint.cpp:196
Eigen::Vector6d mPrimaryAcceleration
J * q_dd.
Definition Joint.hpp:1041
virtual double getAccelerationUpperLimit(std::size_t _index) const =0
Get upper limit for acceleration.
virtual void addChildBiasForceForInvMassMatrix(Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce)=0
Add child's bias force to parent's one.
virtual void setPositions(const Eigen::VectorXd &_positions)=0
Set the positions of all generalized coordinates in this Joint.
virtual void resetPosition(std::size_t _index)=0
Set the position of this generalized coordinate to its initial position.
virtual void setForceUpperLimit(std::size_t _index, double _force)=0
Set upper limit for force.
virtual void resetConstraintImpulses()=0
Set zero all the constraint impulses.
virtual std::size_t getNumDofs() const =0
Get number of generalized coordinates.
virtual void setCommand(std::size_t _index, double _command)=0
Set a single command.
const Eigen::Vector6d & getRelativePrimaryAcceleration() const
Get J * of this joint.
Definition Joint.cpp:380
detail::ActuatorType ActuatorType
Definition Joint.hpp:65
bool areLimitsEnforced() const
Returns whether enforcing joint position and velocity limits.
Definition Joint.cpp:410
virtual void resetAccelerations()=0
Set the accelerations of all generalized coordinates in this Joint to zero.
virtual double getForceUpperLimit(std::size_t _index) const =0
Get upper limit for force.
virtual void setInitialVelocity(std::size_t _index, double _initial)=0
Change the velocity that resetVelocity() will give to this coordinate.
virtual void updateInvProjArtInertiaImplicit(const Eigen::Matrix6d &_artInertia, double _timeStep)=0
Forward dynamics routine.
virtual void updateRelativeJacobianTimeDeriv() const =0
Update time derivative of spatial Jacobian of the child BodyNode relative to the parent BodyNode expr...
virtual void updateRelativeJacobian(bool mandatory=true) const =0
Update spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child ...
const Eigen::Vector6d & getLocalSpatialVelocity() const
Deprecated. Use getLocalSpatialVelocity() instead.
Definition Joint.cpp:308
bool mNeedPrimaryAccelerationUpdate
True iff this joint's position, velocity, or acceleration has changed since the last call to getRelat...
Definition Joint.hpp:1060
virtual Eigen::VectorXd getPositionUpperLimits() const =0
Get the position upper limits of all the generalized coordinates.
virtual double getConstraintImpulse(std::size_t _index) const =0
Get a single constraint impulse.
virtual void updateDegreeOfFreedomNames()=0
Update the names of the joint's degrees of freedom.
static constexpr ActuatorType PASSIVE
Definition Joint.hpp:67
virtual void setVelocity(std::size_t _index, double _velocity)=0
Set the velocity of a single generalized coordinate.
virtual double computePotentialEnergy() const =0
Compute and return the potential energy.
virtual void setForces(const Eigen::VectorXd &_forces)=0
Set the forces of all generalized coordinates in this Joint.
virtual void getInvAugMassMatrixSegment(Eigen::MatrixXd &_invMassMat, const std::size_t _col, const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc)=0
std::size_t getJointIndexInSkeleton() const
Get the index of this Joint within its Skeleton.
Definition Joint.cpp:416
virtual double getForceLowerLimit(std::size_t _index) const =0
Get lower limit for force.
virtual void setInitialVelocities(const Eigen::VectorXd &_initial)=0
Change the velocities that resetVelocities() will give to this Joint's coordinates.
virtual void resetVelocityChanges()=0
Set zero all the velocity change.
virtual void setAccelerationLowerLimit(std::size_t _index, double _acceleration)=0
Set lower limit for acceleration.
const std::string & getName() const
Get joint name.
Definition Joint.cpp:190
const Eigen::Vector6d & getLocalSpatialAcceleration() const
Deprecated. Use getLocalSpatialAcceleration() instead.
Definition Joint.cpp:314
bool mNeedSpatialVelocityUpdate
True iff this joint's position or velocity has changed since the last call to getRelativeSpatialVeloc...
Definition Joint.hpp:1050
bool checkSanity(bool _printWarnings=true) const
Returns false if the initial position or initial velocity are outside of limits.
Definition Joint.cpp:434
const Eigen::Isometry3d & getLocalTransform() const
Deprecated. Use getRelativeTransform() instead.
Definition Joint.cpp:302
virtual void setVelocityUpperLimits(const Eigen::VectorXd &upperLimits)=0
Set the velocity upper limits of all the generalized coordinates.
static constexpr ActuatorType SERVO
Definition Joint.hpp:68
virtual void integratePositions(double _dt)=0
Integrate positions using Euler method.
virtual void setForceUpperLimits(const Eigen::VectorXd &upperLimits)=0
Set the force upper limits of all the generalized coordinates.
virtual double getVelocityChange(std::size_t _index) const =0
Get a single velocity change.
virtual Eigen::VectorXd getPositionDifferences(const Eigen::VectorXd &_q2, const Eigen::VectorXd &_q1) const =0
Return the difference of two generalized coordinates which are measured in the configuration space of...
BodyNode * getParentBodyNode()
Get the parent BodyNode of this Joint.
Definition Joint.cpp:275
virtual double getSpringStiffness(std::size_t _index) const =0
Get stiffness of joint spring force.
static constexpr ActuatorType ACCELERATION
Definition Joint.hpp:70
Eigen::Vector6d mSpatialAcceleration
Relative spatial acceleration from parent BodyNode to child BodyNode where the acceleration is expres...
Definition Joint.hpp:1036
virtual void updateVelocityChange(const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_velocityChange)=0
Update joint velocity change.
virtual void addChildBiasImpulseTo(Eigen::Vector6d &_parentBiasImpulse, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasImpulse)=0
Add child's bias impulse to parent's one.
virtual void resetForces()=0
Set the forces of all generalized coordinates in this Joint to zero.
virtual void setTransformFromParentBodyNode(const Eigen::Isometry3d &_T)
Set transformation from parent body node to this joint.
Definition Joint.cpp:490
virtual double getVelocity(std::size_t _index) const =0
Get the velocity of a single generalized coordinate.
virtual double getAcceleration(std::size_t _index) const =0
Get the acceleration of a single generalized coordinate.
virtual void updateRelativeSpatialVelocity() const =0
Update spatial velocity of the child BodyNode relative to the parent BodyNode expressed in the child ...
void updateArticulatedInertia() const
Tells the Skeleton to update the articulated inertia if it needs updating.
Definition Joint.cpp:578
bool mNeedTransformUpdate
True iff this joint's position has changed since the last call to getRelativeTransform()
Definition Joint.hpp:1045
detail::JointProperties Properties
Definition Joint.hpp:63
DegreeOfFreedom * createDofPointer(std::size_t _indexInJoint)
Create a DegreeOfFreedom pointer.
Definition Joint.cpp:536
void updateLocalSpatialVelocity() const
Deprecated. Use updateRelativeSpatialVelocity() instead.
Definition Joint.cpp:548
void notifyAccelerationUpdate()
Notify that an acceleration has updated.
Definition Joint.cpp:667
static constexpr ActuatorType LOCKED
Definition Joint.hpp:72
virtual double getCommand(std::size_t _index) const =0
Get a single command.
void notifyVelocityUpdated()
Notify that a velocity has updated.
Definition Joint.cpp:652
void copy(const Joint &_otherJoint)
Copy the properties of another Joint.
Definition Joint.cpp:135
Eigen::Vector6d mSpatialVelocity
Relative spatial velocity from parent BodyNode to child BodyNode where the velocity is expressed in c...
Definition Joint.hpp:1030
void notifyPositionUpdate()
Notify that a position has updated.
Definition Joint.cpp:612
virtual void setPositionLowerLimit(std::size_t _index, double _position)=0
Set lower limit for position.
virtual void addAccelerationTo(Eigen::Vector6d &_acc)=0
Add joint acceleration to _acc.
virtual Joint * clone() const =0
Create a clone of this Joint.
virtual void preserveDofName(std::size_t _index, bool _preserve)=0
Alternative to DegreeOfFreedom::preserveName()
virtual Eigen::VectorXd getVelocityUpperLimits() const =0
Get the velocity upper limits of all the generalized coordinates.
virtual void setInitialPosition(std::size_t _index, double _initial)=0
Change the position that resetPositions() will give to this coordinate.
virtual Eigen::VectorXd getInitialVelocities() const =0
Get the velocities that resetVelocities() will give to this Joint's coordinates.
const std::string & setName(const std::string &_name, bool _renameDofs=true)
Set joint name and return the name.
Definition Joint.cpp:160
virtual Eigen::VectorXd getVelocityLowerLimits() const =0
Get the velocity lower limits of all the generalized coordinates.
virtual Eigen::VectorXd getInitialPositions() const =0
Get the positions that resetPositions() will give to this Joint's coordinates.
virtual void resetPositions()=0
Set the positions of all generalized coordinates in this Joint to their initial positions.
BodyNode * mChildBodyNode
Child BodyNode pointer that this Joint belongs to.
Definition Joint.hpp:1018
bool isKinematic() const
Return true if this joint is kinematic joint.
Definition Joint.cpp:235
void setAspectProperties(const AspectProperties &properties)
Set the AspectProperties of this Joint.
Definition Joint.cpp:115
const Properties & getJointProperties() const
Get the Properties of this Joint.
Definition Joint.cpp:129
virtual void updateForceFD(const Eigen::Vector6d &_bodyForce, double _timeStep, bool _withDampingForces, bool _withSpringForces)=0
Update joint force for forward dynamics.
virtual std::size_t getIndexInTree(std::size_t _index) const =0
Get a unique index in the kinematic tree of a generalized coordinate in this Joint.
virtual void setConstraintImpulse(std::size_t _index, double _impulse)=0
Set a single constraint impulse.
virtual Eigen::VectorXd getCommands() const =0
Get all commands for this Joint.
virtual void setForce(std::size_t _index, double _force)=0
Set the force of a single generalized coordinate.
ActuatorType getActuatorType() const
Get actuator type.
Definition Joint.cpp:202
virtual double getRestPosition(std::size_t _index) const =0
Get rest position of spring force.
virtual bool hasPositionLimit(std::size_t _index) const =0
Get whether the position of a generalized coordinate has limits.
const Eigen::Isometry3d & getRelativeTransform() const
Get transform of the child BodyNode relative to the parent BodyNode expressed in the child BodyNode f...
Definition Joint.cpp:344
virtual void setAccelerations(const Eigen::VectorXd &_accelerations)=0
Set the accelerations of all generalized coordinates in this Joint.
virtual void addInvMassMatrixSegmentTo(Eigen::Vector6d &_acc)=0
virtual void setVelocityLowerLimits(const Eigen::VectorXd &lowerLimits)=0
Set the velocity lower limits of all the generalized coordinates.
virtual const std::string & getDofName(std::size_t _index) const =0
Alternative to DegreeOfFreedom::getName()
const Eigen::Vector6d & getRelativeSpatialAcceleration() const
Get spatial acceleration of the child BodyNode relative to the parent BodyNode expressed in the child...
Definition Joint.cpp:368
void setPositionLimitEnforced(bool enforced)
Sets whether enforcing joint position and velocity limits.
Definition Joint.cpp:392
void notifyVelocityUpdate()
Notify that a velocity has updated.
Definition Joint.cpp:646
virtual void updateRelativePrimaryAcceleration() const =0
Update J * of this joint.
virtual void setPositionUpperLimit(std::size_t _index, double _position)=0
Set upper limit for position.
virtual void resetVelocities()=0
Set the velocities of all generalized coordinates in this Joint to their initial velocities.
virtual double getAccelerationLowerLimit(std::size_t _index) const =0
Get lower limit for acceleration.
virtual void setForceLowerLimits(const Eigen::VectorXd &lowerLimits)=0
Set the force upper limits of all the generalized coordinates.
virtual Eigen::VectorXd getAccelerations() const =0
Get the accelerations of all generalized coordinates in this Joint.
virtual void setDampingCoefficient(std::size_t _index, double _coeff)=0
Set coefficient of joint damping (viscous friction) force.
virtual void setVelocityChange(std::size_t _index, double _velocityChange)=0
Set a single velocity change.
virtual void resetVelocity(std::size_t _index)=0
Set the velocity of a generalized coordinate in this Joint to its initial velocity.
virtual void setSpringStiffness(std::size_t _index, double _k)=0
Set stiffness of joint spring force.
SkeletonPtr getSkeleton()
Get the Skeleton that this Joint belongs to.
Definition Joint.cpp:290
static constexpr ActuatorType FORCE
Definition Joint.hpp:66
virtual void setAcceleration(std::size_t _index, double _acceleration)=0
Set the acceleration of a single generalized coordinate.
void updateLocalSpatialAcceleration() const
Deprecated. Use updateRelativeSpatialAcceleration() instead.
Definition Joint.cpp:554
virtual void registerDofs()=0
Called by the Skeleton class.
virtual Eigen::VectorXd getForceLowerLimits() const =0
Get the force upper limits of all the generalized coordinates.
void setLimitEnforcement(bool enforced)
Sets whether enforcing joint position and velocity limits.
Definition Joint.cpp:398
virtual void setRestPosition(std::size_t _index, double _q0)=0
Set rest position of spring force.
virtual void getInvMassMatrixSegment(Eigen::MatrixXd &_invMassMat, const std::size_t _col, const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc)=0
Joint(const Joint &)=delete
const Joint * getMimicJoint() const
Get mimic joint.
Definition Joint.cpp:217
void notifyAccelerationUpdated()
Notify that an acceleration has updated.
Definition Joint.cpp:673
Joint & operator=(const Joint &_otherJoint)
Same as copy(const Joint&)
Definition Joint.cpp:153
virtual void setPositionUpperLimits(const Eigen::VectorXd &upperLimits)=0
Set the position upper limits of all the generalized coordinates.
virtual void addChildArtInertiaImplicitTo(Eigen::Matrix6d &_parentArtInertiaImplicit, const Eigen::Matrix6d &_childArtInertiaImplicit)=0
Add child's articulated inertia to parent's one. Forward dynamics routine.
virtual void setPositionLowerLimits(const Eigen::VectorXd &lowerLimits)=0
Set the position lower limits of all the generalized coordinates.
virtual void setAccelerationLowerLimits(const Eigen::VectorXd &lowerLimits)=0
Set the acceleration upper limits of all the generalized coordinates.
bool isPositionLimitEnforced() const
Returns whether enforcing joint position limit.
Definition Joint.cpp:404
static const ActuatorType DefaultActuatorType
Default actuator type.
Definition Joint.hpp:93
virtual void setForceLowerLimit(std::size_t _index, double _force)=0
Set lower limit for force.
virtual double getForce(std::size_t _index) const =0
Get the force of a single generalized coordinate.
virtual const std::string & setDofName(std::size_t _index, const std::string &_name, bool _preserveName=true)=0
Alternative to DegreeOfFreedom::setName()
virtual void setVelocities(const Eigen::VectorXd &_velocities)=0
Set the velocities of all generalized coordinates in this Joint.
std::size_t getTreeIndex() const
Get the index of the tree that this Joint belongs to.
Definition Joint.cpp:428
void updateLocalPrimaryAcceleration() const
Deprecated. Use updateRelativePrimaryAcceleration() instead.
Definition Joint.cpp:560
virtual Eigen::VectorXd getForceUpperLimits() const =0
Get the force upper limits of all the generalized coordinates.
virtual Eigen::VectorXd getAccelerationLowerLimits() const =0
Get the acceleration upper limits of all the generalized coordinates.
virtual void updateConstrainedTerms(double _timeStep)=0
Update constrained terms for forward dynamics.
void updateLocalTransform() const
Deprecated. Use updateRelativeTransform() instead.
Definition Joint.cpp:542
void notifyPositionUpdated()
Notify that a position has updated.
Definition Joint.cpp:618
virtual double getInitialVelocity(std::size_t _index) const =0
Get the velocity that resetVelocity() will give to this coordinate.
virtual void resetCommands()=0
Set all the commands for this Joint to zero.
virtual void addVelocityChangeTo(Eigen::Vector6d &_velocityChange)=0
Add joint velocity change to _velocityChange.
virtual const math::Jacobian getRelativeJacobianTimeDeriv() const =0
Get time derivative of spatial Jacobian of the child BodyNode relative to the parent BodyNode express...
const Eigen::Isometry3d & getTransformFromParentBodyNode() const
Get transformation from parent body node to this joint.
Definition Joint.cpp:507
virtual void setPartialAccelerationTo(Eigen::Vector6d &_partialAcceleration, const Eigen::Vector6d &_childVelocity)=0
Set joint partial acceleration to _partialAcceleration.
virtual double getPositionLowerLimit(std::size_t _index) const =0
Get lower limit for position.
virtual void updateRelativeTransform() const =0
Update transform of the child BodyNode relative to the parent BodyNode expressed in the child BodyNod...
virtual double getPosition(std::size_t _index) const =0
Get the position of a single generalized coordinate.
virtual Eigen::VectorXd getPositions() const =0
Get the positions of all generalized coordinates in this Joint.
virtual void addChildBiasForceTo(Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce, const Eigen::Vector6d &_childPartialAcc)=0
Add child's bias force to parent's one.
virtual DegreeOfFreedom * getDof(std::size_t _index)=0
Get an object to access the _index-th degree of freedom (generalized coordinate) of this Joint.
virtual double getCoulombFriction(std::size_t _index) const =0
Get joint Coulomb friction froce.
virtual void addChildArtInertiaTo(Eigen::Matrix6d &_parentArtInertia, const Eigen::Matrix6d &_childArtInertia)=0
Add child's articulated inertia to parent's one.
bool mIsRelativeJacobianTimeDerivDirty
True iff this joint's relative Jacobian time derivative has not been updated since the last position ...
Definition Joint.hpp:1069
virtual void addChildBiasForceForInvAugMassMatrix(Eigen::Vector6d &_parentBiasForce, const Eigen::Matrix6d &_childArtInertia, const Eigen::Vector6d &_childBiasForce)=0
Add child's bias force to parent's one.
double getMimicOffset() const
Get mimic joint offset.
Definition Joint.cpp:229
Eigen::Isometry3d mT
Relative transformation of the child BodyNode relative to the parent BodyNode expressed in the child ...
Definition Joint.hpp:1024
void updateLocalJacobianTimeDeriv() const
Deprecated. Use updateRelativeJacobianTimeDeriv() instead.
Definition Joint.cpp:572
const Eigen::Vector6d & getRelativeSpatialVelocity() const
Get spatial velocity of the child BodyNode relative to the parent BodyNode expressed in the child Bod...
Definition Joint.cpp:356
virtual void setCoulombFriction(std::size_t _index, double _friction)=0
Set joint Coulomb friction froce.
virtual void setCommands(const Eigen::VectorXd &_commands)=0
Set all commands for this Joint.
const math::Jacobian getLocalJacobianTimeDeriv() const
Deprecated. Use getRelativeJacobianTimeDeriv() instead.
Definition Joint.cpp:338
virtual const math::Jacobian getRelativeJacobian() const =0
Get spatial Jacobian of the child BodyNode relative to the parent BodyNode expressed in the child Bod...
virtual void setVelocityUpperLimit(std::size_t _index, double _velocity)=0
Set upper limit for velocity.
static constexpr ActuatorType MIMIC
Definition Joint.hpp:69
double getPotentialEnergy() const
Get potential energy.
Definition Joint.cpp:484
const Eigen::Isometry3d & getTransformFromChildBodyNode() const
Get transformation from child body node to this joint.
Definition Joint.cpp:513
double getMimicMultiplier() const
Get mimic joint multiplier.
Definition Joint.cpp:223
virtual void updateTotalForce(const Eigen::Vector6d &_bodyForce, double _timeStep)=0
Update joint total force.
virtual double getPositionUpperLimit(std::size_t _index) const =0
Get upper limit for position.
BodyNode * getChildBodyNode()
Get the child BodyNode of this Joint.
Definition Joint.cpp:263
virtual void setInitialPositions(const Eigen::VectorXd &_initial)=0
Change the positions that resetPositions() will give to this Joint's coordinates.
bool mIsRelativeJacobianDirty
True iff this joint's relative Jacobian has not been updated since the last position change.
Definition Joint.hpp:1065
void setMimicJoint(const Joint *_mimicJoint, double _mimicMultiplier=1.0, double _mimicOffset=0.0)
Set mimic joint.
Definition Joint.cpp:208
void updateLocalJacobian(bool mandatory=true) const
Deprecated. Use updateRelativeJacobian() instead.
Definition Joint.cpp:566
virtual Eigen::VectorXd getAccelerationUpperLimits() const =0
Get the acceleration upper limits of all the generalized coordinates.
virtual Eigen::VectorXd getPositionLowerLimits() const =0
Get the position lower limits of all the generalized coordinates.
virtual void updateAcceleration(const Eigen::Matrix6d &_artInertia, const Eigen::Vector6d &_spatialAcc)=0
Update joint acceleration.
virtual void resetTotalImpulses()=0
Set total impulses to zero.
virtual void updateImpulseID(const Eigen::Vector6d &_bodyImpulse)=0
Update joint impulses for inverse dynamics.
virtual void setVelocityLowerLimit(std::size_t _index, double _velocity)=0
Set lower limit for velocity.
virtual void setPosition(std::size_t _index, double _position)=0
Set the position of a single generalized coordinate.
void setProperties(const Properties &properties)
Set the Properties of this Joint.
Definition Joint.cpp:109
bool isDynamic() const
Return true if this joint is dynamic joint.
Definition Joint.cpp:257
virtual bool isDofNamePreserved(std::size_t _index) const =0
Alternative to DegreeOfFreedom::isNamePreserved()
virtual void addVelocityTo(Eigen::Vector6d &_vel)=0
Add joint velocity to _vel.
virtual Eigen::VectorXd getVelocities() const =0
Get the velocities of all generalized coordinates in this Joint.
common::Composite::Properties CompositeProperties
Definition Joint.hpp:62
virtual void integrateVelocities(double _dt)=0
Integrate velocities using Euler method.
static constexpr ActuatorType VELOCITY
Definition Joint.hpp:71
const Eigen::Vector6d & getLocalPrimaryAcceleration() const
Deprecated. Use getLocalPrimaryAcceleration() instead.
Definition Joint.cpp:320
std::size_t getJointIndexInTree() const
Get the index of this Joint within its tree.
Definition Joint.cpp:422
virtual void updateRelativeSpatialAcceleration() const =0
Update spatial acceleration of the child BodyNode relative to the parent BodyNode expressed in the ch...
virtual ~Joint()
Destructor.
Definition Joint.cpp:103
virtual void setAccelerationUpperLimits(const Eigen::VectorXd &upperLimits)=0
Set the acceleration upper limits of all the generalized coordinates.
const math::Jacobian getLocalJacobian() const
Deprecated. Use getRelativeJacobian() instead.
Definition Joint.cpp:326
virtual std::size_t getIndexInSkeleton(std::size_t _index) const =0
Get a unique index in skeleton of a generalized coordinate in this Joint.
virtual bool isCyclic(std::size_t _index) const =0
Get whether a generalized coordinate is cyclic.
virtual Eigen::Vector6d getBodyConstraintWrench() const =0
Get constraint wrench expressed in body node frame.
virtual void setAccelerationUpperLimit(std::size_t _index, double _acceleration)=0
Set upper limit for acceleration.
class Skeleton
Definition Skeleton.hpp:59
SoftBodyNode represent a soft body that has one deformable skin.
Definition SoftBodyNode.hpp:46
#define DART_BAKE_SPECIALIZED_ASPECT_IRREGULAR(TypeName, AspectName)
Definition Composite.hpp:164
Definition Random-impl.hpp:92
ActuatorType
Actuator type.
Definition JointAspect.hpp:59
@ PASSIVE
Passive joint doesn't take any command input, and the output is joint acceleration.
Definition JointAspect.hpp:72
@ MIMIC
There is no command input.
Definition JointAspect.hpp:86
@ FORCE
Command input is joint force, and the output is joint acceleration.
Definition JointAspect.hpp:65
@ VELOCITY
Command input is joint velocity, and the output is joint force.
Definition JointAspect.hpp:99
@ ACCELERATION
Command input is joint acceleration, and the output is joint force.
Definition JointAspect.hpp:92
@ SERVO
Command input is desired velocity, and the output is joint acceleration.
Definition JointAspect.hpp:78
@ LOCKED
Locked joint always set the velocity and acceleration to zero so that the joint dosen't move at all (...
Definition JointAspect.hpp:106
std::shared_ptr< Skeleton > SkeletonPtr
Definition SmartPointer.hpp:60
Definition BulletCollisionDetector.cpp:65
Definition SharedLibraryManager.hpp:46
CompositeProperties mCompositeProperties
Properties of all the Aspects attached to this Joint.
Definition Joint.hpp:89
Definition JointAspect.hpp:112