@@ -1272,10 +1272,14 @@ void mj_printFormattedData(const mjModel* m, mjData* d, const char* filename,
1272
1272
d -> efc_J_rowadr , d -> efc_J_colind , fp , float_format );
1273
1273
mj_printSparsity ("JT: constraint Jacobian transposed" , m -> nv , d -> nefc , d -> efc_JT_rowadr , NULL ,
1274
1274
d -> efc_JT_rownnz , d -> efc_JT_rowsuper , d -> efc_JT_colind , fp );
1275
- printArrayInt ("EFC_AR_ROWNNZ" , d -> nefc , 1 , d -> efc_AR_rownnz , fp );
1276
- printArrayInt ("EFC_AR_ROWADR" , d -> nefc , 1 , d -> efc_AR_rowadr , fp );
1277
- printSparse ("EFC_AR" , d -> efc_AR , d -> nefc , d -> efc_AR_rownnz ,
1278
- d -> efc_AR_rowadr , d -> efc_AR_colind , fp , float_format );
1275
+ if (mj_isDual (m )) {
1276
+ printArrayInt ("EFC_AR_ROWNNZ" , d -> nefc , 1 , d -> efc_AR_rownnz , fp );
1277
+ printArrayInt ("EFC_AR_ROWADR" , d -> nefc , 1 , d -> efc_AR_rowadr , fp );
1278
+ printSparse ("EFC_AR" , d -> efc_AR , d -> nefc , d -> efc_AR_rownnz ,
1279
+ d -> efc_AR_rowadr , d -> efc_AR_colind , fp , float_format );
1280
+ mj_printSparsity ("efc_AR: inverse constraint inertia" , d -> nefc , d -> nefc , d -> efc_AR_rowadr ,
1281
+ NULL , d -> efc_AR_rownnz , NULL , d -> efc_AR_colind , fp );
1282
+ }
1279
1283
}
1280
1284
1281
1285
printArray ("EFC_POS" , d -> nefc , 1 , d -> efc_pos , fp , float_format );
0 commit comments