@@ -47,10 +47,10 @@ void Device::integrateRollPitchYaw(ml::Vector& state, const ml::Vector& control,
47
47
jrlMathTools::Vector3D<double > omega;
48
48
// Translation part
49
49
for (unsigned int i=0 ; i<3 ; i++) {
50
- state (i) += control (i)*dt;
51
- ffPose_ (i,3 ) = state (i);
52
- omega (i) = control (i+3 );
53
- }
50
+ state (i) += control (i)*dt;
51
+ ffPose_ (i,3 ) = state (i);
52
+ omega (i) = control (i+3 );
53
+ }
54
54
// Rotation part
55
55
double roll = state (3 );
56
56
double pitch = state (4 );
@@ -73,20 +73,20 @@ void Device::integrateRollPitchYaw(ml::Vector& state, const ml::Vector& control,
73
73
// Apply Rodrigues (1795–1851) formula for rotation about omega vector
74
74
double angle = dt*omega.norm ();
75
75
if (angle == 0 ) {
76
- return ;
77
- }
76
+ return ;
77
+ }
78
78
jrlMathTools::Vector3D<double > k = omega/omega.norm ();
79
79
// ei <- ei cos(angle) + sin(angle)(k ^ ei) + (k.ei)(1-cos(angle))k
80
80
for (unsigned int i=0 ; i<3 ; i++) {
81
- jrlMathTools::Vector3D<double > ei = column[i];
82
- column[i] = ei*cos (angle) + (k^ei)*sin (angle) + k*((k*ei)*(1 -cos (angle)));
83
- }
81
+ jrlMathTools::Vector3D<double > ei = column[i];
82
+ column[i] = ei*cos (angle) + (k^ei)*sin (angle) + k*((k*ei)*(1 -cos (angle)));
83
+ }
84
84
// Store new position if ffPose_ member.
85
85
for (unsigned int r = 0 ; r < 3 ; r++) {
86
- for (unsigned int c = 0 ; c < 3 ; c++) {
87
- ffPose_ (r,c) = column[c](r);
88
- }
86
+ for (unsigned int c = 0 ; c < 3 ; c++) {
87
+ ffPose_ (r,c) = column[c](r);
89
88
}
89
+ }
90
90
const double & nx = column[2 ](2 );
91
91
const double & ny = column[1 ](2 );
92
92
@@ -106,16 +106,16 @@ Device::
106
106
~Device ( )
107
107
{
108
108
for ( unsigned int i=0 ; i<4 ; ++i ) {
109
- delete forcesSOUT[i];
110
- }
109
+ delete forcesSOUT[i];
110
+ }
111
111
}
112
112
113
113
Device::
114
114
Device ( const std::string& n )
115
115
:Entity(n)
116
116
,state_(6 )
117
117
,vel_controlInit_(false )
118
- ,secondOrderIntegration_( false )
118
+ ,controlInputType_(CONTROL_INPUT_VELOCITY )
119
119
,controlSIN( NULL ," Device(" +n+" )::input(double)::control" )
120
120
// ,attitudeSIN(NULL,"Device::input(matrixRot)::attitudeIN")
121
121
,attitudeSIN(NULL ," Device::input(vector3)::attitudeIN" )
@@ -196,6 +196,17 @@ Device( const std::string& n )
196
196
command::makeCommandVoid0 (*this ,&Device::setSecondOrderIntegration,
197
197
docstring));
198
198
199
+ /* SET of control input type. */
200
+ docstring =
201
+ " \n "
202
+ " Set the type of control input which can be \n "
203
+ " acceleration, velocity, or position\n "
204
+ " \n " ;
205
+
206
+ addCommand (" setControlInputType" ,
207
+ new command::Setter<Device,string>
208
+ (*this , &Device::setControlInputType, docstring));
209
+
199
210
// Handle commands and signals called in a synchronous way.
200
211
periodicCallBefore_.addSpecificCommands (*this , commandMap, " before." );
201
212
periodicCallAfter_.addSpecificCommands (*this , commandMap, " after." );
@@ -260,12 +271,25 @@ setRoot( const MatrixHomogeneous & worldMwaist )
260
271
void Device::
261
272
setSecondOrderIntegration ()
262
273
{
263
- secondOrderIntegration_ = true ;
274
+ controlInputType_ = CONTROL_INPUT_ACCELERATION ;
264
275
velocity_.resize (state_.size ());
265
276
velocity_.setZero ();
266
277
velocitySOUT.setConstant ( velocity_ );
267
278
}
268
279
280
+ void Device::
281
+ setControlInputType (const std::string& cit)
282
+ {
283
+ for (int i=0 ; i<CONTROL_INPUT_SIZE; i++)
284
+ if (cit==ControlInput_s[i])
285
+ {
286
+ controlInputType_ = (ControlInput)i;
287
+ sotDEBUG (25 )<<" Control input type: " <<ControlInput_s[i]<<endl;
288
+ return ;
289
+ }
290
+ sotDEBUG (25 )<<" Unrecognized control input type: " <<cit<<endl;
291
+ }
292
+
269
293
void Device::
270
294
increment ( const double & dt )
271
295
{
@@ -309,19 +333,19 @@ increment( const double & dt )
309
333
/* Position the signals corresponding to sensors. */
310
334
stateSOUT .setConstant ( state_ ); stateSOUT.setTime ( time+1 );
311
335
// computation of the velocity signal
312
- if ( secondOrderIntegration_ )
313
- {
314
- velocitySOUT.setConstant ( velocity_ );
315
- velocitySOUT.setTime ( time+1 );
316
- }
336
+ if ( controlInputType_==CONTROL_INPUT_ACCELERATION )
337
+ {
338
+ velocitySOUT.setConstant ( velocity_ );
339
+ velocitySOUT.setTime ( time+1 );
340
+ }
317
341
else
318
- {
319
- velocitySOUT.setConstant ( controlSIN.accessCopy () );
320
- velocitySOUT.setTime ( time+1 );
321
- }
342
+ {
343
+ velocitySOUT.setConstant ( controlSIN.accessCopy () );
344
+ velocitySOUT.setTime ( time+1 );
345
+ }
322
346
for ( int i=0 ;i<4 ;++i ){
323
- if ( !withForceSignals[i] ) forcesSOUT[i]->setConstant (forceZero6);
324
- }
347
+ if ( !withForceSignals[i] ) forcesSOUT[i]->setConstant (forceZero6);
348
+ }
325
349
ml::Vector zmp (3 ); zmp.fill ( .0 );
326
350
ZMPPreviousControllerSOUT .setConstant ( zmp );
327
351
@@ -359,12 +383,18 @@ void Device::integrate( const double & dt )
359
383
{
360
384
const ml::Vector & control = controlSIN.accessCopy ();
361
385
386
+ if (controlInputType_==CONTROL_INPUT_POSITION)
387
+ {
388
+ state_ = control;
389
+ return ;
390
+ }
391
+
362
392
if ( !vel_controlInit_ )
363
- {
364
- vel_control_ = ml::Vector (control.size ());
365
- vel_control_.setZero ();
366
- vel_controlInit_ = true ;
367
- }
393
+ {
394
+ vel_control_ = ml::Vector (control.size ());
395
+ vel_control_.setZero ();
396
+ vel_controlInit_ = true ;
397
+ }
368
398
369
399
// If control size is state size - 6, integrate joint angles,
370
400
// if control and state are of same size, integrate 6 first degrees of
@@ -373,27 +403,27 @@ void Device::integrate( const double & dt )
373
403
374
404
375
405
376
- if (secondOrderIntegration_)
406
+ if (controlInputType_==CONTROL_INPUT_ACCELERATION)
407
+ {
408
+ for ( unsigned int i=0 ;i<control.size ();++i )
377
409
{
378
- for ( unsigned int i=0 ;i<control.size ();++i )
379
- {
380
- if (control.size () == velocity_.size ()) offset = 0 ;
381
- vel_control_ (i) = velocity_ (i+offset) + control (i)*dt*0.5 ;
382
- velocity_ (i+offset) = velocity_ (i+offset) + control (i)*dt;
383
- }
410
+ if (control.size () == velocity_.size ()) offset = 0 ;
411
+ vel_control_ (i) = velocity_ (i+offset) + control (i)*dt*0.5 ;
412
+ velocity_ (i+offset) = velocity_ (i+offset) + control (i)*dt;
384
413
}
414
+ }
385
415
else
386
- {
387
- vel_control_ = control;
388
- }
416
+ {
417
+ vel_control_ = control;
418
+ }
389
419
390
420
if (vel_control_.size () == state_.size ()) {
391
- offset = 0 ;
392
- integrateRollPitchYaw (state_, vel_control_, dt);
393
- }
421
+ offset = 0 ;
422
+ integrateRollPitchYaw (state_, vel_control_, dt);
423
+ }
394
424
395
425
for ( unsigned int i=6 ;i<state_.size ();++i )
396
- { state_ (i) += (vel_control_ (i-offset)*dt); }
426
+ { state_ (i) += (vel_control_ (i-offset)*dt); }
397
427
}
398
428
399
429
/* --- DISPLAY ------------------------------------------------------------ */
0 commit comments