Skip to content

Commit

Permalink
Rename nnzJ to nJ in mjData.
Browse files Browse the repository at this point in the history
This naming is more consistent.

PiperOrigin-RevId: 691858223
Change-Id: Ife3db822afa0b51b30d0792548b35b3742da388a
  • Loading branch information
yuvaltassa authored and copybara-github committed Oct 31, 2024
1 parent 5546410 commit c9f78ad
Show file tree
Hide file tree
Showing 10 changed files with 33 additions and 34 deletions.
10 changes: 5 additions & 5 deletions doc/includes/references.h
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ struct mjData_ {
int nf; // number of friction constraints
int nl; // number of limit constraints
int nefc; // number of constraints
int nnzJ; // number of non-zeros in constraint Jacobian
int nJ; // number of non-zeros in constraint Jacobian
int nisland; // number of detected constraint islands

// global properties
Expand Down Expand Up @@ -361,13 +361,13 @@ struct mjData_ {
int* efc_J_rownnz; // number of non-zeros in constraint Jacobian row (nefc x 1)
int* efc_J_rowadr; // row start address in colind array (nefc x 1)
int* efc_J_rowsuper; // number of subsequent rows in supernode (nefc x 1)
int* efc_J_colind; // column indices in constraint Jacobian (nnzJ x 1)
int* efc_J_colind; // column indices in constraint Jacobian (nJ x 1)
int* efc_JT_rownnz; // number of non-zeros in constraint Jacobian row T (nv x 1)
int* efc_JT_rowadr; // row start address in colind array T (nv x 1)
int* efc_JT_rowsuper; // number of subsequent rows in supernode T (nv x 1)
int* efc_JT_colind; // column indices in constraint Jacobian T (nnzJ x 1)
mjtNum* efc_J; // constraint Jacobian (nnzJ x 1)
mjtNum* efc_JT; // constraint Jacobian transposed (nnzJ x 1)
int* efc_JT_colind; // column indices in constraint Jacobian T (nJ x 1)
mjtNum* efc_J; // constraint Jacobian (nJ x 1)
mjtNum* efc_JT; // constraint Jacobian transposed (nJ x 1)
mjtNum* efc_pos; // constraint position (equality, contact) (nefc x 1)
mjtNum* efc_margin; // inclusion margin (contact) (nefc x 1)
mjtNum* efc_frictionloss; // frictionloss (friction) (nefc x 1)
Expand Down
10 changes: 5 additions & 5 deletions include/mujoco/mjdata.h
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,7 @@ struct mjData_ {
int nf; // number of friction constraints
int nl; // number of limit constraints
int nefc; // number of constraints
int nnzJ; // number of non-zeros in constraint Jacobian
int nJ; // number of non-zeros in constraint Jacobian
int nisland; // number of detected constraint islands

// global properties
Expand Down Expand Up @@ -389,13 +389,13 @@ struct mjData_ {
int* efc_J_rownnz; // number of non-zeros in constraint Jacobian row (nefc x 1)
int* efc_J_rowadr; // row start address in colind array (nefc x 1)
int* efc_J_rowsuper; // number of subsequent rows in supernode (nefc x 1)
int* efc_J_colind; // column indices in constraint Jacobian (nnzJ x 1)
int* efc_J_colind; // column indices in constraint Jacobian (nJ x 1)
int* efc_JT_rownnz; // number of non-zeros in constraint Jacobian row T (nv x 1)
int* efc_JT_rowadr; // row start address in colind array T (nv x 1)
int* efc_JT_rowsuper; // number of subsequent rows in supernode T (nv x 1)
int* efc_JT_colind; // column indices in constraint Jacobian T (nnzJ x 1)
mjtNum* efc_J; // constraint Jacobian (nnzJ x 1)
mjtNum* efc_JT; // constraint Jacobian transposed (nnzJ x 1)
int* efc_JT_colind; // column indices in constraint Jacobian T (nJ x 1)
mjtNum* efc_J; // constraint Jacobian (nJ x 1)
mjtNum* efc_JT; // constraint Jacobian transposed (nJ x 1)
mjtNum* efc_pos; // constraint position (equality, contact) (nefc x 1)
mjtNum* efc_margin; // inclusion margin (contact) (nefc x 1)
mjtNum* efc_frictionloss; // frictionloss (friction) (nefc x 1)
Expand Down
10 changes: 5 additions & 5 deletions include/mujoco/mjxmacro.h
Original file line number Diff line number Diff line change
Expand Up @@ -689,13 +689,13 @@
X( int, efc_J_rownnz, MJ_D(nefc), 1 ) \
X( int, efc_J_rowadr, MJ_D(nefc), 1 ) \
X( int, efc_J_rowsuper, MJ_D(nefc), 1 ) \
X( int, efc_J_colind, MJ_D(nnzJ), 1 ) \
X( int, efc_J_colind, MJ_D(nJ), 1 ) \
X( int, efc_JT_rownnz, MJ_M(nv), 1 ) \
X( int, efc_JT_rowadr, MJ_M(nv), 1 ) \
X( int, efc_JT_rowsuper, MJ_M(nv), 1 ) \
X( int, efc_JT_colind, MJ_D(nnzJ), 1 ) \
X( mjtNum, efc_J, MJ_D(nnzJ), 1 ) \
X( mjtNum, efc_JT, MJ_D(nnzJ), 1 ) \
X( int, efc_JT_colind, MJ_D(nJ), 1 ) \
X( mjtNum, efc_J, MJ_D(nJ), 1 ) \
X( mjtNum, efc_JT, MJ_D(nJ), 1 ) \
X( mjtNum, efc_pos, MJ_D(nefc), 1 ) \
X( mjtNum, efc_margin, MJ_D(nefc), 1 ) \
X( mjtNum, efc_frictionloss, MJ_D(nefc), 1 ) \
Expand Down Expand Up @@ -755,7 +755,7 @@
X( int, nf ) \
X( int, nl ) \
X( int, nefc ) \
X( int, nnzJ ) \
X( int, nJ ) \
X( int, nisland ) \
X( mjtNum, time ) \
X( uintptr_t, threadpool )
Expand Down
10 changes: 5 additions & 5 deletions introspect/structs.py
Original file line number Diff line number Diff line change
Expand Up @@ -4692,7 +4692,7 @@
doc='number of constraints',
),
StructFieldDecl(
name='nnzJ',
name='nJ',
type=ValueType(name='int'),
doc='number of non-zeros in constraint Jacobian',
),
Expand Down Expand Up @@ -5588,7 +5588,7 @@
inner_type=ValueType(name='int'),
),
doc='column indices in constraint Jacobian',
array_extent=('nnzJ',),
array_extent=('nJ',),
),
StructFieldDecl(
name='efc_JT_rownnz',
Expand Down Expand Up @@ -5616,23 +5616,23 @@
type=PointerType(
inner_type=ValueType(name='int'),
),
doc='column indices in constraint Jacobian T (nnzJ x 1)', # pylint: disable=line-too-long
doc='column indices in constraint Jacobian T (nJ x 1)', # pylint: disable=line-too-long
),
StructFieldDecl(
name='efc_J',
type=PointerType(
inner_type=ValueType(name='mjtNum'),
),
doc='constraint Jacobian',
array_extent=('nnzJ',),
array_extent=('nJ',),
),
StructFieldDecl(
name='efc_JT',
type=PointerType(
inner_type=ValueType(name='mjtNum'),
),
doc='constraint Jacobian transposed',
array_extent=('nnzJ',),
array_extent=('nJ',),
),
StructFieldDecl(
name='efc_pos',
Expand Down
2 changes: 1 addition & 1 deletion mjx/mujoco/mjx/_src/io.py
Original file line number Diff line number Diff line change
Expand Up @@ -408,7 +408,7 @@ def get_data_into(
ncon = (d_i.contact.dist <= 0).sum()
efc_active = (d_i.efc_J != 0).any(axis=1)
nefc = int(efc_active.sum())
result_i.nnzJ = nefc * m.nv
result_i.nJ = nefc * m.nv
if ncon != result_i.ncon or nefc != result_i.nefc:
mujoco._functions._realloc_con_efc(result_i, ncon=ncon, nefc=nefc) # pylint: disable=protected-access
result_i.efc_J_rownnz[:] = np.repeat(m.nv, nefc)
Expand Down
4 changes: 2 additions & 2 deletions python/mujoco/structs.cc
Original file line number Diff line number Diff line change
Expand Up @@ -747,7 +747,7 @@ void MjDataWrapper::Serialize(std::ostream& output) const {
X(ncon);
X(ne);
X(nf);
X(nnzJ);
X(nJ);
X(nefc);
X(nisland);
X(time);
Expand Down Expand Up @@ -824,7 +824,7 @@ MjDataWrapper MjDataWrapper::Deserialize(std::istream& input) {
X(ncon);
X(ne);
X(nf);
X(nnzJ);
X(nJ);
X(nefc);
X(nisland);
X(time);
Expand Down
15 changes: 7 additions & 8 deletions src/engine/engine_core_constraint.c
Original file line number Diff line number Diff line change
Expand Up @@ -1943,21 +1943,21 @@ static int mj_nc(const mjModel* m, mjData* d, int* nnz) {
// driver: call all functions above
void mj_makeConstraint(const mjModel* m, mjData* d) {
// clear sizes
d->ne = d->nf = d->nl = d->nefc = d->nnzJ = 0;
d->ne = d->nf = d->nl = d->nefc = d->nJ = 0;

// disabled or Jacobian not allocated: return
if (mjDISABLED(mjDSBL_CONSTRAINT)) {
return;
}

// precount sizes for constraint Jacobian matrices
int *nnz = mj_isSparse(m) ? &(d->nnzJ) : NULL;
int *nnz = mj_isSparse(m) ? &(d->nJ) : NULL;
int ne_allocated = mj_ne(m, d, nnz);
int nf_allocated = mj_nf(m, d, nnz);
int nl_allocated = mj_nl(m, d, nnz);
int nefc_allocated = ne_allocated + nf_allocated + nl_allocated + mj_nc(m, d, nnz);
if (!mj_isSparse(m)) {
d->nnzJ = nefc_allocated * m->nv;
d->nJ = nefc_allocated * m->nv;
}
d->nefc = nefc_allocated;

Expand Down Expand Up @@ -1998,12 +1998,11 @@ void mj_makeConstraint(const mjModel* m, mjData* d) {
mjERROR("nefc mis-allocation: found nefc=%d but allocated %d", d->nefc, nefc_allocated);
}

// check that nnzJ was computed correctly
// check that nJ was computed correctly
if (d->nefc > 0) {
int nnzJ = d->efc_J_rownnz[d->nefc - 1] + d->efc_J_rowadr[d->nefc - 1];
if (d->nnzJ != nnzJ) {
mjERROR("constraint Jacobian mis-allocation: found nnzJ=%d but allocated %d",
nnzJ, d->nnzJ);
int nJ = d->efc_J_rownnz[d->nefc - 1] + d->efc_J_rowadr[d->nefc - 1];
if (d->nJ != nJ) {
mjERROR("constraint Jacobian mis-allocation: found nJ=%d but allocated %d", nJ, d->nJ);
}
}
} else if (d->nefc > nefc_allocated) {
Expand Down
2 changes: 1 addition & 1 deletion src/engine/engine_io.c
Original file line number Diff line number Diff line change
Expand Up @@ -1815,7 +1815,7 @@ static void _resetData(const mjModel* m, mjData* d, unsigned char debug_value) {
d->nf = 0;
d->nl = 0;
d->nefc = 0;
d->nnzJ = 0;
d->nJ = 0;
d->nisland = 0;

// clear global properties
Expand Down
2 changes: 1 addition & 1 deletion test/engine/engine_io_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,7 @@ TEST_F(EngineIoTest, ResetVariableSizes) {
EXPECT_EQ(data->ne, 0);
EXPECT_EQ(data->nf, 0);
EXPECT_EQ(data->nefc, 0);
EXPECT_EQ(data->nnzJ, 0);
EXPECT_EQ(data->nJ, 0);
EXPECT_EQ(data->ncon, 0);

mj_deleteData(data);
Expand Down
2 changes: 1 addition & 1 deletion unity/Runtime/Bindings/MjBindings.cs
Original file line number Diff line number Diff line change
Expand Up @@ -4851,7 +4851,7 @@ public unsafe struct mjData_ {
public int nf;
public int nl;
public int nefc;
public int nnzJ;
public int nJ;
public int nisland;
public double time;
public fixed double energy[2];
Expand Down

0 comments on commit c9f78ad

Please sign in to comment.