1212)
1313
1414
15- class RobotWrapper ( object ) :
15+ class RobotWrapper :
1616 @staticmethod
1717 def BuildFromURDF (
1818 filename , package_dirs = None , root_joint = None , verbose = False , meshLoader = None
@@ -160,13 +160,16 @@ def centroidalMomentum(self, q, v):
160160
161161 def centroidalMap (self , q ):
162162 """
163- Computes the centroidal momentum matrix which maps from the joint velocity vector to the centroidal momentum expressed around the center of mass.
163+ Computes the centroidal momentum matrix which maps from the joint velocity
164+ vector to the centroidal momentum expressed around the center of mass.
164165 """
165166 return pin .computeCentroidalMap (self .model , self .data , q )
166167
167168 def centroidal (self , q , v ):
168169 """
169- Computes all the quantities related to the centroidal dynamics (hg, Ag and Ig), corresponding to the centroidal momentum, the centroidal map and the centroidal rigid inertia.
170+ Computes all the quantities related to the centroidal dynamics (hg, Ag and Ig),
171+ corresponding to the centroidal momentum, the centroidal map and the centroidal
172+ rigid inertia.
170173 """
171174 pin .ccrba (self .model , self .data , q , v )
172175 return (self .data .hg , self .data .Ag , self .data .Ig )
@@ -350,15 +353,16 @@ def buildReducedRobot(self, list_of_joints_to_lock, reference_configuration=None
350353
351354 def getFrameJacobian (self , frame_id , rf_frame = pin .ReferenceFrame .LOCAL ):
352355 """
353- It computes the Jacobian of frame given by its id (frame_id) either expressed in the
354- local coordinate frame or in the world coordinate frame.
356+ It computes the Jacobian of frame given by its id (frame_id) either expressed in
357+ the local coordinate frame or in the world coordinate frame.
355358 """
356359 return pin .getFrameJacobian (self .model , self .data , frame_id , rf_frame )
357360
358361 def computeFrameJacobian (self , q , frame_id ):
359362 """
360363 Similar to getFrameJacobian but does not need pin.computeJointJacobians and
361- pin.updateFramePlacements to update internal value of self.data related to frames.
364+ pin.updateFramePlacements to update internal value of self.data related to
365+ frames.
362366 """
363367 return pin .computeFrameJacobian (self .model , self .data , q , frame_id )
364368
@@ -396,8 +400,10 @@ def viewer(self):
396400 return self .viz .viewer
397401
398402 def setVisualizer (self , visualizer , init = True , copy_models = False ):
399- """Set the visualizer. If init is True, the visualizer is initialized with this wrapper's models.
400- If copy_models is also True, the models are copied. Otherwise, they are simply kept as a reference.
403+ """
404+ Set the visualizer. If init is True, the visualizer is initialized with this
405+ wrapper's models. If copy_models is also True, the models are copied.
406+ Otherwise, they are simply kept as a reference.
401407 """
402408 if init :
403409 visualizer .__init__ (
@@ -406,7 +412,10 @@ def setVisualizer(self, visualizer, init=True, copy_models=False):
406412 self .viz = visualizer
407413
408414 def getViewerNodeName (self , geometry_object , geometry_type ):
409- """For each geometry object, returns the corresponding name of the node in the display."""
415+ """
416+ For each geometry object, returns the corresponding name of the node in the
417+ display.
418+ """
410419 return self .viz .getViewerNodeName (geometry_object , geometry_type )
411420
412421 def initViewer (self , share_data = True , * args , ** kwargs ):
@@ -437,7 +446,9 @@ def loadViewerModel(self, *args, **kwargs):
437446 self .viz .loadViewerModel (* args , ** kwargs )
438447
439448 def display (self , q ):
440- """Display the robot at configuration q in the viewer by placing all the bodies."""
449+ """
450+ Display the robot at configuration q in the viewer by placing all the bodies.
451+ """
441452 self .viz .display (q )
442453
443454 def displayCollisions (self , visibility ):
0 commit comments