Skip to content

Commit e1f5ceb

Browse files
yuvaltassacopybara-github
authored andcommitted
Add mjModel.tendon_armature (in preparation, not yet implemented)
PiperOrigin-RevId: 743649968 Change-Id: I1d893e3e06afc48b652575bc7837750ab3573670
1 parent f96f3e1 commit e1f5ceb

File tree

14 files changed

+140
-11
lines changed

14 files changed

+140
-11
lines changed

doc/XMLreference.rst

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -835,7 +835,7 @@ has any effect. The settings here are global and apply to the entire model.
835835
.. _compiler-saveinertial:
836836

837837
:at:`saveinertial`: :at-val:`[false, true], "false"`
838-
If set to "true", the compiler will save explicit :ref:`inertial <body-inerital>` clauses for all bodies.
838+
If set to "true", the compiler will save explicit :ref:`inertial <body-inertial>` clauses for all bodies.
839839

840840
.. _compiler-lengthrange:
841841

@@ -4706,6 +4706,13 @@ length X, as in the clip on the right of `this example model
47064706
joint damping which is integrated implicitly by the Euler method, tendon damping is not integrated implicitly, thus
47074707
joint damping should be used if possible.
47084708

4709+
.. TODO(tassa): Update here once the feature is implemented.
4710+
4711+
.. _tendon-spatial-armature:
4712+
4713+
:at:`armature`: :at-val:`real, "0"`
4714+
Inertia associated with tendon. This feature is not yet implemented.
4715+
47094716
.. _tendon-spatial-user:
47104717

47114718
:at:`user`: :at-val:`real(nuser_tendon), "0 0 ..."`
@@ -4815,6 +4822,8 @@ as above.
48154822

48164823
.. _tendon-fixed-damping:
48174824

4825+
.. _tendon-fixed-armature:
4826+
48184827
.. _tendon-fixed-user:
48194828

48204829
.. |tendon/fixed attrib list| replace::

doc/XMLschema.rst

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -627,7 +627,7 @@
627627
| | | +-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+ |
628628
| | | | :ref:`material<tendon-spatial-material>` | :ref:`margin<tendon-spatial-margin>` | :ref:`stiffness<tendon-spatial-stiffness>` | :ref:`damping<tendon-spatial-damping>` | |
629629
| | | +-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+ |
630-
| | | | :ref:`rgba<tendon-spatial-rgba>` | :ref:`user<tendon-spatial-user>` | | | |
630+
| | | | :ref:`armature<tendon-spatial-armature>` | :ref:`rgba<tendon-spatial-rgba>` | :ref:`user<tendon-spatial-user>` | | |
631631
| | | +-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+ |
632632
+------------------------------------+----+------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------+
633633
| |_2| spatial |br| |_2| |L| | | .. table:: |
@@ -661,7 +661,7 @@
661661
| | | +-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+ |
662662
| | | | :ref:`solimpfriction<tendon-fixed-solimpfriction>` | :ref:`frictionloss<tendon-fixed-frictionloss>` | :ref:`springlength<tendon-fixed-springlength>` | :ref:`margin<tendon-fixed-margin>` | |
663663
| | | +-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+ |
664-
| | | | :ref:`stiffness<tendon-fixed-stiffness>` | :ref:`damping<tendon-fixed-damping>` | :ref:`user<tendon-fixed-user>` | | |
664+
| | | | :ref:`stiffness<tendon-fixed-stiffness>` | :ref:`damping<tendon-fixed-damping>` | :ref:`armature<tendon-fixed-armature>` | :ref:`user<tendon-fixed-user>` | |
665665
| | | +-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+ |
666666
+------------------------------------+----+------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------+
667667
| |_2| fixed |br| |_2| |L| | | .. table:: |

doc/includes/references.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1339,6 +1339,7 @@ struct mjModel_ {
13391339
mjtNum* tendon_margin; // min distance for limit detection (ntendon x 1)
13401340
mjtNum* tendon_stiffness; // stiffness coefficient (ntendon x 1)
13411341
mjtNum* tendon_damping; // damping coefficient (ntendon x 1)
1342+
mjtNum* tendon_armature; // inertia associated with tendon velocity (ntendon x 1)
13421343
mjtNum* tendon_frictionloss; // loss due to friction (ntendon x 1)
13431344
mjtNum* tendon_lengthspring; // spring resting length range (ntendon x 2)
13441345
mjtNum* tendon_length0; // tendon length in qpos0 (ntendon x 1)
@@ -2174,13 +2175,14 @@ typedef struct mjsTendon_ { // tendon specification
21742175
mjsElement* element; // element type
21752176
mjString* name; // name
21762177

2177-
// stiffness, damping, friction
2178+
// stiffness, damping, friction, armature
21782179
double stiffness; // stiffness coefficient
21792180
double springlength[2]; // spring resting length; {-1, -1}: use qpos_spring
21802181
double damping; // damping coefficient
21812182
double frictionloss; // friction loss
21822183
mjtNum solref_friction[mjNREF]; // solver reference: tendon friction
21832184
mjtNum solimp_friction[mjNIMP]; // solver impedance: tendon friction
2185+
double armature; // inertia associated with tendon velocity
21842186

21852187
// length range
21862188
int limited; // does tendon have limits (mjtLimited)

include/mujoco/mjmodel.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1040,6 +1040,7 @@ struct mjModel_ {
10401040
mjtNum* tendon_margin; // min distance for limit detection (ntendon x 1)
10411041
mjtNum* tendon_stiffness; // stiffness coefficient (ntendon x 1)
10421042
mjtNum* tendon_damping; // damping coefficient (ntendon x 1)
1043+
mjtNum* tendon_armature; // inertia associated with tendon velocity (ntendon x 1)
10431044
mjtNum* tendon_frictionloss; // loss due to friction (ntendon x 1)
10441045
mjtNum* tendon_lengthspring; // spring resting length range (ntendon x 2)
10451046
mjtNum* tendon_length0; // tendon length in qpos0 (ntendon x 1)

include/mujoco/mjspec.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -617,13 +617,14 @@ typedef struct mjsTendon_ { // tendon specification
617617
mjsElement* element; // element type
618618
mjString* name; // name
619619

620-
// stiffness, damping, friction
620+
// stiffness, damping, friction, armature
621621
double stiffness; // stiffness coefficient
622622
double springlength[2]; // spring resting length; {-1, -1}: use qpos_spring
623623
double damping; // damping coefficient
624624
double frictionloss; // friction loss
625625
mjtNum solref_friction[mjNREF]; // solver reference: tendon friction
626626
mjtNum solimp_friction[mjNIMP]; // solver impedance: tendon friction
627+
double armature; // inertia associated with tendon velocity
627628

628629
// length range
629630
int limited; // does tendon have limits (mjtLimited)

include/mujoco/mjxmacro.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -484,6 +484,7 @@
484484
X ( mjtNum, tendon_margin, ntendon, 1 ) \
485485
XMJV( mjtNum, tendon_stiffness, ntendon, 1 ) \
486486
XMJV( mjtNum, tendon_damping, ntendon, 1 ) \
487+
X ( mjtNum, tendon_armature, ntendon, 1 ) \
487488
XMJV( mjtNum, tendon_frictionloss, ntendon, 1 ) \
488489
XMJV( mjtNum, tendon_lengthspring, ntendon, 2 ) \
489490
X ( mjtNum, tendon_length0, ntendon, 1 ) \

mjx/mujoco/mjx/_src/types.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -771,6 +771,7 @@ class Model(PyTreeNode):
771771
tendon_margin: min distance for limit detection (ntendon,)
772772
tendon_stiffness: stiffness coefficient (ntendon,)
773773
tendon_damping: damping coefficient (ntendon,)
774+
tendon_armature: inertia associated with tendon velocity (ntendon,)
774775
tendon_frictionloss: loss due to friction (ntendon,)
775776
tendon_lengthspring: spring resting length range (ntendon, 2)
776777
tendon_length0: tendon length in qpos0 (ntendon,)
@@ -1113,6 +1114,7 @@ class Model(PyTreeNode):
11131114
tendon_margin: jax.Array
11141115
tendon_stiffness: jax.Array
11151116
tendon_damping: jax.Array
1117+
tendon_armature: jax.Array
11161118
tendon_frictionloss: jax.Array
11171119
tendon_lengthspring: jax.Array
11181120
tendon_length0: jax.Array

python/mujoco/introspect/structs.py

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3687,6 +3687,14 @@
36873687
doc='damping coefficient',
36883688
array_extent=('ntendon',),
36893689
),
3690+
StructFieldDecl(
3691+
name='tendon_armature',
3692+
type=PointerType(
3693+
inner_type=ValueType(name='mjtNum'),
3694+
),
3695+
doc='inertia associated with tendon velocity',
3696+
array_extent=('ntendon',),
3697+
),
36903698
StructFieldDecl(
36913699
name='tendon_frictionloss',
36923700
type=PointerType(
@@ -11324,6 +11332,11 @@
1132411332
),
1132511333
doc='solver impedance: tendon friction',
1132611334
),
11335+
StructFieldDecl(
11336+
name='armature',
11337+
type=ValueType(name='double'),
11338+
doc='inertia associated with tendon velocity',
11339+
),
1132711340
StructFieldDecl(
1132811341
name='limited',
1132911342
type=ValueType(name='int'),

src/user/user_model.cc

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3390,6 +3390,7 @@ void mjCModel::CopyObjects(mjModel* m) {
33903390
m->tendon_margin[i] = (mjtNum)pte->margin;
33913391
m->tendon_stiffness[i] = (mjtNum)pte->stiffness;
33923392
m->tendon_damping[i] = (mjtNum)pte->damping;
3393+
m->tendon_armature[i] = (mjtNum)pte->armature;
33933394
m->tendon_frictionloss[i] = (mjtNum)pte->frictionloss;
33943395
m->tendon_lengthspring[2*i] = (mjtNum)pte->springlength[0];
33953396
m->tendon_lengthspring[2*i+1] = (mjtNum)pte->springlength[1];
@@ -4931,6 +4932,7 @@ bool mjCModel::CopyBack(const mjModel* m) {
49314932
tendons_[i]->margin = (double)m->tendon_margin[i];
49324933
tendons_[i]->stiffness = (double)m->tendon_stiffness[i];
49334934
tendons_[i]->damping = (double)m->tendon_damping[i];
4935+
tendons_[i]->armature = (double)m->tendon_armature[i];
49344936
tendons_[i]->frictionloss = (double)m->tendon_frictionloss[i];
49354937

49364938
if (nuser_tendon) {

src/user/user_objects.cc

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5616,6 +5616,12 @@ void mjCTendon::Compile(void) {
56165616

56175617
// spatial path
56185618
else {
5619+
if (armature < 0) {
5620+
throw mjCError(this,
5621+
"tendon '%s' (id = %d): tendon armature cannot be negative",
5622+
name.c_str(), id);
5623+
}
5624+
56195625
switch (path[i]->type) {
56205626
case mjWRAP_PULLEY:
56215627
// pulley should not follow other pulley
@@ -5657,6 +5663,12 @@ void mjCTendon::Compile(void) {
56575663
name.c_str(), id, i);
56585664
}
56595665

5666+
if (armature > 0) {
5667+
throw mjCError(this,
5668+
"tendon '%s' (id = %d): geom wrapping not supported by tendon armature",
5669+
name.c_str(), id);
5670+
}
5671+
56605672
// mark geoms as non visual
56615673
model->Geoms()[path[i]->obj->id]->SetNotVisual();
56625674
break;

0 commit comments

Comments
 (0)