DART 6.12.2
Loading...
Searching...
No Matches
GenericJoint.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_GENERICJOINT_HPP_
34#define DART_DYNAMICS_GENERICJOINT_HPP_
35
36#include <array>
37#include <string>
38
40
41namespace dart {
42namespace dynamics {
43
44class DegreeOfFreedom;
45
46template <class ConfigSpaceT>
48 : public detail::GenericJointBase<GenericJoint<ConfigSpaceT>, ConfigSpaceT>
49{
50public:
51 static constexpr std::size_t NumDofs = ConfigSpaceT::NumDofs;
52
55
56 using Point = typename ConfigSpaceT::Point;
57 using EuclideanPoint = typename ConfigSpaceT::EuclideanPoint;
58 using Vector = typename ConfigSpaceT::Vector;
59 using JacobianMatrix = typename ConfigSpaceT::JacobianMatrix;
60 using Matrix = typename ConfigSpaceT::Matrix;
61
66
68 typename ThisClass::Aspect, GenericJointAspect)
69
70 GenericJoint(const ThisClass&) = delete;
71
73 virtual ~GenericJoint();
74
77
80
82 void setAspectState(const AspectState& state);
83
86
89
91 void copy(const ThisClass& otherJoint);
92
94 void copy(const ThisClass* otherJoint);
95
97 ThisClass& operator=(const ThisClass& other);
98
99 //----------------------------------------------------------------------------
101 //----------------------------------------------------------------------------
102
103 // Documentation inherited
104 DegreeOfFreedom* getDof(std::size_t index) override;
105
106 // Documentation inherited
107 const DegreeOfFreedom* getDof(std::size_t _index) const override;
108
109 // Documentation inherited
110 std::size_t getNumDofs() const override;
111
112 // Documentation inherited
113 const std::string& setDofName(
114 std::size_t index,
115 const std::string& name,
116 bool preserveName = true) override;
117
118 // Documentation inherited
119 void preserveDofName(size_t index, bool preserve) override;
120
121 // Documentation inherited
122 bool isDofNamePreserved(size_t index) const override;
123
124 // Documentation inherited
125 const std::string& getDofName(size_t index) const override;
126
127 // Documentation inherited
128 size_t getIndexInSkeleton(size_t index) const override;
129
130 // Documentation inherited
131 size_t getIndexInTree(size_t index) const override;
132
134
135 //----------------------------------------------------------------------------
137 //----------------------------------------------------------------------------
138
139 // Documentation inherited
140 void setCommand(std::size_t index, double command) override;
141
142 // Documentation inherited
143 double getCommand(std::size_t index) const override;
144
145 // Documentation inherited
146 void setCommands(const Eigen::VectorXd& commands) override;
147
148 // Documentation inherited
149 Eigen::VectorXd getCommands() const override;
150
151 // Documentation inherited
152 void resetCommands() override;
153
155
156 //----------------------------------------------------------------------------
158 //----------------------------------------------------------------------------
159
160 // Documentation inherited
161 void setPosition(std::size_t index, double position) override;
162
163 // Documentation inherited
164 double getPosition(std::size_t index) const override;
165
166 // Documentation inherited
167 void setPositions(const Eigen::VectorXd& positions) override;
168
169 // Documentation inherited
170 Eigen::VectorXd getPositions() const override;
171
172 // Documentation inherited
173 void setPositionLowerLimit(std::size_t index, double position) override;
174
175 // Documentation inherited
176 double getPositionLowerLimit(std::size_t index) const override;
177
178 // Documentation inherited
179 void setPositionLowerLimits(const Eigen::VectorXd& lowerLimits) override;
180
181 // Documentation inherited
182 Eigen::VectorXd getPositionLowerLimits() const override;
183
184 // Documentation inherited
185 void setPositionUpperLimit(std::size_t index, double position) override;
186
187 // Documentation inherited
188 double getPositionUpperLimit(std::size_t index) const override;
189
190 // Documentation inherited
191 void setPositionUpperLimits(const Eigen::VectorXd& upperLimits) override;
192
193 // Documentation inherited
194 Eigen::VectorXd getPositionUpperLimits() const override;
195
196 // Documentation inherited
197 bool hasPositionLimit(std::size_t index) const override;
198
199 // Documentation inherited
200 void resetPosition(std::size_t index) override;
201
202 // Documentation inherited
203 void resetPositions() override;
204
205 // Documentation inherited
206 void setInitialPosition(std::size_t index, double initial) override;
207
208 // Documentation inherited
209 double getInitialPosition(std::size_t index) const override;
210
211 // Documentation inherited
212 void setInitialPositions(const Eigen::VectorXd& initial) override;
213
214 // Documentation inherited
215 Eigen::VectorXd getInitialPositions() const override;
216
218
219 //----------------------------------------------------------------------------
221 //----------------------------------------------------------------------------
222
223 // Note: The fixed-size versions of these functions exist to make it easier
224 // to comply with the auto-updating design. Use these functions to avoid
225 // accessing mPosition directly, that way it is easier to ensure that the
226 // auto-updating design assumptions are being satisfied when reviewing the
227 // code.
228
230 void setPositionsStatic(const Vector& positions);
231
233 const Vector& getPositionsStatic() const;
234
236 void setVelocitiesStatic(const Vector& velocities);
237
239 const Vector& getVelocitiesStatic() const;
240
242 void setAccelerationsStatic(const Vector& accels);
243
245 const Vector& getAccelerationsStatic() const;
246
248
249 //----------------------------------------------------------------------------
251 //----------------------------------------------------------------------------
252
253 // Documentation inherited
254 void setVelocity(std::size_t index, double velocity) override;
255
256 // Documentation inherited
257 double getVelocity(std::size_t index) const override;
258
259 // Documentation inherited
260 void setVelocities(const Eigen::VectorXd& velocities) override;
261
262 // Documentation inherited
263 Eigen::VectorXd getVelocities() const override;
264
265 // Documentation inherited
266 void setVelocityLowerLimit(std::size_t index, double velocity) override;
267
268 // Documentation inherited
269 double getVelocityLowerLimit(std::size_t index) const override;
270
271 // Documentation inherited
272 void setVelocityLowerLimits(const Eigen::VectorXd& lowerLimits) override;
273
274 // Documentation inherited
275 Eigen::VectorXd getVelocityLowerLimits() const override;
276
277 // Documentation inherited
278 void setVelocityUpperLimit(std::size_t index, double velocity) override;
279
280 // Documentation inherited
281 double getVelocityUpperLimit(std::size_t index) const override;
282
283 // Documentation inherited
284 void setVelocityUpperLimits(const Eigen::VectorXd& upperLimits) override;
285
286 // Documentation inherited
287 Eigen::VectorXd getVelocityUpperLimits() const override;
288
289 // Documentation inherited
290 void resetVelocity(std::size_t index) override;
291
292 // Documentation inherited
293 void resetVelocities() override;
294
295 // Documentation inherited
296 void setInitialVelocity(std::size_t index, double initial) override;
297
298 // Documentation inherited
299 double getInitialVelocity(std::size_t index) const override;
300
301 // Documentation inherited
302 void setInitialVelocities(const Eigen::VectorXd& initial) override;
303
304 // Documentation inherited
305 Eigen::VectorXd getInitialVelocities() const override;
306
308
309 //----------------------------------------------------------------------------
311 //----------------------------------------------------------------------------
312
313 // Documentation inherited
314 void setAcceleration(std::size_t index, double acceleration) override;
315
316 // Documentation inherited
317 double getAcceleration(std::size_t index) const override;
318
319 // Documentation inherited
320 void setAccelerations(const Eigen::VectorXd& accelerations) override;
321
322 // Documentation inherited
323 Eigen::VectorXd getAccelerations() const override;
324
325 // Documentation inherited
326 void setAccelerationLowerLimit(size_t index, double acceleration) override;
327
328 // Documentation inherited
329 double getAccelerationLowerLimit(std::size_t index) const override;
330
331 // Documentation inherited
332 void setAccelerationLowerLimits(const Eigen::VectorXd& lowerLimits) override;
333
334 // Documentation inherited
335 Eigen::VectorXd getAccelerationLowerLimits() const override;
336
337 // Documentation inherited
339 std::size_t index, double acceleration) override;
340
341 // Documentation inherited
342 double getAccelerationUpperLimit(std::size_t index) const override;
343
344 // Documentation inherited
345 void setAccelerationUpperLimits(const Eigen::VectorXd& upperLimits) override;
346
347 // Documentation inherited
348 Eigen::VectorXd getAccelerationUpperLimits() const override;
349
350 // Documentation inherited
351 void resetAccelerations() override;
352
354
355 //----------------------------------------------------------------------------
357 //----------------------------------------------------------------------------
358
359 // Documentation inherited
360 void setForce(std::size_t index, double force) override;
361
362 // Documentation inherited
363 double getForce(std::size_t index) const override;
364
365 // Documentation inherited
366 void setForces(const Eigen::VectorXd& forces) override;
367
368 // Documentation inherited
369 Eigen::VectorXd getForces() const override;
370
371 // Documentation inherited
372 void setForceLowerLimit(size_t index, double force) override;
373
374 // Documentation inherited
375 double getForceLowerLimit(std::size_t index) const override;
376
377 // Documentation inherited
378 void setForceLowerLimits(const Eigen::VectorXd& lowerLimits) override;
379
380 // Documentation inherited
381 Eigen::VectorXd getForceLowerLimits() const override;
382
383 // Documentation inherited
384 void setForceUpperLimit(size_t index, double force) override;
385
386 // Documentation inherited
387 double getForceUpperLimit(size_t index) const override;
388
389 // Documentation inherited
390 void setForceUpperLimits(const Eigen::VectorXd& upperLimits) override;
391
392 // Documentation inherited
393 Eigen::VectorXd getForceUpperLimits() const override;
394
395 // Documentation inherited
396 void resetForces() override;
397
399
400 //----------------------------------------------------------------------------
402 //----------------------------------------------------------------------------
403
404 // Documentation inherited
405 void setVelocityChange(std::size_t index, double velocityChange) override;
406
407 // Documentation inherited
408 double getVelocityChange(std::size_t index) const override;
409
410 // Documentation inherited
411 void resetVelocityChanges() override;
412
414
415 //----------------------------------------------------------------------------
417 //----------------------------------------------------------------------------
418
419 // Documentation inherited
420 void setConstraintImpulse(std::size_t index, double impulse) override;
421
422 // Documentation inherited
423 double getConstraintImpulse(std::size_t index) const override;
424
425 // Documentation inherited
426 void resetConstraintImpulses() override;
427
429
430 //----------------------------------------------------------------------------
432 //----------------------------------------------------------------------------
433
434 // Documentation inherited
435 void integratePositions(double dt) override;
436
437 // Documentation inherited
438 void integrateVelocities(double dt) override;
439
440 // Documentation inherited
442 const Eigen::VectorXd& q2, const Eigen::VectorXd& q1) const override;
443
446 const Vector& q2, const Vector& q1) const;
447
449
450 //----------------------------------------------------------------------------
452 //----------------------------------------------------------------------------
453
454 // Documentation inherited
455 void setSpringStiffness(std::size_t index, double k) override;
456
457 // Documentation inherited
458 double getSpringStiffness(std::size_t index) const override;
459
460 // Documentation inherited
461 void setRestPosition(std::size_t index, double q0) override;
462
463 // Documentation inherited
464 double getRestPosition(std::size_t index) const override;
465
466 // Documentation inherited
467 void setDampingCoefficient(std::size_t index, double coeff) override;
468
469 // Documentation inherited
470 double getDampingCoefficient(std::size_t index) const override;
471
472 // Documentation inherited
473 void setCoulombFriction(std::size_t index, double friction) override;
474
475 // Documentation inherited
476 double getCoulombFriction(std::size_t index) const override;
477
479
480 //----------------------------------------------------------------------------
482 //----------------------------------------------------------------------------
483
484 // Documentation inherited
485 double computePotentialEnergy() const override;
486
488
489 // Documentation inherited
490 Eigen::Vector6d getBodyConstraintWrench() const override;
491
492 //----------------------------------------------------------------------------
494 //----------------------------------------------------------------------------
495
496 // Documentation inherited
497 const math::Jacobian getRelativeJacobian() const override;
498
500 const typename GenericJoint<ConfigSpaceT>::JacobianMatrix&
502
503 // Documentation inherited
504 math::Jacobian getRelativeJacobian(
505 const Eigen::VectorXd& _positions) const override;
506
509 const Vector& positions) const = 0;
510
511 // Documentation inherited
512 const math::Jacobian getRelativeJacobianTimeDeriv() const override;
513
516
518
519protected:
521
522 // Documentation inherited
523 void registerDofs() override;
524
525 //----------------------------------------------------------------------------
527 //----------------------------------------------------------------------------
528
530 const Matrix& getInvProjArtInertia() const;
531
535
536 // Documentation inherited
537 void updateRelativeSpatialVelocity() const override;
538
539 // Documentation inherited
540 void updateRelativeSpatialAcceleration() const override;
541
542 // Documentation inherited
543 void updateRelativePrimaryAcceleration() const override;
544
545 // Documentation inherited
546 void addVelocityTo(Eigen::Vector6d& vel) override;
547
548 // Documentation inherited
550 Eigen::Vector6d& partialAcceleration,
551 const Eigen::Vector6d& childVelocity) override;
552
553 // Documentation inherited
554 void addAccelerationTo(Eigen::Vector6d& acc) override;
555
556 // Documentation inherited
557 void addVelocityChangeTo(Eigen::Vector6d& velocityChange) override;
558
559 // Documentation inherited
561 Eigen::Matrix6d& parentArtInertia,
562 const Eigen::Matrix6d& childArtInertia) override;
563
564 // Documentation inherited
566 Eigen::Matrix6d& parentArtInertiaImplicit,
567 const Eigen::Matrix6d& childArtInertiaImplicit) override;
568
569 // Documentation inherited
570 void updateInvProjArtInertia(const Eigen::Matrix6d& artInertia) override;
571
572 // Documentation inherited
574 const Eigen::Matrix6d& artInertia, double timeStep) override;
575
576 // Documentation inherited
578 Eigen::Vector6d& parentBiasForce,
579 const Eigen::Matrix6d& childArtInertia,
580 const Eigen::Vector6d& childBiasForce,
581 const Eigen::Vector6d& childPartialAcc) override;
582
583 // Documentation inherited
585 Eigen::Vector6d& parentBiasImpulse,
586 const Eigen::Matrix6d& childArtInertia,
587 const Eigen::Vector6d& childBiasImpulse) override;
588
589 // Documentation inherited
590 void updateTotalForce(
591 const Eigen::Vector6d& bodyForce, double timeStep) override;
592
593 // Documentation inherited
594 void updateTotalImpulse(const Eigen::Vector6d& bodyImpulse) override;
595
596 // Documentation inherited
597 void resetTotalImpulses() override;
598
599 // Documentation inherited
601 const Eigen::Matrix6d& artInertia,
602 const Eigen::Vector6d& spatialAcc) override;
603
604 // Documentation inherited
606 const Eigen::Matrix6d& artInertia,
607 const Eigen::Vector6d& velocityChange) override;
608
609 // Documentation inherited
610 void updateForceID(
611 const Eigen::Vector6d& bodyForce,
612 double timeStep,
613 bool withDampingForces,
614 bool withSpringForces) override;
615
616 // Documentation inherited
617 void updateForceFD(
618 const Eigen::Vector6d& bodyForce,
619 double timeStep,
620 bool withDampingForcese,
621 bool withSpringForces) override;
622
623 // Documentation inherited
624 void updateImpulseID(const Eigen::Vector6d& bodyImpulse) override;
625
626 // Documentation inherited
627 void updateImpulseFD(const Eigen::Vector6d& bodyImpulse) override;
628
629 // Documentation inherited
630 void updateConstrainedTerms(double timeStep) override;
631
633
634 //----------------------------------------------------------------------------
636 //----------------------------------------------------------------------------
637
638 // Documentation inherited
640 Eigen::Vector6d& parentBiasForce,
641 const Eigen::Matrix6d& childArtInertia,
642 const Eigen::Vector6d& childBiasForce) override;
643
644 // Documentation inherited
646 Eigen::Vector6d& parentBiasForce,
647 const Eigen::Matrix6d& childArtInertia,
648 const Eigen::Vector6d& childBiasForce) override;
649
650 // Documentation inherited
652 const Eigen::Vector6d& bodyForce) override;
653
654 // Documentation inherited
656 Eigen::MatrixXd& invMassMat,
657 const size_t col,
658 const Eigen::Matrix6d& artInertia,
659 const Eigen::Vector6d& spatialAcc) override;
660
661 // Documentation inherited
663 Eigen::MatrixXd& invMassMat,
664 const size_t col,
665 const Eigen::Matrix6d& artInertia,
666 const Eigen::Vector6d& spatialAcc) override;
667
668 // Documentation inherited
669 void addInvMassMatrixSegmentTo(Eigen::Vector6d& acc) override;
670
671 // Documentation inherited
673 const Eigen::Vector6d& spatial) override;
674
676
677protected:
680
681 //----------------------------------------------------------------------------
682 // Impulse
683 //----------------------------------------------------------------------------
684
687
690
693
694 //----------------------------------------------------------------------------
695 // For recursive dynamics algorithms
696 //----------------------------------------------------------------------------
697
703
709
714
721
724
727
728 //----------------------------------------------------------------------------
729 // For equations of motion
730 //----------------------------------------------------------------------------
731
734
737
738private:
739 //----------------------------------------------------------------------------
741 //----------------------------------------------------------------------------
742
744 Eigen::Matrix6d& parentArtInertia,
745 const Eigen::Matrix6d& childArtInertia);
746
748 Eigen::Matrix6d& parentArtInertia,
749 const Eigen::Matrix6d& childArtInertia);
750
752 Eigen::Matrix6d& parentArtInertia,
753 const Eigen::Matrix6d& childArtInertia);
754
756 Eigen::Matrix6d& parentArtInertia,
757 const Eigen::Matrix6d& childArtInertia);
758
759 void updateInvProjArtInertiaDynamic(const Eigen::Matrix6d& artInertia);
760
761 void updateInvProjArtInertiaKinematic(const Eigen::Matrix6d& artInertia);
762
764 const Eigen::Matrix6d& artInertia, double timeStep);
765
767 const Eigen::Matrix6d& artInertia, double timeStep);
768
770 Eigen::Vector6d& parentBiasForce,
771 const Eigen::Matrix6d& childArtInertia,
772 const Eigen::Vector6d& childBiasForce,
773 const Eigen::Vector6d& childPartialAcc);
774
776 Eigen::Vector6d& parentBiasForce,
777 const Eigen::Matrix6d& childArtInertia,
778 const Eigen::Vector6d& childBiasForce,
779 const Eigen::Vector6d& childPartialAcc);
780
782 Eigen::Vector6d& parentBiasImpulse,
783 const Eigen::Matrix6d& childArtInertia,
784 const Eigen::Vector6d& childBiasImpulse);
785
787 Eigen::Vector6d& parentBiasImpulse,
788 const Eigen::Matrix6d& childArtInertia,
789 const Eigen::Vector6d& childBiasImpulse);
790
792 const Eigen::Vector6d& bodyForce, double timeStep);
793
795 const Eigen::Vector6d& bodyForce, double timeStep);
796
797 void updateTotalImpulseDynamic(const Eigen::Vector6d& bodyImpulse);
798
799 void updateTotalImpulseKinematic(const Eigen::Vector6d& bodyImpulse);
800
802 const Eigen::Matrix6d& artInertia, const Eigen::Vector6d& spatialAcc);
803
805 const Eigen::Matrix6d& artInertia, const Eigen::Vector6d& spatialAcc);
806
808 const Eigen::Matrix6d& artInertia, const Eigen::Vector6d& velocityChange);
809
811 const Eigen::Matrix6d& artInertia, const Eigen::Vector6d& velocityChange);
812
813 void updateConstrainedTermsDynamic(double timeStep);
814
815 void updateConstrainedTermsKinematic(double timeStep);
816
818};
819
820} // namespace dynamics
821} // namespace dart
822
823#include "dart/dynamics/detail/GenericJoint.hpp"
824
825#endif // DART_DYNAMICS_GENERICJOINT_HPP_
BodyPropPtr properties
Definition SdfParser.cpp:80
std::string * name
Definition SkelParser.cpp:1697
bool * preserveName
Definition SkelParser.cpp:1696
Eigen::VectorXd velocity
Definition SkelParser.cpp:109
Eigen::VectorXd force
Definition SkelParser.cpp:111
std::size_t index
Definition SkelParser.cpp:1672
Eigen::VectorXd acceleration
Definition SkelParser.cpp:110
double * friction
Definition SkelParser.cpp:1694
Eigen::VectorXd position
Definition SkelParser.cpp:108
This is an alternative to EmbedStateAndProperties which allows your class to also inherit other Compo...
Definition EmbeddedAspect.hpp:435
typename Impl::AspectState AspectState
Definition EmbeddedAspect.hpp:440
typename Impl::Aspect Aspect
Definition EmbeddedAspect.hpp:443
typename Impl::AspectProperties AspectProperties
Definition EmbeddedAspect.hpp:442
DegreeOfFreedom class is a proxy class for accessing single degrees of freedom (aka generalized coord...
Definition DegreeOfFreedom.hpp:56
Definition GenericJoint.hpp:49
void setAspectState(const AspectState &state)
Set the AspectState of this GenericJoint.
Definition GenericJoint.hpp:113
void setForceLowerLimits(const Eigen::VectorXd &lowerLimits) override
Definition GenericJoint.hpp:1239
double getCommand(std::size_t index) const override
Definition GenericJoint.hpp:389
typename ConfigSpaceT::Matrix Matrix
Definition GenericJoint.hpp:60
void addChildArtInertiaImplicitToKinematic(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia)
Definition GenericJoint.hpp:1840
Eigen::VectorXd getCommands() const override
Definition GenericJoint.hpp:475
void resetVelocities() override
Definition GenericJoint.hpp:945
const Vector & getPositionsStatic() const
Fixed-size version of getPositions()
Definition GenericJoint.hpp:733
void setAccelerationsStatic(const Vector &accels)
Fixed-size version of setAccelerations()
Definition GenericJoint.hpp:759
void copy(const ThisClass &otherJoint)
Copy the Properties of another GenericJoint.
Definition GenericJoint.hpp:158
void setForceUpperLimits(const Eigen::VectorXd &upperLimits) override
Definition GenericJoint.hpp:1286
void updateTotalImpulseKinematic(const Eigen::Vector6d &bodyImpulse)
Definition GenericJoint.hpp:2203
void setCoulombFriction(std::size_t index, double friction) override
Definition GenericJoint.hpp:1515
const JacobianMatrix & getRelativeJacobianTimeDerivStatic() const
Fixed-size version of getRelativeJacobianTimeDeriv()
Definition GenericJoint.hpp:1598
void setRestPosition(std::size_t index, double q0) override
Definition GenericJoint.hpp:1461
Vector mTotalForce
Total force projected on joint space.
Definition GenericJoint.hpp:723
void setAccelerations(const Eigen::VectorXd &accelerations) override
Definition GenericJoint.hpp:1035
Vector mInvM_a
Definition GenericJoint.hpp:733
void updateTotalImpulse(const Eigen::Vector6d &bodyImpulse) override
Definition GenericJoint.hpp:2169
void updateForceFD(const Eigen::Vector6d &bodyForce, double timeStep, bool withDampingForcese, bool withSpringForces) override
Definition GenericJoint.hpp:2350
const Matrix & getInvProjArtInertiaImplicit() const
Get the inverse of projected articulated inertia for implicit joint damping and spring forces.
Definition GenericJoint.hpp:1738
Eigen::VectorXd getPositionUpperLimits() const override
Definition GenericJoint.hpp:632
Vector mVelocityChanges
Change of generalized velocity.
Definition GenericJoint.hpp:686
void setVelocityUpperLimits(const Eigen::VectorXd &upperLimits) override
Definition GenericJoint.hpp:911
void updateForceID(const Eigen::Vector6d &bodyForce, double timeStep, bool withDampingForces, bool withSpringForces) override
Definition GenericJoint.hpp:2316
Eigen::VectorXd getAccelerationUpperLimits() const override
Definition GenericJoint.hpp:1147
void updateAccelerationKinematic(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc)
Definition GenericJoint.hpp:2258
void updateVelocityChangeDynamic(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &velocityChange)
Definition GenericJoint.hpp:2291
Eigen::VectorXd getVelocityLowerLimits() const override
Definition GenericJoint.hpp:877
void updateInvProjArtInertiaImplicit(const Eigen::Matrix6d &artInertia, double timeStep) override
Definition GenericJoint.hpp:1899
void setVelocityLowerLimits(const Eigen::VectorXd &lowerLimits) override
Definition GenericJoint.hpp:863
void updateConstrainedTermsDynamic(double timeStep)
Definition GenericJoint.hpp:2430
void setPositionLowerLimit(std::size_t index, double position) override
Definition GenericJoint.hpp:543
const GenericJoint< ConfigSpaceT >::JacobianMatrix & getRelativeJacobianStatic() const
Fixed-size version of getRelativeJacobian()
Definition GenericJoint.hpp:1568
void addChildArtInertiaToDynamic(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia)
Definition GenericJoint.hpp:1771
const math::Jacobian getRelativeJacobianTimeDeriv() const override
Definition GenericJoint.hpp:1589
void setVelocities(const Eigen::VectorXd &velocities) override
Definition GenericJoint.hpp:812
void addChildBiasImpulseToKinematic(Eigen::Vector6d &parentBiasImpulse, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasImpulse)
Definition GenericJoint.hpp:2088
void addChildArtInertiaImplicitTo(Eigen::Matrix6d &parentArtInertiaImplicit, const Eigen::Matrix6d &childArtInertiaImplicit) override
Definition GenericJoint.hpp:1799
void setPosition(std::size_t index, double position) override
Definition GenericJoint.hpp:489
void updateVelocityChange(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &velocityChange) override
Definition GenericJoint.hpp:2267
void setCommand(std::size_t index, double command) override
Definition GenericJoint.hpp:319
std::array< DegreeOfFreedom *, NumDofs > mDofs
Array of DegreeOfFreedom objects.
Definition GenericJoint.hpp:679
void setInitialPosition(std::size_t index, double initial) override
Definition GenericJoint.hpp:673
Eigen::VectorXd getForces() const override
Definition GenericJoint.hpp:1206
void resetCommands() override
Definition GenericJoint.hpp:482
void setVelocityChange(std::size_t index, double velocityChange) override
Definition GenericJoint.hpp:1317
typename Base::AspectState AspectState
Definition GenericJoint.hpp:64
void setAccelerationUpperLimits(const Eigen::VectorXd &upperLimits) override
Definition GenericJoint.hpp:1133
void setPartialAccelerationTo(Eigen::Vector6d &partialAcceleration, const Eigen::Vector6d &childVelocity) override
Definition GenericJoint.hpp:1690
double getVelocity(std::size_t index) const override
Definition GenericJoint.hpp:799
Eigen::Vector6d getBodyConstraintWrench() const override
Definition GenericJoint.hpp:1645
void addAccelerationTo(Eigen::Vector6d &acc) override
Definition GenericJoint.hpp:1704
void updateTotalImpulseDynamic(const Eigen::Vector6d &bodyImpulse)
Definition GenericJoint.hpp:2193
void setForce(std::size_t index, double force) override
Definition GenericJoint.hpp:1161
Vector mConstraintImpulses
Generalized constraint impulse.
Definition GenericJoint.hpp:692
void setInitialVelocity(std::size_t index, double initial) override
Definition GenericJoint.hpp:952
double getForce(std::size_t index) const override
Definition GenericJoint.hpp:1177
void setInitialVelocities(const Eigen::VectorXd &initial) override
Definition GenericJoint.hpp:979
void updateInvProjArtInertiaDynamic(const Eigen::Matrix6d &artInertia)
Definition GenericJoint.hpp:1875
void setPositionUpperLimit(std::size_t index, double position) override
Definition GenericJoint.hpp:591
void updateInvProjArtInertiaImplicitKinematic(const Eigen::Matrix6d &artInertia, double timeStep)
Definition GenericJoint.hpp:1944
const math::Jacobian getRelativeJacobian() const override
Definition GenericJoint.hpp:1560
std::size_t getNumDofs() const override
Definition GenericJoint.hpp:211
void resetForces() override
Definition GenericJoint.hpp:1307
DegreeOfFreedom * getDof(std::size_t index) override
void addChildArtInertiaTo(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia) override
Definition GenericJoint.hpp:1747
Eigen::VectorXd getPositionLowerLimits() const override
Definition GenericJoint.hpp:584
bool isDofNamePreserved(size_t index) const override
Definition GenericJoint.hpp:263
void addVelocityTo(Eigen::Vector6d &vel) override
Definition GenericJoint.hpp:1679
void preserveDofName(size_t index, bool preserve) override
Definition GenericJoint.hpp:250
double getVelocityUpperLimit(std::size_t index) const override
Definition GenericJoint.hpp:898
double getVelocityChange(std::size_t index) const override
Definition GenericJoint.hpp:1331
Vector mTotalImpulse
Total impluse projected on joint space.
Definition GenericJoint.hpp:726
void updateTotalForce(const Eigen::Vector6d &bodyForce, double timeStep) override
Definition GenericJoint.hpp:2101
void resetConstraintImpulses() override
Definition GenericJoint.hpp:1378
virtual Vector getPositionDifferencesStatic(const Vector &q2, const Vector &q1) const
Fixed-size version of getPositionDifferences()
Definition GenericJoint.hpp:1424
void setVelocity(std::size_t index, double velocity) override
Definition GenericJoint.hpp:778
double getRestPosition(std::size_t index) const override
Definition GenericJoint.hpp:1474
void updateConstrainedTerms(double timeStep) override
Definition GenericJoint.hpp:2407
void integrateVelocities(double dt) override
Definition GenericJoint.hpp:1397
Eigen::VectorXd getPositions() const override
Definition GenericJoint.hpp:536
void addChildBiasImpulseToDynamic(Eigen::Vector6d &parentBiasImpulse, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasImpulse)
Definition GenericJoint.hpp:2068
double getAcceleration(std::size_t index) const override
Definition GenericJoint.hpp:1022
Eigen::VectorXd getVelocities() const override
Definition GenericJoint.hpp:829
Eigen::VectorXd getInitialPositions() const override
Definition GenericJoint.hpp:714
Eigen::VectorXd getPositionDifferences(const Eigen::VectorXd &q2, const Eigen::VectorXd &q1) const override
Definition GenericJoint.hpp:1405
void setPositionLowerLimits(const Eigen::VectorXd &lowerLimits) override
Definition GenericJoint.hpp:570
double getAccelerationUpperLimit(std::size_t index) const override
Definition GenericJoint.hpp:1120
Matrix mInvProjArtInertia
Inverse of projected articulated inertia.
Definition GenericJoint.hpp:713
void setForceLowerLimit(size_t index, double force) override
Definition GenericJoint.hpp:1213
void setSpringStiffness(std::size_t index, double k) override
Definition GenericJoint.hpp:1433
void updateRelativePrimaryAcceleration() const override
Definition GenericJoint.hpp:1671
void setProperties(const Properties &properties)
Set the Properties of this GenericJoint.
Definition GenericJoint.hpp:97
double getForceLowerLimit(std::size_t index) const override
Definition GenericJoint.hpp:1226
static constexpr std::size_t NumDofs
Definition GenericJoint.hpp:51
const Vector & getVelocitiesStatic() const
Fixed-size version of getVelocities()
Definition GenericJoint.hpp:752
double getPositionUpperLimit(std::size_t index) const override
Definition GenericJoint.hpp:605
const std::string & getDofName(size_t index) const override
Definition GenericJoint.hpp:276
double computePotentialEnergy() const override
Definition GenericJoint.hpp:1544
double getSpringStiffness(std::size_t index) const override
Definition GenericJoint.hpp:1448
void setDampingCoefficient(std::size_t index, double coeff) override
Definition GenericJoint.hpp:1487
void updateInvProjArtInertia(const Eigen::Matrix6d &artInertia) override
Definition GenericJoint.hpp:1851
void resetVelocity(std::size_t index) override
Definition GenericJoint.hpp:932
JacobianMatrix mJacobianDeriv
Time derivative of spatial Jacobian expressed in the child body frame.
Definition GenericJoint.hpp:708
void setPositionsStatic(const Vector &positions)
Fixed-size version of setPositions()
Definition GenericJoint.hpp:721
void addChildBiasForceForInvAugMassMatrix(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce) override
Definition GenericJoint.hpp:2471
void updateConstrainedTermsKinematic(double timeStep)
Definition GenericJoint.hpp:2443
void setAccelerationLowerLimits(const Eigen::VectorXd &lowerLimits) override
Definition GenericJoint.hpp:1086
void setAspectProperties(const AspectProperties &properties)
Set the AspectProperties of this GenericJoint.
Definition GenericJoint.hpp:124
Eigen::VectorXd getForceUpperLimits() const override
Definition GenericJoint.hpp:1300
void updateImpulseFD(const Eigen::Vector6d &bodyImpulse) override
Definition GenericJoint.hpp:2384
void updateInvProjArtInertiaImplicitDynamic(const Eigen::Matrix6d &artInertia, double timeStep)
Definition GenericJoint.hpp:1923
void updateTotalForceKinematic(const Eigen::Vector6d &bodyForce, double timeStep)
Definition GenericJoint.hpp:2161
void resetTotalImpulses() override
Definition GenericJoint.hpp:2211
void integratePositions(double dt) override
Definition GenericJoint.hpp:1385
void setPositions(const Eigen::VectorXd &positions) override
Definition GenericJoint.hpp:523
void addChildBiasForceToDynamic(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce, const Eigen::Vector6d &childPartialAcc)
Definition GenericJoint.hpp:1981
Eigen::VectorXd getForceLowerLimits() const override
Definition GenericJoint.hpp:1253
double getInitialVelocity(std::size_t index) const override
Definition GenericJoint.hpp:966
Eigen::VectorXd getAccelerations() const override
Definition GenericJoint.hpp:1052
typename ConfigSpaceT::Vector Vector
Definition GenericJoint.hpp:58
void updateVelocityChangeKinematic(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &velocityChange)
Definition GenericJoint.hpp:2307
const Vector & getAccelerationsStatic() const
Fixed-size version of getAccelerations()
Definition GenericJoint.hpp:771
Eigen::VectorXd getInitialVelocities() const override
Definition GenericJoint.hpp:993
void setCommands(const Eigen::VectorXd &commands) override
Definition GenericJoint.hpp:402
Eigen::VectorXd getSpatialToGeneralized(const Eigen::Vector6d &spatial) override
Definition GenericJoint.hpp:2559
typename ConfigSpaceT::JacobianMatrix JacobianMatrix
Definition GenericJoint.hpp:59
void getInvAugMassMatrixSegment(Eigen::MatrixXd &invMassMat, const size_t col, const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) override
Definition GenericJoint.hpp:2526
double getVelocityLowerLimit(std::size_t index) const override
Definition GenericJoint.hpp:850
void updateImpulseID(const Eigen::Vector6d &bodyImpulse) override
Definition GenericJoint.hpp:2376
void setVelocityLowerLimit(std::size_t index, double velocity) override
Definition GenericJoint.hpp:836
double getInitialPosition(std::size_t index) const override
Definition GenericJoint.hpp:687
void updateAcceleration(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) override
Definition GenericJoint.hpp:2218
Vector mInvMassMatrixSegment
Definition GenericJoint.hpp:736
void addChildBiasForceToKinematic(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce, const Eigen::Vector6d &childPartialAcc)
Definition GenericJoint.hpp:2011
void setVelocityUpperLimit(std::size_t index, double velocity) override
Definition GenericJoint.hpp:884
typename ConfigSpaceT::Point Point
Definition GenericJoint.hpp:56
void updateInvProjArtInertiaKinematic(const Eigen::Matrix6d &artInertia)
Definition GenericJoint.hpp:1891
bool hasPositionLimit(std::size_t index) const override
Definition GenericJoint.hpp:639
JacobianMatrix mJacobian
Spatial Jacobian expressed in the child body frame.
Definition GenericJoint.hpp:702
void setInitialPositions(const Eigen::VectorXd &initial) override
Definition GenericJoint.hpp:700
void addChildBiasForceTo(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce, const Eigen::Vector6d &childPartialAcc) override
Definition GenericJoint.hpp:1952
double getCoulombFriction(std::size_t index) const override
Definition GenericJoint.hpp:1531
void addInvMassMatrixSegmentTo(Eigen::Vector6d &acc) override
Definition GenericJoint.hpp:2551
Vector mImpulses
Generalized impulse.
Definition GenericJoint.hpp:689
void setConstraintImpulse(std::size_t index, double impulse) override
Definition GenericJoint.hpp:1351
void resetPosition(std::size_t index) override
Definition GenericJoint.hpp:653
double getForceUpperLimit(size_t index) const override
Definition GenericJoint.hpp:1273
void registerDofs() override
Definition GenericJoint.hpp:1632
void addVelocityChangeTo(Eigen::Vector6d &velocityChange) override
Definition GenericJoint.hpp:1715
const std::string & setDofName(std::size_t index, const std::string &name, bool preserveName=true) override
Definition GenericJoint.hpp:218
void setAccelerationUpperLimit(std::size_t index, double acceleration) override
Definition GenericJoint.hpp:1107
double getDampingCoefficient(std::size_t index) const override
Definition GenericJoint.hpp:1502
typename Base::AspectProperties AspectProperties
Definition GenericJoint.hpp:65
Matrix mInvProjArtInertiaImplicit
Inverse of projected articulated inertia for implicit joint damping and spring forces.
Definition GenericJoint.hpp:720
void setPositionUpperLimits(const Eigen::VectorXd &upperLimits) override
Definition GenericJoint.hpp:618
Eigen::VectorXd getAccelerationLowerLimits() const override
Definition GenericJoint.hpp:1100
void updateTotalForceDynamic(const Eigen::Vector6d &bodyForce, double timeStep)
Definition GenericJoint.hpp:2140
void setVelocitiesStatic(const Vector &velocities)
Fixed-size version of setVelocities()
Definition GenericJoint.hpp:740
void updateRelativeSpatialAcceleration() const override
Definition GenericJoint.hpp:1662
void updateRelativeSpatialVelocity() const override
Definition GenericJoint.hpp:1654
void setForceUpperLimit(size_t index, double force) override
Definition GenericJoint.hpp:1260
size_t getIndexInTree(size_t index) const override
Definition GenericJoint.hpp:306
Eigen::VectorXd getVelocityUpperLimits() const override
Definition GenericJoint.hpp:925
void setAccelerationLowerLimit(size_t index, double acceleration) override
Definition GenericJoint.hpp:1059
double getPosition(std::size_t index) const override
Definition GenericJoint.hpp:510
void addChildArtInertiaImplicitToDynamic(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia)
Definition GenericJoint.hpp:1823
double getAccelerationLowerLimit(std::size_t index) const override
Definition GenericJoint.hpp:1073
void addChildBiasImpulseTo(Eigen::Vector6d &parentBiasImpulse, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasImpulse) override
Definition GenericJoint.hpp:2040
double getPositionLowerLimit(std::size_t index) const override
Definition GenericJoint.hpp:557
void updateAccelerationDynamic(const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc)
Definition GenericJoint.hpp:2242
void resetPositions() override
Definition GenericJoint.hpp:666
void addChildBiasForceForInvMassMatrix(Eigen::Vector6d &parentBiasForce, const Eigen::Matrix6d &childArtInertia, const Eigen::Vector6d &childBiasForce) override
Definition GenericJoint.hpp:2451
void getInvMassMatrixSegment(Eigen::MatrixXd &invMassMat, const size_t col, const Eigen::Matrix6d &artInertia, const Eigen::Vector6d &spatialAcc) override
Definition GenericJoint.hpp:2501
typename ConfigSpaceT::EuclideanPoint EuclideanPoint
Definition GenericJoint.hpp:57
Properties getGenericJointProperties() const
Get the Properties of this GenericJoint.
Definition GenericJoint.hpp:150
const Matrix & getInvProjArtInertia() const
Get the inverse of the projected articulated inertia.
Definition GenericJoint.hpp:1728
void setForces(const Eigen::VectorXd &forces) override
Definition GenericJoint.hpp:1190
void updateTotalForceForInvMassMatrix(const Eigen::Vector6d &bodyForce) override
Definition GenericJoint.hpp:2491
void resetAccelerations() override
Definition GenericJoint.hpp:1154
void setAcceleration(std::size_t index, double acceleration) override
Definition GenericJoint.hpp:1000
void addChildArtInertiaToKinematic(Eigen::Matrix6d &parentArtInertia, const Eigen::Matrix6d &childArtInertia)
Definition GenericJoint.hpp:1788
double getConstraintImpulse(std::size_t index) const override
Definition GenericJoint.hpp:1365
size_t getIndexInSkeleton(size_t index) const override
Definition GenericJoint.hpp:293
void resetVelocityChanges() override
Definition GenericJoint.hpp:1344
#define DART_BAKE_SPECIALIZED_ASPECT_IRREGULAR(TypeName, AspectName)
Definition Composite.hpp:164
Definition Random-impl.hpp:92
Definition BulletCollisionDetector.cpp:60
Definition SharedLibraryManager.hpp:46
Definition GenericJointAspect.hpp:191
Definition GenericJointAspect.hpp:88