@@ -42,15 +42,15 @@ const std::string Device::CLASS_NAME = "Device";
42
42
/* --------------------------------------------------------------------- */
43
43
44
44
void Device::integrateRollPitchYaw (ml::Vector& state, const ml::Vector& control,
45
- double dt)
45
+ double dt)
46
46
{
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,26 +73,26 @@ 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);
86
+ for (unsigned int c = 0 ; c < 3 ; c++) {
87
+ ffPose_ (r,c) = column[c](r);
88
+ }
88
89
}
89
- }
90
90
const double & nx = column[2 ](2 );
91
91
const double & ny = column[1 ](2 );
92
92
93
93
state (3 ) = atan2 (ny,nx);
94
94
state (4 ) = atan2 (-column[0 ](2 ),
95
- sqrt (ny*ny+nx*nx));
95
+ sqrt (ny*ny+nx*nx));
96
96
state (5 ) = atan2 (column[0 ](1 ),column[0 ](0 ));
97
97
98
98
}
@@ -106,8 +106,8 @@ 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::
@@ -117,7 +117,7 @@ Device( const std::string& n )
117
117
,vel_controlInit_(false )
118
118
,secondOrderIntegration_(false )
119
119
,controlSIN( NULL ," Device(" +n+" )::input(double)::control" )
120
- // ,attitudeSIN(NULL,"Device::input(matrixRot)::attitudeIN")
120
+ // ,attitudeSIN(NULL,"Device::input(matrixRot)::attitudeIN")
121
121
,attitudeSIN(NULL ," Device::input(vector3)::attitudeIN" )
122
122
,zmpSIN(NULL ," Device::input(vector3)::zmp" )
123
123
,stateSOUT( " Device(" +n+" )::output(vector)::state" )
@@ -127,24 +127,24 @@ Device( const std::string& n )
127
127
,previousControlSOUT( " Device(" +n+" )::output(vector)::previousControl" )
128
128
,motorcontrolSOUT( " Device(" +n+" )::output(vector)::motorcontrol" )
129
129
,ZMPPreviousControllerSOUT( " Device(" +n+" )::output(vector)::zmppreviouscontroller" ), ffPose_(),
130
- forceZero6 (6 )
130
+ forceZero6 (6 )
131
131
{
132
132
forceZero6.fill (0 );
133
133
/* --- SIGNALS --- */
134
134
for ( int i=0 ;i<4 ;++i ){ withForceSignals[i] = false ; }
135
135
forcesSOUT[0 ] =
136
- new Signal<ml::Vector, int >(" OpenHRP::output(vector6)::forceRLEG" );
136
+ new Signal<ml::Vector, int >(" OpenHRP::output(vector6)::forceRLEG" );
137
137
forcesSOUT[1 ] =
138
- new Signal<ml::Vector, int >(" OpenHRP::output(vector6)::forceLLEG" );
138
+ new Signal<ml::Vector, int >(" OpenHRP::output(vector6)::forceLLEG" );
139
139
forcesSOUT[2 ] =
140
- new Signal<ml::Vector, int >(" OpenHRP::output(vector6)::forceRARM" );
140
+ new Signal<ml::Vector, int >(" OpenHRP::output(vector6)::forceRARM" );
141
141
forcesSOUT[3 ] =
142
- new Signal<ml::Vector, int >(" OpenHRP::output(vector6)::forceLARM" );
142
+ new Signal<ml::Vector, int >(" OpenHRP::output(vector6)::forceLARM" );
143
143
144
144
signalRegistration ( controlSIN<<stateSOUT<<velocitySOUT<<attitudeSOUT
145
- <<attitudeSIN<<zmpSIN <<*forcesSOUT[0 ]<<*forcesSOUT[1 ]
146
- <<*forcesSOUT[2 ]<<*forcesSOUT[3 ] <<previousControlSOUT
147
- <<pseudoTorqueSOUT << motorcontrolSOUT << ZMPPreviousControllerSOUT );
145
+ <<attitudeSIN<<zmpSIN <<*forcesSOUT[0 ]<<*forcesSOUT[1 ]
146
+ <<*forcesSOUT[2 ]<<*forcesSOUT[3 ] <<previousControlSOUT
147
+ <<pseudoTorqueSOUT << motorcontrolSOUT << ZMPPreviousControllerSOUT );
148
148
state_.fill (.0 ); stateSOUT.setConstant ( state_ );
149
149
150
150
velocity_.resize (state_.size ()); velocity_.setZero ();
@@ -155,46 +155,46 @@ Device( const std::string& n )
155
155
std::string docstring;
156
156
/* Command setStateSize. */
157
157
docstring =
158
- " \n "
159
- " Set size of state vector\n "
160
- " \n " ;
158
+ " \n "
159
+ " Set size of state vector\n "
160
+ " \n " ;
161
161
addCommand (" resize" ,
162
- new command::Setter<Device, unsigned int >
163
- (*this , &Device::setStateSize, docstring));
162
+ new command::Setter<Device, unsigned int >
163
+ (*this , &Device::setStateSize, docstring));
164
164
docstring =
165
- " \n "
166
- " Set state vector value\n "
167
- " \n " ;
165
+ " \n "
166
+ " Set state vector value\n "
167
+ " \n " ;
168
168
addCommand (" set" ,
169
- new command::Setter<Device, Vector>
170
- (*this , &Device::setState, docstring));
169
+ new command::Setter<Device, Vector>
170
+ (*this , &Device::setState, docstring));
171
171
172
172
docstring =
173
- " \n "
174
- " Set velocity vector value\n "
175
- " \n " ;
173
+ " \n "
174
+ " Set velocity vector value\n "
175
+ " \n " ;
176
176
addCommand (" setVelocity" ,
177
- new command::Setter<Device, Vector>
178
- (*this , &Device::setVelocity, docstring));
177
+ new command::Setter<Device, Vector>
178
+ (*this , &Device::setVelocity, docstring));
179
179
180
180
void (Device::*setRootPtr)(const ml::Matrix&) = &Device::setRoot;
181
181
docstring
182
- = command::docCommandVoid1 (" Set the root position." ,
183
- " matrix homogeneous" );
182
+ = command::docCommandVoid1 (" Set the root position." ,
183
+ " matrix homogeneous" );
184
184
addCommand (" setRoot" ,
185
- command::makeCommandVoid1 (*this ,setRootPtr,
186
- docstring));
185
+ command::makeCommandVoid1 (*this ,setRootPtr,
186
+ docstring));
187
187
188
188
/* Second Order Integration set. */
189
189
docstring =
190
- " \n "
191
- " Set the position calculous starting from \n "
192
- " acceleration measure instead of velocity \n "
193
- " \n " ;
190
+ " \n "
191
+ " Set the position calculous starting from \n "
192
+ " acceleration measure instead of velocity \n "
193
+ " \n " ;
194
194
195
195
addCommand (" setSecondOrderIntegration" ,
196
- command::makeCommandVoid0 (*this ,&Device::setSecondOrderIntegration,
197
- docstring));
196
+ command::makeCommandVoid0 (*this ,&Device::setSecondOrderIntegration,
197
+ docstring));
198
198
199
199
// Handle commands and signals called in a synchronous way.
200
200
periodicCallBefore_.addSpecificCommands (*this , commandMap, " before." );
@@ -275,27 +275,27 @@ increment( const double & dt )
275
275
// Run Synchronous commands and evaluate signals outside the main
276
276
// connected component of the graph.
277
277
try
278
- {
279
- periodicCallBefore_.run (time+1 );
280
- }
278
+ {
279
+ periodicCallBefore_.run (time+1 );
280
+ }
281
281
catch (std::exception& e)
282
- {
283
- std::cerr
284
- << " exception caught while running periodical commands (before): "
285
- << e.what () << std::endl;
286
- }
282
+ {
283
+ std::cerr
284
+ << " exception caught while running periodical commands (before): "
285
+ << e.what () << std::endl;
286
+ }
287
287
catch (const char * str)
288
- {
289
- std::cerr
290
- << " exception caught while running periodical commands (before): "
291
- << str << std::endl;
292
- }
288
+ {
289
+ std::cerr
290
+ << " exception caught while running periodical commands (before): "
291
+ << str << std::endl;
292
+ }
293
293
catch (...)
294
- {
295
- std::cerr
296
- << " unknown exception caught while"
297
- << " running periodical commands (before)" << std::endl;
298
- }
294
+ {
295
+ std::cerr
296
+ << " unknown exception caught while"
297
+ << " running periodical commands (before)" << std::endl;
298
+ }
299
299
300
300
301
301
/* Force the recomputation of the control. */
@@ -308,7 +308,7 @@ increment( const double & dt )
308
308
309
309
/* Position the signals corresponding to sensors. */
310
310
stateSOUT .setConstant ( state_ ); stateSOUT.setTime ( time+1 );
311
- // computation of the velocity signal
311
+ // computation of the velocity signal
312
312
if ( secondOrderIntegration_ )
313
313
{
314
314
velocitySOUT.setConstant ( velocity_ );
@@ -320,35 +320,35 @@ increment( const double & dt )
320
320
velocitySOUT.setTime ( time+1 );
321
321
}
322
322
for ( int i=0 ;i<4 ;++i ){
323
- if ( !withForceSignals[i] ) forcesSOUT[i]->setConstant (forceZero6);
324
- }
323
+ if ( !withForceSignals[i] ) forcesSOUT[i]->setConstant (forceZero6);
324
+ }
325
325
ml::Vector zmp (3 ); zmp.fill ( .0 );
326
326
ZMPPreviousControllerSOUT .setConstant ( zmp );
327
327
328
328
// Run Synchronous commands and evaluate signals outside the main
329
329
// connected component of the graph.
330
330
try
331
- {
332
- periodicCallAfter_.run (time+1 );
333
- }
331
+ {
332
+ periodicCallAfter_.run (time+1 );
333
+ }
334
334
catch (std::exception& e)
335
- {
336
- std::cerr
337
- << " exception caught while running periodical commands (after): "
338
- << e.what () << std::endl;
339
- }
335
+ {
336
+ std::cerr
337
+ << " exception caught while running periodical commands (after): "
338
+ << e.what () << std::endl;
339
+ }
340
340
catch (const char * str)
341
- {
342
- std::cerr
343
- << " exception caught while running periodical commands (after): "
344
- << str << std::endl;
345
- }
341
+ {
342
+ std::cerr
343
+ << " exception caught while running periodical commands (after): "
344
+ << str << std::endl;
345
+ }
346
346
catch (...)
347
- {
348
- std::cerr
349
- << " unknown exception caught while"
350
- << " running periodical commands (after)" << std::endl;
351
- }
347
+ {
348
+ std::cerr
349
+ << " unknown exception caught while"
350
+ << " running periodical commands (after)" << std::endl;
351
+ }
352
352
353
353
354
354
// Others signals.
@@ -376,21 +376,21 @@ void Device::integrate( const double & dt )
376
376
if (secondOrderIntegration_)
377
377
{
378
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
- }
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
+ }
384
384
}
385
385
else
386
386
{
387
387
vel_control_ = control;
388
388
}
389
389
390
390
if (vel_control_.size () == state_.size ()) {
391
- offset = 0 ;
392
- integrateRollPitchYaw (state_, vel_control_, dt);
393
- }
391
+ offset = 0 ;
392
+ integrateRollPitchYaw (state_, vel_control_, dt);
393
+ }
394
394
395
395
for ( unsigned int i=6 ;i<state_.size ();++i )
396
396
{ state_ (i) += (vel_control_ (i-offset)*dt); }
0 commit comments