@@ -39,7 +39,7 @@ mjtNum gettm(void) {
3939}
4040
4141// deallocate and print message
42- int finish (const char * msg = 0 , mjModel* m = 0 ) {
42+ int finish (const char * msg = 0 , int exitcode = EXIT_SUCCESS, mjModel* m = 0 ) {
4343 // deallocated everything
4444 if (m) {
4545 mj_deleteModel (m);
@@ -50,7 +50,7 @@ int finish(const char* msg = 0, mjModel* m = 0) {
5050 std::cout << msg << std::endl;
5151 }
5252
53- return EXIT_SUCCESS ;
53+ return exitcode ;
5454}
5555
5656
@@ -109,7 +109,7 @@ int main(int argc, char** argv) {
109109
110110 // print help if arguments are missing
111111 if (argc!=3 && argc!=2 ) {
112- return finish (helpstring);
112+ return finish (helpstring, EXIT_FAILURE );
113113 }
114114
115115 // determine file types
@@ -119,7 +119,7 @@ int main(int argc, char** argv) {
119119 // check types
120120 if (type1==typeUNKNOWN || type1==typeTXT ||
121121 type2==typeUNKNOWN || (type1==typeMJB && type2==typeXML)) {
122- return finish (" Illegal combination of file formats" );
122+ return finish (" Illegal combination of file formats" , EXIT_FAILURE );
123123 }
124124
125125 // check if output file exists
@@ -153,16 +153,16 @@ int main(int argc, char** argv) {
153153 // check error
154154 if (!m) {
155155 if (type1==typeXML) {
156- return finish (error, 0 );
156+ return finish (error, EXIT_FAILURE );
157157 } else {
158- return finish (" Could not load model" , 0 );
158+ return finish (" Could not load model" , EXIT_FAILURE );
159159 }
160160 }
161161
162162 // save model
163163 if (type2==typeXML) {
164164 if (!mj_saveLastXML (argv[2 ], m, error, 1000 )) {
165- return finish (error, m);
165+ return finish (error, EXIT_FAILURE, m);
166166 }
167167 } else if (type2==typeMJB) {
168168 mj_saveModel (m, argv[2 ], 0 , 0 );
@@ -181,5 +181,5 @@ int main(int argc, char** argv) {
181181 snprintf (msg, sizeof (msg), " Done." );
182182 }
183183
184- return finish (msg, m);
184+ return finish (msg, EXIT_SUCCESS, m);
185185}
0 commit comments