rbdl / addons / benchmark / benchmark.cc

The dev branch has multiple heads

  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
#include <iostream>

#include <algorithm>
#include <string>
#include <vector>
#include <cstdlib>
#include <iomanip>
#include <sstream>

#include "rbdl/rbdl.h"
#include "model_generator.h"
#include "Human36Model.h"
#include "SampleData.h"
#include "Timer.h"

using namespace std;
using namespace RigidBodyDynamics;
using namespace RigidBodyDynamics::Math;

int benchmark_sample_count = 1000;
int benchmark_model_max_depth = 5;

bool benchmark_run_fd_aba = true;
bool benchmark_run_fd_lagrangian = true;
bool benchmark_run_id_rnea = true;
bool benchmark_run_crba = true;
bool benchmark_run_contacts = false;

enum ContactsBenchmark {
	ContactsBenchmarkLagrangian = 0,
	ContactsBenchmarkKokkevis
};

double run_forward_dynamics_ABA_benchmark (Model *model, int sample_count) {
	SampleData sample_data;
	sample_data.fill_random_data(model->dof_count, sample_count);

	TimerInfo tinfo;
	timer_start (&tinfo);

	for (int i = 0; i < sample_count; i++) {
		ForwardDynamics (*model,
				sample_data.q_data[i],
				sample_data.qdot_data[i],
				sample_data.tau_data[i],
				sample_data.qddot_data[i]);
	}

	double duration = timer_stop (&tinfo);

	cout << "#DOF: " << setw(3) << model->dof_count 
		<< " #samples: " << sample_count 
		<< " duration = " << setw(10) << duration << "(s)"
		<< " (~" << setw(10) << duration / sample_count << "(s) per call)" << endl;
	
	return duration;
}

double run_forward_dynamics_lagrangian_benchmark (Model *model, int sample_count) {
	SampleData sample_data;
	sample_data.fill_random_data(model->dof_count, sample_count);

	TimerInfo tinfo;
	timer_start (&tinfo);

	for (int i = 0; i < sample_count; i++) {
		ForwardDynamicsLagrangian (*model,
				sample_data.q_data[i],
				sample_data.qdot_data[i],
				sample_data.tau_data[i],
				sample_data.qddot_data[i]
);
	}

	double duration = timer_stop (&tinfo);

	cout << "#DOF: " << setw(3) << model->dof_count 
		<< " #samples: " << sample_count 
		<< " duration = " << setw(10) << duration << "(s)"
		<< " (~" << setw(10) << duration / sample_count << "(s) per call)" << endl;
	
	return duration;
}

double run_inverse_dynamics_RNEA_benchmark (Model *model, int sample_count) {
	SampleData sample_data;
	sample_data.fill_random_data(model->dof_count, sample_count);

	TimerInfo tinfo;
	timer_start (&tinfo);

	for (int i = 0; i < sample_count; i++) {
		InverseDynamics (*model,
				sample_data.q_data[i],
				sample_data.qdot_data[i],
				sample_data.qddot_data[i],
				sample_data.tau_data[i]
				);
	}

	double duration = timer_stop (&tinfo);

	cout << "#DOF: " << setw(3) << model->dof_count 
		<< " #samples: " << sample_count 
		<< " duration = " << setw(10) << duration << "(s)"
		<< " (~" << setw(10) << duration / sample_count << "(s) per call)" << endl;

	return duration;
}

double run_CRBA_benchmark (Model *model, int sample_count) {
	SampleData sample_data;
	sample_data.fill_random_data(model->dof_count, sample_count);

	Math::MatrixNd H = Math::MatrixNd(model->dof_count, model->dof_count);

	TimerInfo tinfo;
	timer_start (&tinfo);

	for (int i = 0; i < sample_count; i++) {
		CompositeRigidBodyAlgorithm (*model, sample_data.q_data[i], H, true);
	}

	double duration = timer_stop (&tinfo);

	cout << "#DOF: " << setw(3) << model->dof_count 
		<< " #samples: " << sample_count 
		<< " duration = " << setw(10) << duration << "(s)"
		<< " (~" << setw(10) << duration / sample_count << "(s) per call)" << endl;

	return duration;
}

double run_contacts_lagrangian_benchmark (Model *model, ConstraintSet *constraint_set, int sample_count) {
	SampleData sample_data;
	sample_data.fill_random_data(model->dof_count, sample_count);

	TimerInfo tinfo;
	timer_start (&tinfo);

	for (int i = 0; i < sample_count; i++) {
		ForwardDynamicsContactsLagrangian (*model, sample_data.q_data[i], sample_data.qdot_data[i], sample_data.tau_data[i], *constraint_set, sample_data.qddot_data[i]); 
	}

	double duration = timer_stop (&tinfo);

	return duration;
}

double run_contacts_kokkevis_benchmark (Model *model, ConstraintSet *constraint_set, int sample_count) {
	SampleData sample_data;
	sample_data.fill_random_data(model->dof_count, sample_count);

	TimerInfo tinfo;
	timer_start (&tinfo);

	for (int i = 0; i < sample_count; i++) {
		ForwardDynamicsContacts (*model, sample_data.q_data[i], sample_data.qdot_data[i], sample_data.tau_data[i], *constraint_set, sample_data.qddot_data[i]); 
	}

	double duration = timer_stop (&tinfo);

	return duration;
}

double contacts_benchmark (int sample_count, ContactsBenchmark contacts_benchmark) {
	// initialize the human model
	Model *model = new Model();
	generate_human36model(model);

	// initialize the constraint sets
	unsigned int foot_r = model->GetBodyId ("foot_r");
	unsigned int foot_l = model->GetBodyId ("foot_l");
	unsigned int hand_r = model->GetBodyId ("hand_r");
	unsigned int hand_l = model->GetBodyId ("hand_l");

	ConstraintSet one_body_one_constraint;
	ConstraintSet two_bodies_one_constraint;
	ConstraintSet four_bodies_one_constraint;

	ConstraintSet one_body_four_constraints;
	ConstraintSet two_bodies_four_constraints;
	ConstraintSet four_bodies_four_constraints;

	// one_body_one
	one_body_one_constraint.AddConstraint (foot_r, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	one_body_one_constraint.Bind (*model);

	// two_bodies_one
	two_bodies_one_constraint.AddConstraint (foot_r, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	two_bodies_one_constraint.AddConstraint (foot_l, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	two_bodies_one_constraint.Bind (*model);

	// four_bodies_one
	four_bodies_one_constraint.AddConstraint (foot_r, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	four_bodies_one_constraint.AddConstraint (foot_l, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	four_bodies_one_constraint.AddConstraint (hand_r, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	four_bodies_one_constraint.AddConstraint (hand_l, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	four_bodies_one_constraint.Bind (*model);

	// one_body_four
	one_body_four_constraints.AddConstraint (foot_r, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	one_body_four_constraints.AddConstraint (foot_r, Vector3d (0.1, 0., -0.05), Vector3d (0., 1., 0.));
	one_body_four_constraints.AddConstraint (foot_r, Vector3d (0.1, 0., -0.05), Vector3d (0., 0., 1.));
	one_body_four_constraints.AddConstraint (foot_r, Vector3d (-0.1, 0., -0.05), Vector3d (1., 0., 0.));
	one_body_four_constraints.Bind (*model);	

	// two_bodies_four
	two_bodies_four_constraints.AddConstraint (foot_r, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	two_bodies_four_constraints.AddConstraint (foot_r, Vector3d (0.1, 0., -0.05), Vector3d (0., 1., 0.));
	two_bodies_four_constraints.AddConstraint (foot_r, Vector3d (0.1, 0., -0.05), Vector3d (0., 0., 1.));
	two_bodies_four_constraints.AddConstraint (foot_r, Vector3d (-0.1, 0., -0.05), Vector3d (1., 0., 0.));
	
	two_bodies_four_constraints.AddConstraint (foot_l, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	two_bodies_four_constraints.AddConstraint (foot_l, Vector3d (0.1, 0., -0.05), Vector3d (0., 1., 0.));
	two_bodies_four_constraints.AddConstraint (foot_l, Vector3d (0.1, 0., -0.05), Vector3d (0., 0., 1.));
	two_bodies_four_constraints.AddConstraint (foot_l, Vector3d (-0.1, 0., -0.05), Vector3d (1., 0., 0.));

	two_bodies_four_constraints.Bind (*model);

	// four_bodies_four
	four_bodies_four_constraints.AddConstraint (foot_r, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	four_bodies_four_constraints.AddConstraint (foot_r, Vector3d (0.1, 0., -0.05), Vector3d (0., 1., 0.));
	four_bodies_four_constraints.AddConstraint (foot_r, Vector3d (0.1, 0., -0.05), Vector3d (0., 0., 1.));
	four_bodies_four_constraints.AddConstraint (foot_r, Vector3d (-0.1, 0., -0.05), Vector3d (1., 0., 0.));
	
	four_bodies_four_constraints.AddConstraint (foot_l, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	four_bodies_four_constraints.AddConstraint (foot_l, Vector3d (0.1, 0., -0.05), Vector3d (0., 1., 0.));
	four_bodies_four_constraints.AddConstraint (foot_l, Vector3d (0.1, 0., -0.05), Vector3d (0., 0., 1.));
	four_bodies_four_constraints.AddConstraint (foot_l, Vector3d (-0.1, 0., -0.05), Vector3d (1., 0., 0.));

	four_bodies_four_constraints.AddConstraint (hand_r, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	four_bodies_four_constraints.AddConstraint (hand_r, Vector3d (0.1, 0., -0.05), Vector3d (0., 1., 0.));
	four_bodies_four_constraints.AddConstraint (hand_r, Vector3d (0.1, 0., -0.05), Vector3d (0., 0., 1.));
	four_bodies_four_constraints.AddConstraint (hand_r, Vector3d (-0.1, 0., -0.05), Vector3d (1., 0., 0.));
	
	four_bodies_four_constraints.AddConstraint (hand_l, Vector3d (0.1, 0., -0.05), Vector3d (1., 0., 0.));
	four_bodies_four_constraints.AddConstraint (hand_l, Vector3d (0.1, 0., -0.05), Vector3d (0., 1., 0.));
	four_bodies_four_constraints.AddConstraint (hand_l, Vector3d (0.1, 0., -0.05), Vector3d (0., 0., 1.));
	four_bodies_four_constraints.AddConstraint (hand_l, Vector3d (-0.1, 0., -0.05), Vector3d (1., 0., 0.));

	four_bodies_four_constraints.Bind (*model);

	cout << "= #DOF: " << setw(3) << model->dof_count << endl;
	cout << "= #samples: " << sample_count << endl;
	cout << "= No constraints (Articulated Body Algorithm):" << endl;
	run_forward_dynamics_ABA_benchmark (model, sample_count);
	cout << "= Constraints:" << endl;
	double duration;

	// one body one
	if (contacts_benchmark == ContactsBenchmarkLagrangian) {
		duration = run_contacts_lagrangian_benchmark (model, &one_body_one_constraint, sample_count);
	} else {
		duration = run_contacts_kokkevis_benchmark (model, &one_body_one_constraint, sample_count);
	}

	cout << "ConstraintSet: 1 Body 1 Constraint   : "
		<< " duration = " << setw(10) << duration << "(s)"
		<< " (~" << setw(10) << duration / sample_count << "(s) per call)" << endl;

	// two_bodies_one
	if (contacts_benchmark == ContactsBenchmarkLagrangian) {
		duration = run_contacts_lagrangian_benchmark (model, &two_bodies_one_constraint, sample_count);
	} else {
		duration = run_contacts_kokkevis_benchmark (model, &two_bodies_one_constraint, sample_count);
	}

	cout << "ConstraintSet: 2 Bodies 1 Constraint : "
		<< " duration = " << setw(10) << duration << "(s)"
		<< " (~" << setw(10) << duration / sample_count << "(s) per call)" << endl;


	// four_bodies_one
	if (contacts_benchmark == ContactsBenchmarkLagrangian) {
		duration = run_contacts_lagrangian_benchmark (model, &four_bodies_one_constraint, sample_count);
	} else {
		duration = run_contacts_kokkevis_benchmark (model, &four_bodies_one_constraint, sample_count);
	}

	cout << "ConstraintSet: 4 Bodies 1 Constraint : "
		<< " duration = " << setw(10) << duration << "(s)"
		<< " (~" << setw(10) << duration / sample_count << "(s) per call)" << endl;

	// one_body_four
	if (contacts_benchmark == ContactsBenchmarkLagrangian) {
		duration = run_contacts_lagrangian_benchmark (model, &one_body_four_constraints, sample_count);
	} else {
		duration = run_contacts_kokkevis_benchmark (model, &one_body_four_constraints, sample_count);
	}

	cout << "ConstraintSet: 1 Body 4 Constraints  : "
		<< " duration = " << setw(10) << duration << "(s)"
		<< " (~" << setw(10) << duration / sample_count << "(s) per call)" << endl;

	// two_bodies_four
	if (contacts_benchmark == ContactsBenchmarkLagrangian) {
		duration = run_contacts_lagrangian_benchmark (model, &two_bodies_four_constraints, sample_count);
	} else {
		duration = run_contacts_kokkevis_benchmark (model, &two_bodies_four_constraints, sample_count);
	}

	cout << "ConstraintSet: 2 Bodies 4 Constraints: "
		<< " duration = " << setw(10) << duration << "(s)"
		<< " (~" << setw(10) << duration / sample_count << "(s) per call)" << endl;


	// four_bodies_four
	if (contacts_benchmark == ContactsBenchmarkLagrangian) {
		duration = run_contacts_lagrangian_benchmark (model, &four_bodies_four_constraints, sample_count);
	} else {
		duration = run_contacts_kokkevis_benchmark (model, &four_bodies_four_constraints, sample_count);
	}

	cout << "ConstraintSet: 4 Bodies 4 Constraints: "
		<< " duration = " << setw(10) << duration << "(s)"
		<< " (~" << setw(10) << duration / sample_count << "(s) per call)" << endl;

	delete model;

	return duration;
}

void print_usage () {
	cout << "Usage: benchmark [--count|-c <sample_count>] [--depth|-d <depth>]" << endl;
	cout << "Simple benchmark tool for the Rigid Body Dynamics Library." << endl;
	cout << "  --count | -c <sample_count> : sets the number of sample states that should" << endl;
	cout << "                be calculated (default: 1000)" << endl;
	cout << "  --depth | -d <depth>        : sets maximum depth for the branched test model" << endl;
	cout << "                which is created increased from 1 to <depth> (default: 5)." << endl;
	cout << "  --no-fd                     : disables benchmarking of forward dynamics." << endl;
	cout << "  --no-fd-aba                 : disables benchmark for forwards dynamics using" << endl;
	cout << "                                the Articulated Body Algorithm" << endl;
	cout << "  --no-fd-lagrangian          : disables benchmark for forward dynamics via" << endl;
	cout << "                                solving the lagrangian equation." << endl;
	cout << "  --no-id-rnea                : disables benchmark for inverse dynamics using" << endl;
	cout << "                                the recursive newton euler algorithm." << endl;
	cout << "  --no-crba                   : disables benchmark for joint space inertia" << endl;
	cout << "                                matrix computation using the composite rigid." << endl;
	cout << "                                body algorithm." << endl;
	cout << "  --only-contacts | -C        : only runs contact model benchmarks." << endl;
	cout << "  --help | -h                 : prints this help." << endl;
}

void disable_all_benchmarks () {
	benchmark_run_fd_aba = false;
	benchmark_run_fd_lagrangian = false;
	benchmark_run_id_rnea = false;
	benchmark_run_crba = false;
	benchmark_run_contacts = false;
}

void parse_args (int argc, char* argv[]) {
	int argi = 1;
	while (argi < argc) {
		string arg = argv[argi];

		if (arg == "--help" || arg == "-h") {
			print_usage();
			exit (1);
		} else if (arg == "--count" || arg == "-c" ) {
			if (argi == argc - 1) {
				print_usage();

				cerr << "Error: missing number of samples!" << endl;
				exit (1);
			}

			argi++;
			stringstream count_stream (argv[argi]);

			count_stream >> benchmark_sample_count;
		} else if (arg == "--depth" || arg == "-d" ) {
			if (argi == argc - 1) {
				print_usage();

				cerr << "Error: missing number for model depth!" << endl;
				exit (1);
			}

			argi++;
			stringstream depth_stream (argv[argi]);

			depth_stream >> benchmark_model_max_depth;
		} else if (arg == "--no-fd" ) {
			benchmark_run_fd_aba = false;
			benchmark_run_fd_lagrangian = false;
		} else if (arg == "--no-fd-aba" ) {
			benchmark_run_fd_aba = false;
		} else if (arg == "--no-fd-lagrangian" ) {
			benchmark_run_fd_lagrangian = false;
		} else if (arg == "--no-id-rnea" ) {
			benchmark_run_id_rnea = false;
		} else if (arg == "--no-crba" ) {
			benchmark_run_crba = false;
		} else if (arg == "--only-contacts" || arg == "-C") {
			disable_all_benchmarks();
			benchmark_run_contacts = true;
		} else {
			print_usage();
			cerr << "Invalid argument '" << arg << "'." << endl;
			exit(1);
		}
		argi++;
	}
}

int main (int argc, char *argv[]) {
	parse_args (argc, argv);

	Model *model = NULL;

	model = new Model();
	generate_human36model (model);
	cout << "Human dofs = " << model->dof_count << endl;
	delete model;

	rbdl_print_version();
	cout << endl;

	if (benchmark_run_fd_aba) {
		cout << "= Forward Dynamics: ABA =" << endl;
		for (int depth = 1; depth <= benchmark_model_max_depth; depth++) {
			model = new Model();
			model->gravity = Vector3d (0., -9.81, 0.);

			generate_planar_tree (model, depth);

			run_forward_dynamics_ABA_benchmark (model, benchmark_sample_count);

			delete model;
		}
		cout << endl;
	}

	if (benchmark_run_fd_lagrangian) {
		cout << "= Forward Dynamics: Lagrangian (Piv. LU decomposition) =" << endl;
		for (int depth = 1; depth <= benchmark_model_max_depth; depth++) {
			model = new Model();
			model->gravity = Vector3d (0., -9.81, 0.);

			generate_planar_tree (model, depth);

			run_forward_dynamics_lagrangian_benchmark (model, benchmark_sample_count);

			delete model;
		}
		cout << endl;
	}

	if (benchmark_run_id_rnea) {
		cout << "= Inverse Dynamics: RNEA =" << endl;
		for (int depth = 1; depth <= benchmark_model_max_depth; depth++) {
			model = new Model();
			model->gravity = Vector3d (0., -9.81, 0.);

			generate_planar_tree (model, depth);

			run_inverse_dynamics_RNEA_benchmark (model, benchmark_sample_count);

			delete model;
		}
		cout << endl;
	}

	if (benchmark_run_crba) {
		cout << "= Joint Space Inertia Matrix: CRBA =" << endl;
		for (int depth = 1; depth <= benchmark_model_max_depth; depth++) {
			model = new Model();
			model->gravity = Vector3d (0., -9.81, 0.);

			generate_planar_tree (model, depth);

			run_CRBA_benchmark (model, benchmark_sample_count);

			delete model;
		}
		cout << endl;
	}

	if (benchmark_run_contacts) {
		cout << "= Contacts: ForwardDynamicsContactsLagrangian" << endl;
		contacts_benchmark (benchmark_sample_count, ContactsBenchmarkLagrangian);

		cout << "= Contacts: ForwardDynamicsContactsKokkevis" << endl;
		contacts_benchmark (benchmark_sample_count, ContactsBenchmarkKokkevis);
	}



	return 0;
}
Tip: Filter by directory path e.g. /media app.js to search for public/media/app.js.
Tip: Use camelCasing e.g. ProjME to search for ProjectModifiedEvent.java.
Tip: Filter by extension type e.g. /repo .js to search for all .js files in the /repo directory.
Tip: Separate your search with spaces e.g. /ssh pom.xml to search for src/ssh/pom.xml.
Tip: Use ↑ and ↓ arrow keys to navigate and return to view the file.
Tip: You can also navigate files with Ctrl+j (next) and Ctrl+k (previous) and view the file with Ctrl+o.
Tip: You can also navigate files with Alt+j (next) and Alt+k (previous) and view the file with Alt+o.