Source

rbdl / src / Contacts.cc

The dev branch has multiple heads

Full commit
  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
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
/*
 * RBDL - Rigid Body Dynamics Library
 * Copyright (c) 2011-2012 Martin Felis <martin.felis@iwr.uni-heidelberg.de>
 *
 * Licensed under the zlib license. See LICENSE for more details.
 */

#include <iostream>
#include <limits>
#include <assert.h>

#include "rbdl/rbdl_mathutils.h"
#include "rbdl/Logging.h"

#include "rbdl/Model.h"
#include "rbdl/Joint.h"
#include "rbdl/Body.h"
#include "rbdl/Contacts.h"
#include "rbdl/Dynamics.h"
#include "rbdl/Dynamics_experimental.h"
#include "rbdl/Kinematics.h"

namespace RigidBodyDynamics {

using namespace Math;

unsigned int ConstraintSet::AddConstraint (
		unsigned int body_id,
		const Vector3d &body_point,
		const Vector3d &world_normal,
		const char *constraint_name,
		double acceleration) {
	assert (bound == false);

	std::string name_str;
	if (constraint_name != NULL)
		name_str = constraint_name;

	name.push_back (name_str);
	body.push_back (body_id);
	point.push_back (body_point);
	normal.push_back (world_normal);

	unsigned int n_constr = constraint_acceleration.size() + 1;

	constraint_acceleration.conservativeResize (n_constr);
	constraint_acceleration[n_constr - 1] = acceleration;

	constraint_force.conservativeResize (n_constr);
	constraint_force[n_constr - 1] = 0.;

	constraint_impulse.conservativeResize (n_constr);
	constraint_impulse[n_constr - 1] = 0.;

	return n_constr - 1;
}

bool ConstraintSet::Bind (const Model &model) {
	assert (bound == false);

	if (bound) {
		std::cerr << "Error: binding an already bound constraint set!" << std::endl;
		abort();
	}
	unsigned int n_constr = size();

	H.conservativeResize (model.dof_count, model.dof_count);
	C.conservativeResize (model.dof_count);
	gamma.conservativeResize (n_constr);
	G.conservativeResize (n_constr, model.dof_count);
	A.conservativeResize (model.dof_count + n_constr, model.dof_count + n_constr);
	b.conservativeResize (model.dof_count + n_constr);
	x.conservativeResize (model.dof_count + n_constr);

	K.conservativeResize (n_constr, n_constr);
	a.conservativeResize (n_constr);
	QDDot_t.conservativeResize (model.dof_count);
	QDDot_0.conservativeResize (model.dof_count);
	f_t.resize (n_constr, SpatialVectorZero);
	f_ext_constraints.resize (model.mBodies.size(), SpatialVectorZero);
	point_accel_0.resize (n_constr, Vector3d::Zero());

	d_pA = std::vector<SpatialVector> (model.mBodies.size(), SpatialVectorZero);
	d_a = std::vector<SpatialVector> (model.mBodies.size(), SpatialVectorZero);
	d_u = VectorNd::Zero (model.mBodies.size());

	d_IA = std::vector<SpatialMatrix> (model.mBodies.size(), SpatialMatrixIdentity);
	d_U = std::vector<SpatialVector> (model.mBodies.size(), SpatialVectorZero);
	d_d = VectorNd::Zero (model.mBodies.size());

	bound = true;

	return bound;
}

void ConstraintSet::clear() {
	constraint_acceleration.setZero();
	constraint_force.setZero();
	constraint_impulse.setZero();

	H.setZero();
	C.setZero();
	gamma.setZero();
	G.setZero();
	A.setZero();
	b.setZero();
	x.setZero();

	K.setZero();
	a.setZero();
	QDDot_t.setZero();
	QDDot_0.setZero();

	unsigned int i;
	for (i = 0; i < f_t.size(); i++)
		f_t[i].setZero();

	for (i = 0; i < f_ext_constraints.size(); i++)
		f_ext_constraints[i].setZero();

	for (i = 0; i < point_accel_0.size(); i++)
		point_accel_0[i].setZero();

	for (i = 0; i < d_pA.size(); i++)
		d_pA[i].setZero();

	for (i = 0; i < d_a.size(); i++)
		d_a[i].setZero();

	d_u.setZero();
}

void ForwardDynamicsContactsLagrangian (
		Model &model,
		const VectorNd &Q,
		const VectorNd &QDot,
		const VectorNd &Tau,
		ConstraintSet &CS,
		VectorNd &QDDot
		) {
	LOG << "-------- " << __func__ << " --------" << std::endl;
	// Compute C
	CS.QDDot_0.setZero();
	InverseDynamics (model, Q, QDot, CS.QDDot_0, CS.C);

	assert (CS.H.cols() == model.dof_count && CS.H.rows() == model.dof_count);

	// Compute H
	CompositeRigidBodyAlgorithm (model, Q, CS.H, false);
	
	// Compute G
	unsigned int i,j;

	// variables to check whether we need to recompute G
	unsigned int prev_body_id = 0;
	Vector3d prev_body_point = Vector3d::Zero();
	MatrixNd Gi (3, model.dof_count);

	for (i = 0; i < CS.size(); i++) {
		// Only alow contact normals along the coordinate axes
		unsigned int axis_index = 0;

		if (CS.normal[i] == Vector3d(1., 0., 0.))
			axis_index = 0;
		else if (CS.normal[i] == Vector3d(0., 1., 0.))
			axis_index = 1;
		else if (CS.normal[i] == Vector3d(0., 0., 1.))
			axis_index = 2;
		else
			assert (0 && "Invalid contact normal axis!");

		// only compute the matrix Gi if actually needed
		if (prev_body_id != CS.body[i] || prev_body_point != CS.point[i]) {
			CalcPointJacobian (model, Q, CS.body[i], CS.point[i], Gi, false);
			prev_body_id = CS.body[i];
			prev_body_point = CS.point[i];
		}

		for (j = 0; j < model.dof_count; j++) {
			CS.G(i,j) = Gi(axis_index, j);
		}
	}

	// Compute gamma
	prev_body_id = 0;
	prev_body_point = Vector3d::Zero();
	Vector3d gamma_i = Vector3d::Zero();

	// update Kinematics just once
	UpdateKinematics (model, Q, QDot, CS.QDDot_0);

	for (i = 0; i < CS.size(); i++) {
		// Only alow contact normals along the coordinate axes
		unsigned int axis_index = 0;

		if (CS.normal[i] == Vector3d(1., 0., 0.))
			axis_index = 0;
		else if (CS.normal[i] == Vector3d(0., 1., 0.))
			axis_index = 1;
		else if (CS.normal[i] == Vector3d(0., 0., 1.))
			axis_index = 2;
		else
			assert (0 && "Invalid contact normal axis!");

		// only compute point accelerations when necessary
		if (prev_body_id != CS.body[i] || prev_body_point != CS.point[i]) {
			gamma_i = CalcPointAcceleration (model, Q, QDot, CS.QDDot_0, CS.body[i], CS.point[i], false);
			prev_body_id = CS.body[i];
			prev_body_point = CS.point[i];
		}
	
		// we also substract ContactData[i].acceleration such that the contact
		// point will have the desired acceleration
		CS.gamma[i] = gamma_i[axis_index] - CS.constraint_acceleration[i];
	}
	
	// Build the system
	CS.A.setZero();
	CS.b.setZero();
	CS.x.setZero();

	// Build the system: Copy H
	for (i = 0; i < model.dof_count; i++) {
		for (j = 0; j < model.dof_count; j++) {
			CS.A(i,j) = CS.H(i,j);	
		}
	}

	// Build the system: Copy G, and G^T
	for (i = 0; i < CS.size(); i++) {
		for (j = 0; j < model.dof_count; j++) {
			CS.A(i + model.dof_count, j) = CS.G (i,j);
			CS.A(j, i + model.dof_count) = CS.G (i,j);
		}
	}

	// Build the system: Copy -C + \tau
	for (i = 0; i < model.dof_count; i++) {
		CS.b[i] = -CS.C[i] + Tau[i];
	}

	// Build the system: Copy -gamma
	for (i = 0; i < CS.size(); i++) {
		CS.b[i + model.dof_count] = - CS.gamma[i];
	}

	LOG << "A = " << std::endl << CS.A << std::endl;
	LOG << "b = " << std::endl << CS.b << std::endl;

#ifndef RBDL_USE_SIMPLE_MATH
	switch (CS.linear_solver) {
		case (LinearSolverPartialPivLU) :
			CS.x = CS.A.partialPivLu().solve(CS.b);
			break;
		case (LinearSolverColPivHouseholderQR) :
			CS.x = CS.A.colPivHouseholderQr().solve(CS.b);
			break;
		default:
			LOG << "Error: Invalid linear solver: " << CS.linear_solver << std::endl;
			assert (0);
			break;
	}
#else
	bool solve_successful = LinSolveGaussElimPivot (CS.A, CS.b, CS.x);
	assert (solve_successful);
#endif

	LOG << "x = " << std::endl << CS.x << std::endl;

	// Copy back QDDot
	for (i = 0; i < model.dof_count; i++)
		QDDot[i] = CS.x[i];

	// Copy back contact forces
	for (i = 0; i < CS.size(); i++) {
		CS.constraint_force[i] = -CS.x[model.dof_count + i];
	}
}

void ComputeContactImpulsesLagrangian (
		Model &model,
		const VectorNd &Q,
		const VectorNd &QDotMinus,
		ConstraintSet &CS,
		VectorNd &QDotPlus
		) {
	LOG << "-------- " << __func__ << " --------" << std::endl;

	// Compute H
	UpdateKinematicsCustom (model, &Q, NULL, NULL);
	CompositeRigidBodyAlgorithm (model, Q, CS.H, false);

	unsigned int i,j;

	// variables to check whether we need to recompute G
	unsigned int prev_body_id = 0;
	Vector3d prev_body_point = Vector3d::Zero();
	MatrixNd Gi (3, model.dof_count);

	for (i = 0; i < CS.size(); i++) {
		// Only alow contact normals along the coordinate axes
		unsigned int axis_index = 0;

		if (CS.normal[i] == Vector3d(1., 0., 0.))
			axis_index = 0;
		else if (CS.normal[i] == Vector3d(0., 1., 0.))
			axis_index = 1;
		else if (CS.normal[i] == Vector3d(0., 0., 1.))
			axis_index = 2;
		else
			assert (0 && "Invalid contact normal axis!");

		// only compute the matrix Gi if actually needed
		if (prev_body_id != CS.body[i] || prev_body_point != CS.point[i]) {
			CalcPointJacobian (model, Q, CS.body[i], CS.point[i], Gi, false);
			prev_body_id = CS.body[i];
			prev_body_point = CS.point[i];
		}

		for (j = 0; j < model.dof_count; j++) {
			CS.G(i,j) = Gi(axis_index, j);
		}
	}

	// Compute H * \dot{q}^-
	VectorNd Hqdotminus (CS.H * QDotMinus);

	// Build the system
	CS.A.setZero();
	CS.b.setZero();
	CS.x.setZero();

	// Build the system: Copy H
	for (i = 0; i < model.dof_count; i++) {
		for (j = 0; j < model.dof_count; j++) {
			CS.A(i,j) = CS.H(i,j);	
		}
	}

	// Build the system: Copy G, and G^T
	for (i = 0; i < CS.size(); i++) {
		for (j = 0; j < model.dof_count; j++) {
			CS.A(i + model.dof_count, j) = CS.G (i,j);
			CS.A(j, i + model.dof_count) = CS.G (i,j);
		}
	}

	// Build the system: Copy -C + \tau
	for (i = 0; i < model.dof_count; i++) {
		CS.b[i] = Hqdotminus[i];
	}

	// Build the system: Copy -gamma
	for (i = 0; i < CS.size(); i++) {
		CS.b[i + model.dof_count] = CS.constraint_acceleration[i];
	}

#ifndef RBDL_USE_SIMPLE_MATH
	switch (CS.linear_solver) {
		case (LinearSolverPartialPivLU) :
			CS.x = CS.A.partialPivLu().solve(CS.b);
			break;
		case (LinearSolverColPivHouseholderQR) :
			CS.x = CS.A.colPivHouseholderQr().solve(CS.b);
			break;
		default:
			LOG << "Error: Invalid linear solver: " << CS.linear_solver << std::endl;
			assert (0);
			break;
	}
#else
	bool solve_successful = LinSolveGaussElimPivot (CS.A, CS.b, CS.x);
	assert (solve_successful);
#endif

	// Copy back QDDot
	for (i = 0; i < model.dof_count; i++)
		QDotPlus[i] = CS.x[i];

	// Copy back contact impulses
	for (i = 0; i < CS.size(); i++) {
		CS.constraint_impulse[i] = -CS.x[model.dof_count + i];
	}
}

/** \brief Compute only the effects of external forces on the generalized accelerations
 *
 * This function is a reduced version of ForwardDynamics() which only
 * computes the effects of the external forces on the generalized
 * accelerations.
 *
 */
void ForwardDynamicsApplyConstraintForces (
		Model &model,
		const VectorNd &Tau,
		ConstraintSet &CS,
		VectorNd &QDDot
		) {
	LOG << "-------- " << __func__ << " --------" << std::endl;

	assert (QDDot.size() == model.dof_count);

	unsigned int i;

	for (i = 1; i < model.mBodies.size(); i++) {
		CS.d_pA[i] = crossf(model.v[i], model.mBodies[i].mSpatialInertia * model.v[i]);
		CS.d_IA[i] = model.mBodies[i].mSpatialInertia;

		if (CS.f_ext_constraints[i] != SpatialVectorZero) {
			CS.d_pA[i] -= model.X_base[i].applyAdjoint ((CS.f_ext_constraints)[i]);
//			LOG << "f_t (local)[" << i << "] = " << spatial_adjoint(model.X_base[i]) * (*f_ext)[i] << std::endl;
		}
//		LOG << "i = " << i << " d_p[i] = " << d_p[i].transpose() << std::endl;
	}

	for (i = model.mBodies.size() - 1; i > 0; i--) {
		CS.d_U[i] = CS.d_IA[i] * model.S[i];
		CS.d_d[i] = model.S[i].dot(model.U[i]);
		CS.d_u[i] = Tau[i - 1] - model.S[i].dot(CS.d_pA[i]);

		unsigned int lambda = model.lambda[i];
		if (lambda != 0) {
			SpatialMatrix Ia = CS.d_IA[i] - CS.d_U[i] * (CS.d_U[i] / CS.d_d[i]).transpose();
			SpatialVector pa = CS.d_pA[i] + Ia * model.c[i] + CS.d_U[i] * CS.d_u[i] / CS.d_d[i];

#ifdef EIGEN_CORE_H
			CS.d_IA[lambda].noalias() += model.X_lambda[i].toMatrixTranspose() * Ia * model.X_lambda[i].toMatrix();
			CS.d_pA[lambda].noalias() += model.X_lambda[i].applyTranspose(pa);
#else
			CS.d_IA[lambda] += model.X_lambda[i].toMatrixTranspose() * Ia * model.X_lambda[i].toMatrix();
			CS.d_pA[lambda] += model.X_lambda[i].applyTranspose(pa);
#endif
		}
	}

	/*
	for (i = 0; i < model.mBodies.size(); i++) {
		LOG << "i = " << i << ": d_IA[i] " << std::endl << d_IA[i] << std::endl;
	}
	*/

	for (unsigned int i = 0; i < CS.f_ext_constraints.size(); i++) {
		LOG << "f_ext[" << i << "] = " << (CS.f_ext_constraints)[i].transpose();
	}

	for (i = 0; i < model.mBodies.size(); i++) {
		LOG << "i = " << i << ": d_pA[i] - pA[i] " << (CS.d_pA[i] - model.pA[i]).transpose();
	}
	for (i = 0; i < model.mBodies.size(); i++) {
		LOG << "i = " << i << ": d_u[i] - u[i] = " << (CS.d_u[i] - model.u[i]) << std::endl;
	}
	for (i = 0; i < model.mBodies.size(); i++) {
		LOG << "i = " << i << ": d_d[i] - d[i] = " << (CS.d_d[i] - model.d[i]) << std::endl;
	}
	for (i = 0; i < model.mBodies.size(); i++) {
		LOG << "i = " << i << ": d_U[i] - U[i] = " << (CS.d_U[i] - model.U[i]).transpose() << std::endl;
	}

	SpatialVector spatial_gravity (0., 0., 0., model.gravity[0], model.gravity[1], model.gravity[2]);

	for (i = 1; i < model.mBodies.size(); i++) {
		unsigned int lambda = model.lambda[i];
		SpatialTransform X_lambda = model.X_lambda[i];

		if (lambda == 0) {
			CS.d_a[i] = X_lambda.apply(spatial_gravity * (-1.)) + model.c[i];
		} else {
			CS.d_a[i] = X_lambda.apply(CS.d_a[lambda]) + model.c[i];
		}

		QDDot[i - 1] = (CS.d_u[i] - model.U[i].dot(CS.d_a[i])) / model.d[i];
		LOG << "QDDot_t[" << i - 1 << "] = " << QDDot[i - 1] << std::endl;
		CS.d_a[i] = CS.d_a[i] + model.S[i] * QDDot[i - 1];
		LOG << "d_a[i] - a[i] = " << (CS.d_a[i] - X_lambda.apply(model.a[i])).transpose() << std::endl;
	}
}

/** \brief Computes the effect of external forces on the generalized accelerations.
 *
 * This function is essentially similar to ForwardDynamics() except that it
 * tries to only perform computations of variables that change due to
 * external forces defined in f_t.
 */
void ForwardDynamicsAccelerationDeltas (
		Model &model,
		ConstraintSet &CS,
		VectorNd &QDDot_t,
		const unsigned int body_id,
		const std::vector<SpatialVector> &f_t
		) {
	LOG << "-------- " << __func__ << " ------" << std::endl;

	assert (CS.d_pA.size() == model.mBodies.size());
	assert (CS.d_a.size() == model.mBodies.size());
	assert (CS.d_u.size() == model.mBodies.size());

	// TODO reset all values (debug)
	for (unsigned int i = 0; i < model.mBodies.size(); i++) {
		CS.d_pA[i].setZero();
		CS.d_a[i].setZero();
		CS.d_u[i] = 0.;
	}

	for (unsigned int i = body_id; i > 0; i--) {
		if (i == body_id) {
			CS.d_pA[i] = -model.X_base[i].applyAdjoint(f_t[i]);
		}

		CS.d_u[i] = - model.S[i].dot(CS.d_pA[i]);

		unsigned int lambda = model.lambda[i];
		if (lambda != 0) {
			CS.d_pA[lambda] = CS.d_pA[lambda] + model.X_lambda[i].applyTranspose (CS.d_pA[i] + model.U[i] * CS.d_u[i] / model.d[i]);
		}
	}

	for (unsigned int i = 0; i < f_t.size(); i++) {
		LOG << "f_t[" << i << "] = " << f_t[i].transpose();
	}

	for (unsigned int i = 0; i < model.mBodies.size(); i++) {
		LOG << "i = " << i << ": d_pA[i] " << CS.d_pA[i].transpose();
	}
	for (unsigned int i = 0; i < model.mBodies.size(); i++) {
		LOG << "i = " << i << ": d_u[i] = " << CS.d_u[i] << std::endl;
	}

	QDDot_t[0] = 0.;
	CS.d_a[0] = model.a[0];

	for (unsigned int i = 1; i < model.mBodies.size(); i++) {
		unsigned int lambda = model.lambda[i];

		SpatialVector Xa = model.X_lambda[i].apply(CS.d_a[lambda]);
		QDDot_t[i - 1] = (CS.d_u[i] - model.U[i].dot(Xa) ) / model.d[i];
		CS.d_a[i] = Xa + model.S[i] * QDDot_t[i - 1];

		LOG << "QDDot_t[" << i - 1 << "] = " << QDDot_t[i - 1] << std::endl;
		LOG << "d_a[i] = " << CS.d_a[i].transpose() << std::endl;
	}
}

inline void set_zero (std::vector<SpatialVector> &spatial_values) {
	for (unsigned int i = 0; i < spatial_values.size(); i++)
		spatial_values[i].setZero();
}

void ForwardDynamicsContacts (
		Model &model,
		const VectorNd &Q,
		const VectorNd &QDot,
		const VectorNd &Tau,
		ConstraintSet &CS,
		VectorNd &QDDot
		) {
	LOG << "-------- " << __func__ << " ------" << std::endl;

	assert (CS.f_ext_constraints.size() == model.mBodies.size());
	assert (CS.QDDot_0.size() == model.dof_count);
	assert (CS.QDDot_t.size() == model.dof_count);
	assert (CS.f_t.size() == CS.size());
	assert (CS.point_accel_0.size() == CS.size());
	assert (CS.K.rows() == CS.size());
	assert (CS.K.cols() == CS.size());
	assert (CS.constraint_force.size() == CS.size());
	assert (CS.a.size() == CS.size());

	Vector3d point_accel_t;

	unsigned int ci = 0;
	
	// The default acceleration only needs to be computed once
	{
		SUPPRESS_LOGGING;
		ForwardDynamics (model, Q, QDot, Tau, CS.QDDot_0);
	}

	LOG << "=== Initial Loop Start ===" << std::endl;
	// we have to compute the standard accelerations first as we use them to
	// compute the effects of each test force
	for (ci = 0; ci < CS.size(); ci++) {
		unsigned int body_id = CS.body[ci];
		Vector3d point = CS.point[ci];
		Vector3d normal = CS.normal[ci];
		double acceleration = CS.constraint_acceleration[ci];

		LOG << "body_id = " << body_id << std::endl;
		LOG << "point = " << point << std::endl;
		LOG << "normal = " << normal << std::endl;
		LOG << "QDDot_0 = " << CS.QDDot_0.transpose() << std::endl;
		{
			SUPPRESS_LOGGING;
			UpdateKinematicsCustom (model, NULL, NULL, &CS.QDDot_0);
			CS.point_accel_0[ci] = CalcPointAcceleration (model, Q, QDot, CS.QDDot_0, body_id, point, false);

			CS.a[ci] = - acceleration + normal.dot(CS.point_accel_0[ci]);
		}
		LOG << "point_accel_0 = " << CS.point_accel_0[ci].transpose();
	}

	// Now we can compute and apply the test forces and use their net effect
	// to compute the inverse articlated inertia to fill K.
	for (ci = 0; ci < CS.size(); ci++) {
		LOG << "=== Testforce Loop Start ===" << std::endl;
		unsigned int body_id = CS.body[ci];
		Vector3d point = CS.point[ci];
		Vector3d normal = CS.normal[ci];

		// assemble the test force
		LOG << "normal = " << normal.transpose() << std::endl;

		Vector3d point_global = CalcBodyToBaseCoordinates (model, Q, body_id, point, false);
		LOG << "point_global = " << point_global.transpose() << std::endl;

		CS.f_t[ci].set (0., 0., 0., -normal[0], -normal[1], -normal[2]);
		CS.f_t[ci] = spatial_adjoint(Xtrans_mat(-point_global)) * CS.f_t[ci];
		CS.f_ext_constraints[body_id] = CS.f_t[ci];
		LOG << "f_t[" << body_id << "] = " << CS.f_t[ci].transpose() << std::endl;

		{
//			SUPPRESS_LOGGING;
			ForwardDynamicsAccelerationDeltas (model, CS, CS.QDDot_t, body_id, CS.f_ext_constraints);
			LOG << "QDDot_0 = " << CS.QDDot_0.transpose() << std::endl;
			LOG << "QDDot_t = " << (CS.QDDot_t + CS.QDDot_0).transpose() << std::endl;
			LOG << "QDDot_t - QDDot_0= " << (CS.QDDot_t).transpose() << std::endl;
		}
		CS.f_ext_constraints[body_id].setZero();

		CS.QDDot_t += CS.QDDot_0;

		// compute the resulting acceleration
		{
			SUPPRESS_LOGGING;
			UpdateKinematicsCustom (model, NULL, NULL, &CS.QDDot_t);
		}

		for (unsigned int cj = 0; cj < CS.size(); cj++) {
			{
				SUPPRESS_LOGGING;

				point_accel_t = CalcPointAcceleration (model, Q, QDot, CS.QDDot_t, CS.body[cj], CS.point[cj], false);
			}
	
			LOG << "point_accel_0  = " << CS.point_accel_0[ci].transpose() << std::endl;
			CS.K(ci,cj) = CS.normal[cj].dot(point_accel_t - CS.point_accel_0[cj]);
			LOG << "point_accel_t = " << point_accel_t.transpose() << std::endl;
		}
	}

	LOG << "K = " << std::endl << CS.K << std::endl;
	LOG << "a = " << std::endl << CS.a << std::endl;

#ifndef RBDL_USE_SIMPLE_MATH
	switch (CS.linear_solver) {
		case (LinearSolverPartialPivLU) :
			CS.constraint_force = CS.K.partialPivLu().solve(CS.a);
			break;
		case (LinearSolverColPivHouseholderQR) :
			CS.constraint_force = CS.K.colPivHouseholderQr().solve(CS.a);
			break;
		default:
			LOG << "Error: Invalid linear solver: " << CS.linear_solver << std::endl;
			assert (0);
			break;
	}
#else
	bool solve_successful = LinSolveGaussElimPivot (CS.K, CS.a, CS.constraint_force);
	assert (solve_successful);
#endif

	LOG << "f = " << CS.constraint_force.transpose() << std::endl;

	for (ci = 0; ci < CS.size(); ci++) {
		unsigned int body_id = CS.body[ci];

		CS.f_ext_constraints[body_id] -= CS.f_t[ci] * CS.constraint_force[ci]; 
		LOG << "f_ext[" << body_id << "] = " << CS.f_ext_constraints[body_id].transpose() << std::endl;
	}

	{
		SUPPRESS_LOGGING;
		ForwardDynamicsApplyConstraintForces (model, Tau, CS, QDDot);
	}
}

} /* namespace RigidBodyDynamics */