@@ -273,9 +273,8 @@ def initializeRobot(self):
273273 """
274274 self .halfSitting = pinocchio .neutral (self .pinocchioModel )
275275 self .defineHalfSitting (self .halfSitting )
276- self .halfSitting = numpy .array (self .halfSitting [:3 ].tolist ()
277- + [0. , 0. , 0. ] # Replace quaternion by RPY.
278- + self .halfSitting [7 :].tolist ())
276+ self .halfSitting = numpy .array (self .halfSitting [:3 ].tolist () + [0. , 0. , 0. ] # Replace quaternion by RPY.
277+ + self .halfSitting [7 :].tolist ())
279278 assert self .halfSitting .shape [0 ] == self .dynamic .getDimension ()
280279
281280 # Set the device limits.
@@ -287,9 +286,9 @@ def opposite(v):
287286 return [- x for x in v ]
288287
289288 self .dynamic .add_signals ()
290- self .device .setPositionBounds ( get (self .dynamic .lowerJl ), get (self .dynamic .upperJl ))
289+ self .device .setPositionBounds (get (self .dynamic .lowerJl ), get (self .dynamic .upperJl ))
291290 self .device .setVelocityBounds (- get (self .dynamic .upperVl ), get (self .dynamic .upperVl ))
292- self .device .setTorqueBounds (- get (self .dynamic .upperTl ), get (self .dynamic .upperTl ))
291+ self .device .setTorqueBounds (- get (self .dynamic .upperTl ), get (self .dynamic .upperTl ))
293292
294293 # Freeflyer reference frame should be the same as global
295294 # frame so that operational point positions correspond to
@@ -303,7 +302,9 @@ def opposite(v):
303302 plug (self .device .state , self .velocityDerivator .sin )
304303 plug (self .velocityDerivator .sout , self .dynamic .velocity )
305304 else :
306- self .dynamic .velocity .value = numpy .zeros ([self .dimension ,])
305+ self .dynamic .velocity .value = numpy .zeros ([
306+ self .dimension ,
307+ ])
307308
308309 if self .enableAccelerationDerivator :
309310 self .accelerationDerivator = \
@@ -312,7 +313,9 @@ def opposite(v):
312313 plug (self .velocityDerivator .sout , self .accelerationDerivator .sin )
313314 plug (self .accelerationDerivator .sout , self .dynamic .acceleration )
314315 else :
315- self .dynamic .acceleration .value = numpy .zeros ([self .dimension ,])
316+ self .dynamic .acceleration .value = numpy .zeros ([
317+ self .dimension ,
318+ ])
316319
317320 def addTrace (self , entityName , signalName ):
318321 if self .tracer :
0 commit comments