Skip to content

Commit 63e2836

Browse files
yuvaltassacopybara-github
authored andcommitted
Expose mj_printSparsity in engine_print.h.
This is useful for debugging sparse operations. PiperOrigin-RevId: 711765082 Change-Id: I532a5218da0f921dd4b04730d0b12c5136e7ca65
1 parent 923f75f commit 63e2836

File tree

2 files changed

+25
-18
lines changed

2 files changed

+25
-18
lines changed

src/engine/engine_print.c

Lines changed: 19 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -114,8 +114,8 @@ static void printSparse(const char* str, const mjtNum* mat, int nr,
114114

115115

116116
// print sparse matrix structure
117-
static void printSparsity(const char* str, int nr, int nc, const int* rowadr, const int* diag,
118-
const int* rownnz, const int* rowsuper, const int* colind, FILE* fp) {
117+
void mj_printSparsity(const char* str, int nr, int nc, const int* rowadr, const int* diag,
118+
const int* rownnz, const int* rowsuper, const int* colind, FILE* fp) {
119119
// if no rows / columns, or too many columns to be visually useful, return
120120
if (!nr || !nc || nc > 300) {
121121
return;
@@ -1060,8 +1060,9 @@ void mj_printFormattedData(const mjModel* m, mjData* d, const char* filename,
10601060
if (!mj_isSparse(m)) {
10611061
printArray("FLEXEDGE_J", m->nflexedge, m->nv, d->flexedge_J, fp, float_format);
10621062
} else {
1063-
printSparsity("FLEXEDGE_J: flex edge connectivity", m->nflexedge, m->nv,
1064-
d->flexedge_J_rowadr, NULL, d->flexedge_J_rownnz, NULL, d->flexedge_J_colind, fp);
1063+
mj_printSparsity("FLEXEDGE_J: flex edge connectivity", m->nflexedge, m->nv,
1064+
d->flexedge_J_rowadr, NULL, d->flexedge_J_rownnz, NULL, d->flexedge_J_colind,
1065+
fp);
10651066
printArrayInt("FLEXEDGE_J_ROWNNZ", m->nflexedge, 1, d->flexedge_J_rownnz, fp);
10661067
printArrayInt("FLEXEDGE_J_ROWADR", m->nflexedge, 1, d->flexedge_J_rowadr, fp);
10671068
printSparse("FLEXEDGE_J", d->flexedge_J, m->nflexedge, d->flexedge_J_rownnz,
@@ -1073,8 +1074,8 @@ void mj_printFormattedData(const mjModel* m, mjData* d, const char* filename,
10731074
if (!mj_isSparse(m)) {
10741075
printArray("TEN_MOMENT", m->ntendon, m->nv, d->ten_J, fp, float_format);
10751076
} else {
1076-
printSparsity("TEN_J: tendon moments", m->ntendon, m->nv, d->ten_J_rowadr, NULL,
1077-
d->ten_J_rownnz, NULL, d->ten_J_colind, fp);
1077+
mj_printSparsity("TEN_J: tendon moments", m->ntendon, m->nv, d->ten_J_rowadr, NULL,
1078+
d->ten_J_rownnz, NULL, d->ten_J_colind, fp);
10781079
printArrayInt("TEN_J_ROWNNZ", m->ntendon, 1, d->ten_J_rownnz, fp);
10791080
printArrayInt("TEN_J_ROWADR", m->ntendon, 1, d->ten_J_rowadr, fp);
10801081
printSparse("TEN_J", d->ten_J, m->ntendon, d->ten_J_rownnz,
@@ -1090,8 +1091,8 @@ void mj_printFormattedData(const mjModel* m, mjData* d, const char* filename,
10901091
}
10911092

10921093
printArray("ACTUATOR_LENGTH", m->nu, 1, d->actuator_length, fp, float_format);
1093-
printSparsity("actuator_moment", m->nu, m->nv,
1094-
d->moment_rowadr, NULL, d->moment_rownnz, NULL, d->moment_colind, fp);
1094+
mj_printSparsity("actuator_moment", m->nu, m->nv,
1095+
d->moment_rowadr, NULL, d->moment_rownnz, NULL, d->moment_colind, fp);
10951096
printSparse("ACTUATOR_MOMENT", d->actuator_moment, m->nu, d->moment_rownnz,
10961097
d->moment_rowadr, d->moment_colind, fp, float_format);
10971098
printArray("CRB", m->nbody, 10, d->crb, fp, float_format);
@@ -1109,8 +1110,8 @@ void mj_printFormattedData(const mjModel* m, mjData* d, const char* filename,
11091110
printArray("QLDIAGINV", m->nv, 1, d->qLDiagInv, fp, float_format);
11101111

11111112
// B sparse structure
1112-
printSparsity("B: body-dof matrix", m->nbody, m->nv, d->B_rowadr, NULL, d->B_rownnz, NULL,
1113-
d->B_colind, fp);
1113+
mj_printSparsity("B: body-dof matrix", m->nbody, m->nv, d->B_rowadr, NULL, d->B_rownnz, NULL,
1114+
d->B_colind, fp);
11141115

11151116
// B_rownnz
11161117
fprintf(fp, NAME_FORMAT, "B_rownnz");
@@ -1134,8 +1135,8 @@ void mj_printFormattedData(const mjModel* m, mjData* d, const char* filename,
11341135
fprintf(fp, "\n\n");
11351136

11361137
// C sparse structure
1137-
printSparsity("C: reduced dof-dof matrix", m->nv, m->nv, d->C_rowadr, d->C_diag, d->C_rownnz,
1138-
NULL, d->C_colind, fp);
1138+
mj_printSparsity("C: reduced dof-dof matrix", m->nv, m->nv, d->C_rowadr, d->C_diag, d->C_rownnz,
1139+
NULL, d->C_colind, fp);
11391140

11401141
fprintf(fp, NAME_FORMAT, "C_rownnz");
11411142
for (int i = 0; i < m->nv; i++) {
@@ -1165,8 +1166,8 @@ void mj_printFormattedData(const mjModel* m, mjData* d, const char* filename,
11651166
fprintf(fp, "\n\n");
11661167

11671168
// D sparse structure
1168-
printSparsity("D: dof-dof matrix", m->nv, m->nv,
1169-
d->D_rowadr, d->D_diag, d->D_rownnz, NULL, d->D_colind, fp);
1169+
mj_printSparsity("D: dof-dof matrix", m->nv, m->nv,
1170+
d->D_rowadr, d->D_diag, d->D_rownnz, NULL, d->D_colind, fp);
11701171

11711172
// D_rownnz
11721173
fprintf(fp, NAME_FORMAT, "D_rownnz");
@@ -1263,14 +1264,14 @@ void mj_printFormattedData(const mjModel* m, mjData* d, const char* filename,
12631264
printArray("EFC_J", d->nefc, m->nv, d->efc_J, fp, float_format);
12641265
printArray("EFC_AR", d->nefc, d->nefc, d->efc_AR, fp, float_format);
12651266
} else {
1266-
printSparsity("J: constraint Jacobian", d->nefc, m->nv,
1267-
d->efc_J_rowadr, NULL, d->efc_J_rownnz, d->efc_J_rowsuper, d->efc_J_colind, fp);
1267+
mj_printSparsity("J: constraint Jacobian", d->nefc, m->nv, d->efc_J_rowadr, NULL,
1268+
d->efc_J_rownnz, d->efc_J_rowsuper, d->efc_J_colind, fp);
12681269
printArrayInt("EFC_J_ROWNNZ", d->nefc, 1, d->efc_J_rownnz, fp);
12691270
printArrayInt("EFC_J_ROWADR", d->nefc, 1, d->efc_J_rowadr, fp);
12701271
printSparse("EFC_J", d->efc_J, d->nefc, d->efc_J_rownnz,
12711272
d->efc_J_rowadr, d->efc_J_colind, fp, float_format);
1272-
printSparsity("JT: constraint Jacobian transposed", m->nv, d->nefc, d->efc_JT_rowadr, NULL,
1273-
d->efc_JT_rownnz, d->efc_JT_rowsuper, d->efc_JT_colind, fp);
1273+
mj_printSparsity("JT: constraint Jacobian transposed", m->nv, d->nefc, d->efc_JT_rowadr, NULL,
1274+
d->efc_JT_rownnz, d->efc_JT_rowsuper, d->efc_JT_colind, fp);
12741275
printArrayInt("EFC_AR_ROWNNZ", d->nefc, 1, d->efc_AR_rownnz, fp);
12751276
printArrayInt("EFC_AR_ROWADR", d->nefc, 1, d->efc_AR_rowadr, fp);
12761277
printSparse("EFC_AR", d->efc_AR, d->nefc, d->efc_AR_rownnz,

src/engine/engine_print.h

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
#ifndef MUJOCO_SRC_ENGINE_ENGINE_PRINT_H_
1616
#define MUJOCO_SRC_ENGINE_ENGINE_PRINT_H_
1717

18+
#include <stdio.h>
19+
1820
#include <mujoco/mjdata.h>
1921
#include <mujoco/mjexport.h>
2022
#include <mujoco/mjmodel.h>
@@ -40,6 +42,10 @@ MJAPI void mj_printFormattedData(const mjModel* m, mjData* d, const char* filena
4042
// print data to text file
4143
MJAPI void mj_printData(const mjModel* m, mjData* d, const char* filename);
4244

45+
// print sparse matrix structure
46+
MJAPI void mj_printSparsity(const char* str, int nr, int nc, const int* rowadr, const int* diag,
47+
const int* rownnz, const int* rowsuper, const int* colind, FILE* fp);
48+
4349
#ifdef __cplusplus
4450
}
4551
#endif

0 commit comments

Comments
 (0)