From be1a995b9683a9989755c9a5be8676d82a4589bc Mon Sep 17 00:00:00 2001
From: Carlos Mastalli <carlos.mastalli@gmail.com>
Date: Tue, 16 Apr 2019 17:49:58 +0200
Subject: [PATCH] [format] Fixed format issues

---
 python/display.py          |  6 +++---
 unittest/test_load.py      |  4 +++-
 unittest/unittest_utils.py | 40 ++++++++++++++++++--------------------
 3 files changed, 25 insertions(+), 25 deletions(-)

diff --git a/python/display.py b/python/display.py
index e91de54..7039f7d 100644
--- a/python/display.py
+++ b/python/display.py
@@ -1,7 +1,8 @@
 import sys
-sys.path.append('/opt/openrobots/share/example-robot-data/unittest/')
-from unittest_utils import loadHyQ, loadTalos, loadTalosArm, loadTiago, loadTiagoNoHand, loadICub
 
+from unittest_utils import loadHyQ, loadICub, loadTalos, loadTalosArm, loadTiago, loadTiagoNoHand
+
+sys.path.append('/opt/openrobots/share/example-robot-data/unittest/')
 
 DISPLAY_HYQ = 'hyq' in sys.argv
 DISPLAY_TALOS = 'talos' in sys.argv
@@ -39,4 +40,3 @@ if DISPLAY_ICUB:
     icub = loadICub()
     icub.initDisplay(loadModel=True)
     icub.display(icub.q0)
-
diff --git a/unittest/test_load.py b/unittest/test_load.py
index e2c5d9d..3bd17d0 100755
--- a/unittest/test_load.py
+++ b/unittest/test_load.py
@@ -2,7 +2,7 @@
 
 import unittest
 
-from unittest_utils import loadHyQ, loadTalos, loadTalosArm, loadTiago, loadTiagoNoHand, loadICub
+from unittest_utils import loadHyQ, loadICub, loadTalos, loadTalosArm, loadTiago, loadTiagoNoHand
 
 
 class RobotTestCase(unittest.TestCase):
@@ -57,10 +57,12 @@ class TiagoNoHandTest(RobotTestCase):
     RobotTestCase.NQ = 14
     RobotTestCase.NV = 12
 
+
 class ICubTest(RobotTestCase):
     RobotTestCase.ROBOT = loadICub()
     RobotTestCase.NQ = 39
     RobotTestCase.NV = 38
 
+
 if __name__ == '__main__':
     unittest.main()
diff --git a/unittest/unittest_utils.py b/unittest/unittest_utils.py
index 50563fd..440c8be 100644
--- a/unittest/unittest_utils.py
+++ b/unittest/unittest_utils.py
@@ -1,7 +1,6 @@
 from os.path import exists, join
 
 import numpy as np
-
 import pinocchio
 from pinocchio.robot_wrapper import RobotWrapper
 
@@ -28,6 +27,7 @@ def readParamsFromSrdf(robot, SRDF_PATH, verbose):
     except:
         print "loadReferenceConfigurations did not work. Please check your \
             Pinocchio Version"
+
         try:
             pinocchio.getNeutralConfiguration(rmodel, SRDF_PATH, verbose)
             robot.q0.flat[:] = rmodel.neutralConfiguration.copy()
@@ -43,10 +43,10 @@ def loadTalosArm():
     SRDF_SUBPATH = "/talos_data/srdf/" + SRDF_FILENAME
     modelPath = getModelPath(URDF_SUBPATH)
     # Load URDF file
-    robot = RobotWrapper.BuildFromURDF(modelPath+URDF_SUBPATH, [modelPath])
+    robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath])
 
     # Load SRDF file
-    readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
+    readParamsFromSrdf(robot, modelPath + SRDF_SUBPATH, False)
     return robot
 
 
@@ -57,11 +57,10 @@ def loadTalos():
     URDF_SUBPATH = "/talos_data/robots/" + URDF_FILENAME
     modelPath = getModelPath(URDF_SUBPATH)
     # Load URDF file
-    robot = RobotWrapper.BuildFromURDF(modelPath+URDF_SUBPATH, [modelPath],
-                                       pinocchio.JointModelFreeFlyer())
+    robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath], pinocchio.JointModelFreeFlyer())
     # Load SRDF file
-    readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
-    assert((robot.model.armature[:6] == 0.).all())
+    readParamsFromSrdf(robot, modelPath + SRDF_SUBPATH, False)
+    assert ((robot.model.armature[:6] == 0.).all())
     return robot
 
 
@@ -72,38 +71,38 @@ def loadHyQ():
     URDF_SUBPATH = "/hyq_description/robots/" + URDF_FILENAME
     modelPath = getModelPath(URDF_SUBPATH)
     # Load URDF file
-    robot = RobotWrapper.BuildFromURDF(modelPath+URDF_SUBPATH, [modelPath],
-                                       pinocchio.JointModelFreeFlyer())
+    robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath], pinocchio.JointModelFreeFlyer())
     # Load SRDF file
-    readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
+    readParamsFromSrdf(robot, modelPath + SRDF_SUBPATH, False)
     return robot
 
 
 def loadTiago():
     URDF_FILENAME = "tiago.urdf"
-#    SRDF_FILENAME = "tiago.srdf"
-#    SRDF_SUBPATH = "/tiago_description/srdf/" + SRDF_FILENAME
+    #    SRDF_FILENAME = "tiago.srdf"
+    #    SRDF_SUBPATH = "/tiago_description/srdf/" + SRDF_FILENAME
     URDF_SUBPATH = "/tiago_description/robots/" + URDF_FILENAME
     modelPath = getModelPath(URDF_SUBPATH)
     # Load URDF file
-    robot = RobotWrapper.BuildFromURDF(modelPath+URDF_SUBPATH, [modelPath])
+    robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath])
     # Load SRDF file
-#    readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
+    #    readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
     return robot
 
 
 def loadTiagoNoHand():
     URDF_FILENAME = "tiago_no_hand.urdf"
-#    SRDF_FILENAME = "tiago.srdf"
-#    SRDF_SUBPATH = "/tiago_description/srdf/" + SRDF_FILENAME
+    #    SRDF_FILENAME = "tiago.srdf"
+    #    SRDF_SUBPATH = "/tiago_description/srdf/" + SRDF_FILENAME
     URDF_SUBPATH = "/tiago_description/robots/" + URDF_FILENAME
     modelPath = getModelPath(URDF_SUBPATH)
     # Load URDF file
-    robot = RobotWrapper.BuildFromURDF(modelPath+URDF_SUBPATH, [modelPath])
+    robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath])
     # Load SRDF file
-#    readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
+    #    readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
     return robot
 
+
 def loadICub(reduced=True):
     if reduced:
         URDF_FILENAME = "icub_reduced.urdf"
@@ -114,8 +113,7 @@ def loadICub(reduced=True):
     URDF_SUBPATH = "/icub_description/robots/" + URDF_FILENAME
     modelPath = getModelPath(URDF_SUBPATH)
     # Load URDF file
-    robot = RobotWrapper.BuildFromURDF(modelPath+URDF_SUBPATH, [modelPath],
-                                       pinocchio.JointModelFreeFlyer())
+    robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath], pinocchio.JointModelFreeFlyer())
     # Load SRDF file
-    readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False)
+    readParamsFromSrdf(robot, modelPath + SRDF_SUBPATH, False)
     return robot
-- 
GitLab