DART 6.12.2
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
48
49namespace dart {
50namespace dynamics {
51
52class BodyNode;
53class Skeleton;
54class DegreeOfFreedom;
55
58class Joint : public virtual common::Subject,
59 public virtual common::VersionCounter,
60 public common::EmbedProperties<Joint, detail::JointProperties>
61{
62public:
65
67 static constexpr ActuatorType FORCE = detail::FORCE;
69 static constexpr ActuatorType SERVO = detail::SERVO;
70 static constexpr ActuatorType MIMIC = detail::MIMIC;
74
76
78 {
81 const Properties& standardProperties = Properties(),
82 const CompositeProperties& aspectProperties = CompositeProperties());
83
86 Properties&& standardProperties,
87 CompositeProperties&& aspectProperties);
88
91 };
92
95
96 Joint(const Joint&) = delete;
97
99 virtual ~Joint();
100
103
106
108 const Properties& getJointProperties() const;
109
111 void copy(const Joint& _otherJoint);
112
114 void copy(const Joint* _otherJoint);
115
117 Joint& operator=(const Joint& _otherJoint);
118
126 const std::string& setName(const std::string& _name, bool _renameDofs = true);
127
129 const std::string& getName() const;
130
132 virtual const std::string& getType() const = 0;
133
135 void setActuatorType(ActuatorType _actuatorType);
136
139
141 void setMimicJoint(
142 const Joint* _mimicJoint,
143 double _mimicMultiplier = 1.0,
144 double _mimicOffset = 0.0);
145
147 const Joint* getMimicJoint() const;
148
150 double getMimicMultiplier() const;
151
153 double getMimicOffset() const;
154
161 bool isKinematic() const;
162
164 bool isDynamic() const;
165
168
170 const BodyNode* getChildBodyNode() const;
171
174
176 const BodyNode* getParentBodyNode() const;
177
180
182 std::shared_ptr<const Skeleton> getSkeleton() const;
183
185 virtual void setTransformFromParentBodyNode(const Eigen::Isometry3d& _T);
186
188 virtual void setTransformFromChildBodyNode(const Eigen::Isometry3d& _T);
189
191 const Eigen::Isometry3d& getTransformFromParentBodyNode() const;
192
194 const Eigen::Isometry3d& getTransformFromChildBodyNode() const;
195
205 DART_DEPRECATED(6.10)
206 void setPositionLimitEnforced(bool enforced);
207
214 void setLimitEnforcement(bool enforced);
215
225 DART_DEPRECATED(6.10)
226 bool isPositionLimitEnforced() const;
227
234 bool areLimitsEnforced() const;
235
237 virtual std::size_t getIndexInSkeleton(std::size_t _index) const = 0;
238
241 virtual std::size_t getIndexInTree(std::size_t _index) const = 0;
242
244 std::size_t getJointIndexInSkeleton() const;
245
247 std::size_t getJointIndexInTree() const;
248
250 std::size_t getTreeIndex() const;
251
254 virtual DegreeOfFreedom* getDof(std::size_t _index) = 0;
255
258 virtual const DegreeOfFreedom* getDof(std::size_t _index) const = 0;
259
261 virtual const std::string& setDofName(
262 std::size_t _index, const std::string& _name, bool _preserveName = true)
263 = 0;
264
266 virtual void preserveDofName(std::size_t _index, bool _preserve) = 0;
267
269 virtual bool isDofNamePreserved(std::size_t _index) const = 0;
270
272 virtual const std::string& getDofName(std::size_t _index) const = 0;
273
275 virtual std::size_t getNumDofs() const = 0;
276
277 //----------------------------------------------------------------------------
279 //----------------------------------------------------------------------------
280
282 virtual void setCommand(std::size_t _index, double _command) = 0;
283
285 virtual double getCommand(std::size_t _index) const = 0;
286
288 virtual void setCommands(const Eigen::VectorXd& _commands) = 0;
289
291 virtual Eigen::VectorXd getCommands() const = 0;
292
294 virtual void resetCommands() = 0;
295
297
298 //----------------------------------------------------------------------------
300 //----------------------------------------------------------------------------
301
303 virtual void setPosition(std::size_t _index, double _position) = 0;
304
306 virtual double getPosition(std::size_t _index) const = 0;
307
309 virtual void setPositions(const Eigen::VectorXd& _positions) = 0;
310
312 virtual Eigen::VectorXd getPositions() const = 0;
313
315 virtual void setPositionLowerLimit(std::size_t _index, double _position) = 0;
316
318 virtual double getPositionLowerLimit(std::size_t _index) const = 0;
319
321 virtual void setPositionLowerLimits(const Eigen::VectorXd& lowerLimits) = 0;
322
324 virtual Eigen::VectorXd getPositionLowerLimits() const = 0;
325
327 virtual void setPositionUpperLimit(std::size_t _index, double _position) = 0;
328
330 virtual double getPositionUpperLimit(std::size_t _index) const = 0;
331
333 virtual void setPositionUpperLimits(const Eigen::VectorXd& upperLimits) = 0;
334
336 virtual Eigen::VectorXd getPositionUpperLimits() const = 0;
337
343 virtual bool isCyclic(std::size_t _index) const = 0;
344
346 virtual bool hasPositionLimit(std::size_t _index) const = 0;
347
349 virtual void resetPosition(std::size_t _index) = 0;
350
353 virtual void resetPositions() = 0;
354
356 virtual void setInitialPosition(std::size_t _index, double _initial) = 0;
357
359 virtual double getInitialPosition(std::size_t _index) const = 0;
360
363 virtual void setInitialPositions(const Eigen::VectorXd& _initial) = 0;
364
367 virtual Eigen::VectorXd getInitialPositions() const = 0;
368
370
371 //----------------------------------------------------------------------------
373 //----------------------------------------------------------------------------
374
376 virtual void setVelocity(std::size_t _index, double _velocity) = 0;
377
379 virtual double getVelocity(std::size_t _index) const = 0;
380
382 virtual void setVelocities(const Eigen::VectorXd& _velocities) = 0;
383
385 virtual Eigen::VectorXd getVelocities() const = 0;
386
388 virtual void setVelocityLowerLimit(std::size_t _index, double _velocity) = 0;
389
391 virtual double getVelocityLowerLimit(std::size_t _index) const = 0;
392
394 virtual void setVelocityLowerLimits(const Eigen::VectorXd& lowerLimits) = 0;
395
397 virtual Eigen::VectorXd getVelocityLowerLimits() const = 0;
398
400 virtual void setVelocityUpperLimit(std::size_t _index, double _velocity) = 0;
401
403 virtual double getVelocityUpperLimit(std::size_t _index) const = 0;
404
406 virtual void setVelocityUpperLimits(const Eigen::VectorXd& upperLimits) = 0;
407
409 virtual Eigen::VectorXd getVelocityUpperLimits() const = 0;
410
413 virtual void resetVelocity(std::size_t _index) = 0;
414
417 virtual void resetVelocities() = 0;
418
420 virtual void setInitialVelocity(std::size_t _index, double _initial) = 0;
421
423 virtual double getInitialVelocity(std::size_t _index) const = 0;
424
427 virtual void setInitialVelocities(const Eigen::VectorXd& _initial) = 0;
428
431 virtual Eigen::VectorXd getInitialVelocities() const = 0;
432
434
435 //----------------------------------------------------------------------------
437 //----------------------------------------------------------------------------
438
440 virtual void setAcceleration(std::size_t _index, double _acceleration) = 0;
441
443 virtual double getAcceleration(std::size_t _index) const = 0;
444
446 virtual void setAccelerations(const Eigen::VectorXd& _accelerations) = 0;
447
449 virtual Eigen::VectorXd getAccelerations() const = 0;
450
452 virtual void resetAccelerations() = 0;
453
456 std::size_t _index, double _acceleration)
457 = 0;
458
460 virtual double getAccelerationLowerLimit(std::size_t _index) const = 0;
461
463 virtual void setAccelerationLowerLimits(const Eigen::VectorXd& lowerLimits)
464 = 0;
465
467 virtual Eigen::VectorXd getAccelerationLowerLimits() const = 0;
468
471 std::size_t _index, double _acceleration)
472 = 0;
473
475 virtual double getAccelerationUpperLimit(std::size_t _index) const = 0;
476
478 virtual void setAccelerationUpperLimits(const Eigen::VectorXd& upperLimits)
479 = 0;
480
482 virtual Eigen::VectorXd getAccelerationUpperLimits() const = 0;
483
485
486 //----------------------------------------------------------------------------
488 //----------------------------------------------------------------------------
489
491 virtual void setForce(std::size_t _index, double _force) = 0;
492
494 virtual double getForce(std::size_t _index) const = 0;
495
497 virtual void setForces(const Eigen::VectorXd& _forces) = 0;
498
500 virtual Eigen::VectorXd getForces() const = 0;
501
503 virtual void resetForces() = 0;
504
506 virtual void setForceLowerLimit(std::size_t _index, double _force) = 0;
507
509 virtual double getForceLowerLimit(std::size_t _index) const = 0;
510
512 virtual void setForceLowerLimits(const Eigen::VectorXd& lowerLimits) = 0;
513
515 virtual Eigen::VectorXd getForceLowerLimits() const = 0;
516
518 virtual void setForceUpperLimit(std::size_t _index, double _force) = 0;
519
521 virtual double getForceUpperLimit(std::size_t _index) const = 0;
522
524 virtual void setForceUpperLimits(const Eigen::VectorXd& upperLimits) = 0;
525
527 virtual Eigen::VectorXd getForceUpperLimits() const = 0;
528
530
531 //----------------------------------------------------------------------------
533 //----------------------------------------------------------------------------
534
537 // TODO: Consider extending this to a more comprehensive sanity check
538 bool checkSanity(bool _printWarnings = true) const;
539
540 //----------------------------------------------------------------------------
542 //----------------------------------------------------------------------------
543
545 virtual void setVelocityChange(std::size_t _index, double _velocityChange)
546 = 0;
547
549 virtual double getVelocityChange(std::size_t _index) const = 0;
550
552 virtual void resetVelocityChanges() = 0;
553
555
556 //----------------------------------------------------------------------------
558 //----------------------------------------------------------------------------
559
561 virtual void setConstraintImpulse(std::size_t _index, double _impulse) = 0;
562
564 virtual double getConstraintImpulse(std::size_t _index) const = 0;
565
567 virtual void resetConstraintImpulses() = 0;
568
570
571 //----------------------------------------------------------------------------
573 //----------------------------------------------------------------------------
574
576 virtual void integratePositions(double _dt) = 0;
577
579 virtual void integrateVelocities(double _dt) = 0;
580
583 virtual Eigen::VectorXd getPositionDifferences(
584 const Eigen::VectorXd& _q2, const Eigen::VectorXd& _q1) const = 0;
585
587
588 //----------------------------------------------------------------------------
590 //----------------------------------------------------------------------------
591
595 virtual void setSpringStiffness(std::size_t _index, double _k) = 0;
596
599 virtual double getSpringStiffness(std::size_t _index) const = 0;
600
604 virtual void setRestPosition(std::size_t _index, double _q0) = 0;
605
609 virtual double getRestPosition(std::size_t _index) const = 0;
610
614 virtual void setDampingCoefficient(std::size_t _index, double _coeff) = 0;
615
618 virtual double getDampingCoefficient(std::size_t _index) const = 0;
619
623 virtual void setCoulombFriction(std::size_t _index, double _friction) = 0;
624
627 virtual double getCoulombFriction(std::size_t _index) const = 0;
628
630
631 //----------------------------------------------------------------------------
632
634 DART_DEPRECATED(6.1)
635 double getPotentialEnergy() const;
636
638 virtual double computePotentialEnergy() const = 0;
639
640 //----------------------------------------------------------------------------
641
643 DART_DEPRECATED(6.0)
644 const Eigen::Isometry3d& getLocalTransform() const;
645
647 DART_DEPRECATED(6.0)
648 const Eigen::Vector6d& getLocalSpatialVelocity() const;
649
651 DART_DEPRECATED(6.0)
652 const Eigen::Vector6d& getLocalSpatialAcceleration() const;
653
655 DART_DEPRECATED(6.0)
656 const Eigen::Vector6d& getLocalPrimaryAcceleration() const;
657
659 DART_DEPRECATED(6.0)
660 const math::Jacobian getLocalJacobian() const;
661
663 DART_DEPRECATED(6.0)
664 math::Jacobian getLocalJacobian(const Eigen::VectorXd& positions) const;
665
667 DART_DEPRECATED(6.0)
668 const math::Jacobian getLocalJacobianTimeDeriv() const;
669
672 const Eigen::Isometry3d& getRelativeTransform() const;
673
676 const Eigen::Vector6d& getRelativeSpatialVelocity() const;
677
680 const Eigen::Vector6d& getRelativeSpatialAcceleration() const;
681
683 const Eigen::Vector6d& getRelativePrimaryAcceleration() const;
684
687 virtual const math::Jacobian getRelativeJacobian() const = 0;
688
691 virtual math::Jacobian getRelativeJacobian(
692 const Eigen::VectorXd& positions) const = 0;
693
696 virtual const math::Jacobian getRelativeJacobianTimeDeriv() const = 0;
697
699 virtual Eigen::Vector6d getBodyConstraintWrench() const = 0;
700 // TODO: Need more informative name.
701
715 // Eigen::VectorXd getSpringForces(double _timeStep) const;
716
727 // Eigen::VectorXd getDampingForces() const;
728
739 const Frame* withRespectTo = nullptr) const;
740
751 const Frame* withRespectTo = nullptr) const;
752
753 //----------------------------------------------------------------------------
755 //----------------------------------------------------------------------------
756
758 DART_DEPRECATED(6.2)
760
763
765 DART_DEPRECATED(6.2)
767
770
772 DART_DEPRECATED(6.2)
774
777
779
780 //----------------------------------------------------------------------------
781 // Friendship
782 //----------------------------------------------------------------------------
783
784 friend class BodyNode;
785 friend class SoftBodyNode;
786 friend class Skeleton;
787
788protected:
790 Joint();
791
794 virtual Joint* clone() const = 0;
795
797 virtual void registerDofs() = 0;
798
806 DegreeOfFreedom* createDofPointer(std::size_t _indexInJoint);
807
810 virtual void updateDegreeOfFreedomNames() = 0;
811
812 //----------------------------------------------------------------------------
814 //----------------------------------------------------------------------------
815
817 DART_DEPRECATED(6.0)
818 void updateLocalTransform() const;
819
821 DART_DEPRECATED(6.0)
822 void updateLocalSpatialVelocity() const;
823
825 DART_DEPRECATED(6.0)
827
829 DART_DEPRECATED(6.0)
831
833 DART_DEPRECATED(6.0)
834 void updateLocalJacobian(bool mandatory = true) const;
835
837 DART_DEPRECATED(6.0)
838 void updateLocalJacobianTimeDeriv() const;
839
842 virtual void updateRelativeTransform() const = 0;
843
846 virtual void updateRelativeSpatialVelocity() const = 0;
847
850 virtual void updateRelativeSpatialAcceleration() const = 0;
851
853 virtual void updateRelativePrimaryAcceleration() const = 0;
854
862 virtual void updateRelativeJacobian(bool mandatory = true) const = 0;
863
869 virtual void updateRelativeJacobianTimeDeriv() const = 0;
870
872 void updateArticulatedInertia() const;
873
875 virtual void addVelocityTo(Eigen::Vector6d& _vel) = 0;
876
879 Eigen::Vector6d& _partialAcceleration,
880 const Eigen::Vector6d& _childVelocity)
881 = 0;
882 // TODO(JS): Rename with more informative name
883
885 virtual void addAccelerationTo(Eigen::Vector6d& _acc) = 0;
886
888 virtual void addVelocityChangeTo(Eigen::Vector6d& _velocityChange) = 0;
889
892 Eigen::Matrix6d& _parentArtInertia,
893 const Eigen::Matrix6d& _childArtInertia)
894 = 0;
895
898 Eigen::Matrix6d& _parentArtInertiaImplicit,
899 const Eigen::Matrix6d& _childArtInertiaImplicit)
900 = 0;
901 // TODO(JS): rename to updateAInertiaChildAInertia()
902
904 virtual void updateInvProjArtInertia(const Eigen::Matrix6d& _artInertia) = 0;
905
908 const Eigen::Matrix6d& _artInertia, double _timeStep)
909 = 0;
910 // TODO(JS): rename to updateAInertiaPsi()
911
914 Eigen::Vector6d& _parentBiasForce,
915 const Eigen::Matrix6d& _childArtInertia,
916 const Eigen::Vector6d& _childBiasForce,
917 const Eigen::Vector6d& _childPartialAcc)
918 = 0;
919
922 Eigen::Vector6d& _parentBiasImpulse,
923 const Eigen::Matrix6d& _childArtInertia,
924 const Eigen::Vector6d& _childBiasImpulse)
925 = 0;
926
928 virtual void updateTotalForce(
929 const Eigen::Vector6d& _bodyForce, double _timeStep)
930 = 0;
931 // TODO: rename
932
934 virtual void updateTotalImpulse(const Eigen::Vector6d& _bodyImpulse) = 0;
935 // TODO: rename
936
938 virtual void resetTotalImpulses() = 0;
939
941 virtual void updateAcceleration(
942 const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc)
943 = 0;
944
949 const Eigen::Matrix6d& _artInertia,
950 const Eigen::Vector6d& _velocityChange)
951 = 0;
952
960 virtual void updateForceID(
961 const Eigen::Vector6d& _bodyForce,
962 double _timeStep,
963 bool _withDampingForces,
964 bool _withSpringForces)
965 = 0;
966
974 virtual void updateForceFD(
975 const Eigen::Vector6d& _bodyForce,
976 double _timeStep,
977 bool _withDampingForces,
978 bool _withSpringForces)
979 = 0;
980
982 virtual void updateImpulseID(const Eigen::Vector6d& _bodyImpulse) = 0;
983
985 virtual void updateImpulseFD(const Eigen::Vector6d& _bodyImpulse) = 0;
986
988 virtual void updateConstrainedTerms(double _timeStep) = 0;
989
991
992 //----------------------------------------------------------------------------
994 //----------------------------------------------------------------------------
995
998 Eigen::Vector6d& _parentBiasForce,
999 const Eigen::Matrix6d& _childArtInertia,
1000 const Eigen::Vector6d& _childBiasForce)
1001 = 0;
1002
1005 Eigen::Vector6d& _parentBiasForce,
1006 const Eigen::Matrix6d& _childArtInertia,
1007 const Eigen::Vector6d& _childBiasForce)
1008 = 0;
1009
1012 const Eigen::Vector6d& _bodyForce)
1013 = 0;
1014
1017 Eigen::MatrixXd& _invMassMat,
1018 const std::size_t _col,
1019 const Eigen::Matrix6d& _artInertia,
1020 const Eigen::Vector6d& _spatialAcc)
1021 = 0;
1022
1025 Eigen::MatrixXd& _invMassMat,
1026 const std::size_t _col,
1027 const Eigen::Matrix6d& _artInertia,
1028 const Eigen::Vector6d& _spatialAcc)
1029 = 0;
1030
1032 virtual void addInvMassMatrixSegmentTo(Eigen::Vector6d& _acc) = 0;
1033
1036 const Eigen::Vector6d& _spatial)
1037 = 0;
1038
1040
1041protected:
1044
1049 mutable Eigen::Isometry3d mT;
1050
1055 mutable Eigen::Vector6d mSpatialVelocity;
1056
1061 mutable Eigen::Vector6d mSpatialAcceleration;
1062
1066 mutable Eigen::Vector6d mPrimaryAcceleration;
1067
1071 // TODO(JS): Rename this to mIsTransformDirty in DART 7
1072
1076 // TODO(JS): Rename this to mIsSpatialVelocityDirty in DART 7
1077
1081 // TODO(JS): Rename this to mIsSpatialAccelerationDirty in DART 7
1082
1086 // TODO(JS): Rename this to mIsPrimaryAccelerationDirty in DART 7
1087
1091
1095
1096public:
1097 // To get byte-aligned Eigen vectors
1098 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1099};
1101
1102} // namespace dynamics
1103} // namespace dart
1104
1105#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:56
The Frame class serves as the backbone of DART's kinematic tree structure.
Definition Frame.hpp:58
class Joint
Definition Joint.hpp:61
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:1080
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:543
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:1066
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:379
detail::ActuatorType ActuatorType
Definition Joint.hpp:66
bool areLimitsEnforced() const
Returns whether enforcing joint position and velocity limits.
Definition Joint.cpp:455
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:307
bool mNeedPrimaryAccelerationUpdate
True iff this joint's position, velocity, or acceleration has changed since the last call to getRelat...
Definition Joint.hpp:1085
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:68
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:461
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:313
bool mNeedSpatialVelocityUpdate
True iff this joint's position or velocity has changed since the last call to getRelativeSpatialVeloc...
Definition Joint.hpp:1075
bool checkSanity(bool _printWarnings=true) const
Returns false if the initial position or initial velocity are outside of limits.
Definition Joint.cpp:479
const Eigen::Isometry3d & getLocalTransform() const
Deprecated. Use getRelativeTransform() instead.
Definition Joint.cpp:301
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:69
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:274
virtual double getSpringStiffness(std::size_t _index) const =0
Get stiffness of joint spring force.
static constexpr ActuatorType ACCELERATION
Definition Joint.hpp:71
Eigen::Vector6d mSpatialAcceleration
Relative spatial acceleration from parent BodyNode to child BodyNode where the acceleration is expres...
Definition Joint.hpp:1061
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:535
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:623
bool mNeedTransformUpdate
True iff this joint's position has changed since the last call to getRelativeTransform()
Definition Joint.hpp:1070
detail::JointProperties Properties
Definition Joint.hpp:64
DegreeOfFreedom * createDofPointer(std::size_t _indexInJoint)
Create a DegreeOfFreedom pointer.
Definition Joint.cpp:581
void updateLocalSpatialVelocity() const
Deprecated. Use updateRelativeSpatialVelocity() instead.
Definition Joint.cpp:593
void notifyAccelerationUpdate()
Notify that an acceleration has updated.
Definition Joint.cpp:712
static constexpr ActuatorType LOCKED
Definition Joint.hpp:73
virtual double getCommand(std::size_t _index) const =0
Get a single command.
void notifyVelocityUpdated()
Notify that a velocity has updated.
Definition Joint.cpp:697
void copy(const Joint &_otherJoint)
Copy the properties of another Joint.
Definition Joint.cpp:135
Eigen::Vector6d getWrenchToChildBodyNode(const Frame *withRespectTo=nullptr) const
Get spring force.
Definition Joint.cpp:391
Eigen::Vector6d mSpatialVelocity
Relative spatial velocity from parent BodyNode to child BodyNode where the velocity is expressed in c...
Definition Joint.hpp:1055
void notifyPositionUpdate()
Notify that a position has updated.
Definition Joint.cpp:657
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:1043
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:343
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:367
void setPositionLimitEnforced(bool enforced)
Sets whether enforcing joint position and velocity limits.
Definition Joint.cpp:437
void notifyVelocityUpdate()
Notify that a velocity has updated.
Definition Joint.cpp:691
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:289
static constexpr ActuatorType FORCE
Definition Joint.hpp:67
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:599
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:443
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:718
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:449
static const ActuatorType DefaultActuatorType
Default actuator type.
Definition Joint.hpp:94
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:473
void updateLocalPrimaryAcceleration() const
Deprecated. Use updateRelativePrimaryAcceleration() instead.
Definition Joint.cpp:605
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:587
void notifyPositionUpdated()
Notify that a position has updated.
Definition Joint.cpp:663
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:552
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:1094
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:1049
void updateLocalJacobianTimeDeriv() const
Deprecated. Use updateRelativeJacobianTimeDeriv() instead.
Definition Joint.cpp:617
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:355
virtual void setCoulombFriction(std::size_t _index, double _friction)=0
Set joint Coulomb friction froce.
Eigen::Vector6d getWrenchToParentBodyNode(const Frame *withRespectTo=nullptr) const
Returns wrench exerted to the parent body node to satisfy the joint constraint.
Definition Joint.cpp:430
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:337
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:70
double getPotentialEnergy() const
Get potential energy.
Definition Joint.cpp:529
const Eigen::Isometry3d & getTransformFromChildBodyNode() const
Get transformation from child body node to this joint.
Definition Joint.cpp:558
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:262
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:1090
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:611
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:256
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:63
virtual void integrateVelocities(double _dt)=0
Integrate velocities using Euler method.
static constexpr ActuatorType VELOCITY
Definition Joint.hpp:72
const Eigen::Vector6d & getLocalPrimaryAcceleration() const
Deprecated. Use getLocalPrimaryAcceleration() instead.
Definition Joint.cpp:319
std::size_t getJointIndexInTree() const
Get the index of this Joint within its tree.
Definition Joint.cpp:467
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:325
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:60
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:60
Definition SharedLibraryManager.hpp:46
CompositeProperties mCompositeProperties
Properties of all the Aspects attached to this Joint.
Definition Joint.hpp:90
Definition JointAspect.hpp:112