@@ -114,8 +114,8 @@ static void printSparse(const char* str, const mjtNum* mat, int nr,
114
114
115
115
116
116
// 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 ) {
119
119
// if no rows / columns, or too many columns to be visually useful, return
120
120
if (!nr || !nc || nc > 300 ) {
121
121
return ;
@@ -1060,8 +1060,9 @@ void mj_printFormattedData(const mjModel* m, mjData* d, const char* filename,
1060
1060
if (!mj_isSparse (m )) {
1061
1061
printArray ("FLEXEDGE_J" , m -> nflexedge , m -> nv , d -> flexedge_J , fp , float_format );
1062
1062
} 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 );
1065
1066
printArrayInt ("FLEXEDGE_J_ROWNNZ" , m -> nflexedge , 1 , d -> flexedge_J_rownnz , fp );
1066
1067
printArrayInt ("FLEXEDGE_J_ROWADR" , m -> nflexedge , 1 , d -> flexedge_J_rowadr , fp );
1067
1068
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,
1073
1074
if (!mj_isSparse (m )) {
1074
1075
printArray ("TEN_MOMENT" , m -> ntendon , m -> nv , d -> ten_J , fp , float_format );
1075
1076
} 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 );
1078
1079
printArrayInt ("TEN_J_ROWNNZ" , m -> ntendon , 1 , d -> ten_J_rownnz , fp );
1079
1080
printArrayInt ("TEN_J_ROWADR" , m -> ntendon , 1 , d -> ten_J_rowadr , fp );
1080
1081
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,
1090
1091
}
1091
1092
1092
1093
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 );
1095
1096
printSparse ("ACTUATOR_MOMENT" , d -> actuator_moment , m -> nu , d -> moment_rownnz ,
1096
1097
d -> moment_rowadr , d -> moment_colind , fp , float_format );
1097
1098
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,
1109
1110
printArray ("QLDIAGINV" , m -> nv , 1 , d -> qLDiagInv , fp , float_format );
1110
1111
1111
1112
// 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 );
1114
1115
1115
1116
// B_rownnz
1116
1117
fprintf (fp , NAME_FORMAT , "B_rownnz" );
@@ -1134,8 +1135,8 @@ void mj_printFormattedData(const mjModel* m, mjData* d, const char* filename,
1134
1135
fprintf (fp , "\n\n" );
1135
1136
1136
1137
// 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 );
1139
1140
1140
1141
fprintf (fp , NAME_FORMAT , "C_rownnz" );
1141
1142
for (int i = 0 ; i < m -> nv ; i ++ ) {
@@ -1165,8 +1166,8 @@ void mj_printFormattedData(const mjModel* m, mjData* d, const char* filename,
1165
1166
fprintf (fp , "\n\n" );
1166
1167
1167
1168
// 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 );
1170
1171
1171
1172
// D_rownnz
1172
1173
fprintf (fp , NAME_FORMAT , "D_rownnz" );
@@ -1263,14 +1264,14 @@ void mj_printFormattedData(const mjModel* m, mjData* d, const char* filename,
1263
1264
printArray ("EFC_J" , d -> nefc , m -> nv , d -> efc_J , fp , float_format );
1264
1265
printArray ("EFC_AR" , d -> nefc , d -> nefc , d -> efc_AR , fp , float_format );
1265
1266
} 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 );
1268
1269
printArrayInt ("EFC_J_ROWNNZ" , d -> nefc , 1 , d -> efc_J_rownnz , fp );
1269
1270
printArrayInt ("EFC_J_ROWADR" , d -> nefc , 1 , d -> efc_J_rowadr , fp );
1270
1271
printSparse ("EFC_J" , d -> efc_J , d -> nefc , d -> efc_J_rownnz ,
1271
1272
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 );
1274
1275
printArrayInt ("EFC_AR_ROWNNZ" , d -> nefc , 1 , d -> efc_AR_rownnz , fp );
1275
1276
printArrayInt ("EFC_AR_ROWADR" , d -> nefc , 1 , d -> efc_AR_rowadr , fp );
1276
1277
printSparse ("EFC_AR" , d -> efc_AR , d -> nefc , d -> efc_AR_rownnz ,
0 commit comments