Skip to content

Commit 1cbd53b

Browse files
Fix the formatting using GNU code style
1 parent c7f33d1 commit 1cbd53b

File tree

2 files changed

+107
-107
lines changed

2 files changed

+107
-107
lines changed

include/sot/core/device.hh

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -43,20 +43,20 @@ namespace dynamicgraph {
4343
/* --------------------------------------------------------------------- */
4444

4545
class SOT_CORE_EXPORT Device
46-
:public Entity
46+
:public Entity
4747
{
4848
public:
4949
static const std::string CLASS_NAME;
5050
virtual const std::string& getClassName(void) const {
51-
return CLASS_NAME;
51+
return CLASS_NAME;
5252
}
5353

5454
enum ForceSignalSource
5555
{
56-
FORCE_SIGNAL_RLEG,
57-
FORCE_SIGNAL_LLEG,
58-
FORCE_SIGNAL_RARM,
59-
FORCE_SIGNAL_LARM
56+
FORCE_SIGNAL_RLEG,
57+
FORCE_SIGNAL_LLEG,
58+
FORCE_SIGNAL_RARM,
59+
FORCE_SIGNAL_LARM
6060
};
6161

6262
protected:
@@ -85,8 +85,8 @@ namespace dynamicgraph {
8585
public: /* --- DISPLAY --- */
8686
virtual void display(std::ostream& os) const;
8787
SOT_CORE_EXPORT friend std::ostream&
88-
operator<<(std::ostream& os,const Device& r) {
89-
r.display(os); return os;
88+
operator<<(std::ostream& os,const Device& r) {
89+
r.display(os); return os;
9090
}
9191

9292
public: /* --- SIGNALS --- */
@@ -110,11 +110,11 @@ namespace dynamicgraph {
110110

111111
public: /* --- COMMANDS --- */
112112
void commandLine(const std::string&, std::istringstream&,
113-
std::ostream&){}
113+
std::ostream&){}
114114
protected:
115115
/// Compute roll pitch yaw angles of freeflyer joint.
116116
void integrateRollPitchYaw(ml::Vector& state, const ml::Vector& control,
117-
double dt);
117+
double dt);
118118
/// Store Position of free flyer joint
119119
MatrixHomogeneous ffPose_;
120120
/// Compute the new position, from the current control.

src/tools/device.cpp

Lines changed: 97 additions & 97 deletions
Original file line numberDiff line numberDiff line change
@@ -42,15 +42,15 @@ const std::string Device::CLASS_NAME = "Device";
4242
/* --------------------------------------------------------------------- */
4343

4444
void Device::integrateRollPitchYaw(ml::Vector& state, const ml::Vector& control,
45-
double dt)
45+
double dt)
4646
{
4747
jrlMathTools::Vector3D<double> omega;
4848
// Translation part
4949
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+
}
5454
// Rotation part
5555
double roll = state(3);
5656
double pitch = state(4);
@@ -73,26 +73,26 @@ void Device::integrateRollPitchYaw(ml::Vector& state, const ml::Vector& control,
7373
// Apply Rodrigues (1795–1851) formula for rotation about omega vector
7474
double angle = dt*omega.norm();
7575
if (angle == 0) {
76-
return;
77-
}
76+
return;
77+
}
7878
jrlMathTools::Vector3D<double> k = omega/omega.norm();
7979
// ei <- ei cos(angle) + sin(angle)(k ^ ei) + (k.ei)(1-cos(angle))k
8080
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+
}
8484
// Store new position if ffPose_ member.
8585
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+
}
8889
}
89-
}
9090
const double & nx = column[2](2);
9191
const double & ny = column[1](2);
9292

9393
state(3) = atan2(ny,nx);
9494
state(4) = atan2(-column[0](2),
95-
sqrt(ny*ny+nx*nx));
95+
sqrt(ny*ny+nx*nx));
9696
state(5) = atan2(column[0](1),column[0](0));
9797

9898
}
@@ -106,8 +106,8 @@ Device::
106106
~Device( )
107107
{
108108
for( unsigned int i=0; i<4; ++i ) {
109-
delete forcesSOUT[i];
110-
}
109+
delete forcesSOUT[i];
110+
}
111111
}
112112

113113
Device::
@@ -117,7 +117,7 @@ Device( const std::string& n )
117117
,vel_controlInit_(false)
118118
,secondOrderIntegration_(false)
119119
,controlSIN( NULL,"Device("+n+")::input(double)::control" )
120-
//,attitudeSIN(NULL,"Device::input(matrixRot)::attitudeIN")
120+
//,attitudeSIN(NULL,"Device::input(matrixRot)::attitudeIN")
121121
,attitudeSIN(NULL,"Device::input(vector3)::attitudeIN")
122122
,zmpSIN(NULL,"Device::input(vector3)::zmp")
123123
,stateSOUT( "Device("+n+")::output(vector)::state" )
@@ -127,24 +127,24 @@ Device( const std::string& n )
127127
,previousControlSOUT( "Device("+n+")::output(vector)::previousControl" )
128128
,motorcontrolSOUT( "Device("+n+")::output(vector)::motorcontrol" )
129129
,ZMPPreviousControllerSOUT( "Device("+n+")::output(vector)::zmppreviouscontroller" ), ffPose_(),
130-
forceZero6 (6)
130+
forceZero6 (6)
131131
{
132132
forceZero6.fill (0);
133133
/* --- SIGNALS --- */
134134
for( int i=0;i<4;++i ){ withForceSignals[i] = false; }
135135
forcesSOUT[0] =
136-
new Signal<ml::Vector, int>("OpenHRP::output(vector6)::forceRLEG");
136+
new Signal<ml::Vector, int>("OpenHRP::output(vector6)::forceRLEG");
137137
forcesSOUT[1] =
138-
new Signal<ml::Vector, int>("OpenHRP::output(vector6)::forceLLEG");
138+
new Signal<ml::Vector, int>("OpenHRP::output(vector6)::forceLLEG");
139139
forcesSOUT[2] =
140-
new Signal<ml::Vector, int>("OpenHRP::output(vector6)::forceRARM");
140+
new Signal<ml::Vector, int>("OpenHRP::output(vector6)::forceRARM");
141141
forcesSOUT[3] =
142-
new Signal<ml::Vector, int>("OpenHRP::output(vector6)::forceLARM");
142+
new Signal<ml::Vector, int>("OpenHRP::output(vector6)::forceLARM");
143143

144144
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 );
148148
state_.fill(.0); stateSOUT.setConstant( state_ );
149149

150150
velocity_.resize(state_.size()); velocity_.setZero();
@@ -155,46 +155,46 @@ Device( const std::string& n )
155155
std::string docstring;
156156
/* Command setStateSize. */
157157
docstring =
158-
"\n"
159-
" Set size of state vector\n"
160-
"\n";
158+
"\n"
159+
" Set size of state vector\n"
160+
"\n";
161161
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));
164164
docstring =
165-
"\n"
166-
" Set state vector value\n"
167-
"\n";
165+
"\n"
166+
" Set state vector value\n"
167+
"\n";
168168
addCommand("set",
169-
new command::Setter<Device, Vector>
170-
(*this, &Device::setState, docstring));
169+
new command::Setter<Device, Vector>
170+
(*this, &Device::setState, docstring));
171171

172172
docstring =
173-
"\n"
174-
" Set velocity vector value\n"
175-
"\n";
173+
"\n"
174+
" Set velocity vector value\n"
175+
"\n";
176176
addCommand("setVelocity",
177-
new command::Setter<Device, Vector>
178-
(*this, &Device::setVelocity, docstring));
177+
new command::Setter<Device, Vector>
178+
(*this, &Device::setVelocity, docstring));
179179

180180
void(Device::*setRootPtr)(const ml::Matrix&) = &Device::setRoot;
181181
docstring
182-
= command::docCommandVoid1("Set the root position.",
183-
"matrix homogeneous");
182+
= command::docCommandVoid1("Set the root position.",
183+
"matrix homogeneous");
184184
addCommand("setRoot",
185-
command::makeCommandVoid1(*this,setRootPtr,
186-
docstring));
185+
command::makeCommandVoid1(*this,setRootPtr,
186+
docstring));
187187

188188
/* Second Order Integration set. */
189189
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";
194194

195195
addCommand("setSecondOrderIntegration",
196-
command::makeCommandVoid0(*this,&Device::setSecondOrderIntegration,
197-
docstring));
196+
command::makeCommandVoid0(*this,&Device::setSecondOrderIntegration,
197+
docstring));
198198

199199
// Handle commands and signals called in a synchronous way.
200200
periodicCallBefore_.addSpecificCommands(*this, commandMap, "before.");
@@ -275,27 +275,27 @@ increment( const double & dt )
275275
// Run Synchronous commands and evaluate signals outside the main
276276
// connected component of the graph.
277277
try
278-
{
279-
periodicCallBefore_.run(time+1);
280-
}
278+
{
279+
periodicCallBefore_.run(time+1);
280+
}
281281
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+
}
287287
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+
}
293293
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+
}
299299

300300

301301
/* Force the recomputation of the control. */
@@ -308,7 +308,7 @@ increment( const double & dt )
308308

309309
/* Position the signals corresponding to sensors. */
310310
stateSOUT .setConstant( state_ ); stateSOUT.setTime( time+1 );
311-
//computation of the velocity signal
311+
//computation of the velocity signal
312312
if( secondOrderIntegration_ )
313313
{
314314
velocitySOUT.setConstant( velocity_ );
@@ -320,35 +320,35 @@ increment( const double & dt )
320320
velocitySOUT.setTime( time+1 );
321321
}
322322
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+
}
325325
ml::Vector zmp(3); zmp.fill( .0 );
326326
ZMPPreviousControllerSOUT .setConstant( zmp );
327327

328328
// Run Synchronous commands and evaluate signals outside the main
329329
// connected component of the graph.
330330
try
331-
{
332-
periodicCallAfter_.run(time+1);
333-
}
331+
{
332+
periodicCallAfter_.run(time+1);
333+
}
334334
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+
}
340340
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+
}
346346
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+
}
352352

353353

354354
// Others signals.
@@ -376,21 +376,21 @@ void Device::integrate( const double & dt )
376376
if (secondOrderIntegration_)
377377
{
378378
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+
}
384384
}
385385
else
386386
{
387387
vel_control_ = control;
388388
}
389389

390390
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+
}
394394

395395
for( unsigned int i=6;i<state_.size();++i )
396396
{ state_(i) += (vel_control_(i-offset)*dt); }

0 commit comments

Comments
 (0)