Skip to content

Commit d77ecb3

Browse files
yuvaltassacopybara-github
authored andcommitted
Move mjtConstraintState from mjmodel.h to mjdata.h.
This is the correct location, this enum is only used in `mjData`, not `mjModel`. PiperOrigin-RevId: 798860951 Change-Id: I48b9a2afc831bd9a6966cc9586429fd03605bdd2
1 parent 1c1bb14 commit d77ecb3

File tree

6 files changed

+45
-44
lines changed

6 files changed

+45
-44
lines changed

doc/APIreference/APItypes.rst

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -338,15 +338,6 @@ of active constraints is constructed at each simulation time step.
338338

339339
.. mujoco-include:: mjtConstraint
340340

341-
.. _mjtConstraintState:
342-
343-
mjtConstraintState
344-
~~~~~~~~~~~~~~~~~~
345-
346-
These values are used by the solver internally to keep track of the constraint states.
347-
348-
.. mujoco-include:: mjtConstraintState
349-
350341

351342
.. _mjtSensor:
352343

@@ -440,6 +431,16 @@ State component elements as integer bitflags and several convenient combinations
440431
.. mujoco-include:: mjtState
441432

442433

434+
.. _mjtConstraintState:
435+
436+
mjtConstraintState
437+
~~~~~~~~~~~~~~~~~~
438+
439+
These values are used by the solver internally to keep track of the constraint states.
440+
441+
.. mujoco-include:: mjtConstraintState
442+
443+
443444
.. _mjtWarning:
444445

445446
mjtWarning

doc/includes/references.h

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,13 @@ typedef enum mjtState_ { // state elements
4141
mjSTATE_USERDATA,
4242
mjSTATE_INTEGRATION = mjSTATE_FULLPHYSICS | mjSTATE_USER | mjSTATE_WARMSTART
4343
} mjtState;
44+
typedef enum mjtConstraintState_ { // constraint state
45+
mjCNSTRSTATE_SATISFIED = 0, // constraint satisfied, zero cost (limit, contact)
46+
mjCNSTRSTATE_QUADRATIC, // quadratic cost (equality, friction, limit, contact)
47+
mjCNSTRSTATE_LINEARNEG, // linear cost, negative side (friction)
48+
mjCNSTRSTATE_LINEARPOS, // linear cost, positive side (friction)
49+
mjCNSTRSTATE_CONE // squared distance to cone cost (elliptic contact)
50+
} mjtConstraintState;
4451
typedef enum mjtWarning_ { // warning types
4552
mjWARN_INERTIA = 0, // (near) singular inertia matrix
4653
mjWARN_CONTACTFULL, // too many contacts in contact list
@@ -642,13 +649,6 @@ typedef enum mjtConstraint_ { // type of constraint
642649
mjCNSTR_CONTACT_PYRAMIDAL, // frictional contact, pyramidal friction cone
643650
mjCNSTR_CONTACT_ELLIPTIC // frictional contact, elliptic friction cone
644651
} mjtConstraint;
645-
typedef enum mjtConstraintState_ { // constraint state
646-
mjCNSTRSTATE_SATISFIED = 0, // constraint satisfied, zero cost (limit, contact)
647-
mjCNSTRSTATE_QUADRATIC, // quadratic cost (equality, friction, limit, contact)
648-
mjCNSTRSTATE_LINEARNEG, // linear cost, negative side (friction)
649-
mjCNSTRSTATE_LINEARPOS, // linear cost, positive side (friction)
650-
mjCNSTRSTATE_CONE // squared distance to cone cost (elliptic contact)
651-
} mjtConstraintState;
652652
typedef enum mjtSensor_ { // type of sensor
653653
// common robotic sensors, attached to a site
654654
mjSENS_TOUCH = 0, // scalar contact normal forces summed over sensor zone

include/mujoco/mjdata.h

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,15 @@ typedef enum mjtState_ { // state elements
5151
} mjtState;
5252

5353

54+
typedef enum mjtConstraintState_ { // constraint state
55+
mjCNSTRSTATE_SATISFIED = 0, // constraint satisfied, zero cost (limit, contact)
56+
mjCNSTRSTATE_QUADRATIC, // quadratic cost (equality, friction, limit, contact)
57+
mjCNSTRSTATE_LINEARNEG, // linear cost, negative side (friction)
58+
mjCNSTRSTATE_LINEARPOS, // linear cost, positive side (friction)
59+
mjCNSTRSTATE_CONE // squared distance to cone cost (elliptic contact)
60+
} mjtConstraintState;
61+
62+
5463
typedef enum mjtWarning_ { // warning types
5564
mjWARN_INERTIA = 0, // (near) singular inertia matrix
5665
mjWARN_CONTACTFULL, // too many contacts in contact list

include/mujoco/mjmodel.h

Lines changed: 0 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -303,15 +303,6 @@ typedef enum mjtConstraint_ { // type of constraint
303303
} mjtConstraint;
304304

305305

306-
typedef enum mjtConstraintState_ { // constraint state
307-
mjCNSTRSTATE_SATISFIED = 0, // constraint satisfied, zero cost (limit, contact)
308-
mjCNSTRSTATE_QUADRATIC, // quadratic cost (equality, friction, limit, contact)
309-
mjCNSTRSTATE_LINEARNEG, // linear cost, negative side (friction)
310-
mjCNSTRSTATE_LINEARPOS, // linear cost, positive side (friction)
311-
mjCNSTRSTATE_CONE // squared distance to cone cost (elliptic contact)
312-
} mjtConstraintState;
313-
314-
315306
typedef enum mjtSensor_ { // type of sensor
316307
// common robotic sensors, attached to a site
317308
mjSENS_TOUCH = 0, // scalar contact normal forces summed over sensor zone

python/mujoco/introspect/enums.py

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -327,18 +327,6 @@
327327
('mjCNSTR_CONTACT_ELLIPTIC', 7),
328328
]),
329329
)),
330-
('mjtConstraintState',
331-
EnumDecl(
332-
name='mjtConstraintState',
333-
declname='enum mjtConstraintState_',
334-
values=dict([
335-
('mjCNSTRSTATE_SATISFIED', 0),
336-
('mjCNSTRSTATE_QUADRATIC', 1),
337-
('mjCNSTRSTATE_LINEARNEG', 2),
338-
('mjCNSTRSTATE_LINEARPOS', 3),
339-
('mjCNSTRSTATE_CONE', 4),
340-
]),
341-
)),
342330
('mjtSensor',
343331
EnumDecl(
344332
name='mjtSensor',
@@ -513,6 +501,18 @@
513501
('mjSTATE_INTEGRATION', 8191),
514502
]),
515503
)),
504+
('mjtConstraintState',
505+
EnumDecl(
506+
name='mjtConstraintState',
507+
declname='enum mjtConstraintState_',
508+
values=dict([
509+
('mjCNSTRSTATE_SATISFIED', 0),
510+
('mjCNSTRSTATE_QUADRATIC', 1),
511+
('mjCNSTRSTATE_LINEARNEG', 2),
512+
('mjCNSTRSTATE_LINEARPOS', 3),
513+
('mjCNSTRSTATE_CONE', 4),
514+
]),
515+
)),
516516
('mjtWarning',
517517
EnumDecl(
518518
name='mjtWarning',

unity/Runtime/Bindings/MjBindings.cs

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -115,6 +115,13 @@ public static class MujocoLib {
115115

116116

117117
// ------------------------------------Enums------------------------------------
118+
public enum mjtConstraintState : int{
119+
mjCNSTRSTATE_SATISFIED = 0,
120+
mjCNSTRSTATE_QUADRATIC = 1,
121+
mjCNSTRSTATE_LINEARNEG = 2,
122+
mjCNSTRSTATE_LINEARPOS = 3,
123+
mjCNSTRSTATE_CONE = 4,
124+
}
118125
public enum mjtWarning : int{
119126
mjWARN_INERTIA = 0,
120127
mjWARN_CONTACTFULL = 1,
@@ -344,13 +351,6 @@ public enum mjtConstraint : int{
344351
mjCNSTR_CONTACT_PYRAMIDAL = 6,
345352
mjCNSTR_CONTACT_ELLIPTIC = 7,
346353
}
347-
public enum mjtConstraintState : int{
348-
mjCNSTRSTATE_SATISFIED = 0,
349-
mjCNSTRSTATE_QUADRATIC = 1,
350-
mjCNSTRSTATE_LINEARNEG = 2,
351-
mjCNSTRSTATE_LINEARPOS = 3,
352-
mjCNSTRSTATE_CONE = 4,
353-
}
354354
public enum mjtSensor : int{
355355
mjSENS_TOUCH = 0,
356356
mjSENS_ACCELEROMETER = 1,

0 commit comments

Comments
 (0)