From 9c6a8ee4b48a1989c8d628868f8e77b680c64240 Mon Sep 17 00:00:00 2001 From: Guilhem Saurel <guilhem.saurel@gmail.com> Date: Tue, 26 Feb 2019 14:26:07 +0100 Subject: [PATCH] [Test] Standardization --- .gitlab-ci.yml | 6 +---- CMakeLists.txt | 6 ++++- Dockerfile | 6 ----- unittest/CMakeLists.txt | 8 +++++++ unittest/test_all.py | 21 ---------------- unittest/test_load.py | 12 +++++++--- unittest/unittest_utils.py | 49 +++++++++++++++++++------------------- 7 files changed, 47 insertions(+), 61 deletions(-) delete mode 100644 Dockerfile create mode 100644 unittest/CMakeLists.txt delete mode 100644 unittest/test_all.py mode change 100644 => 100755 unittest/test_load.py diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 2a4326f..830ed8f 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -1,5 +1 @@ -image: gepgitlab.laas.fr:4567/Gepetto/example-robot-data - -test: - script: - - cd unittest && python test_all.py +include: http://rainboard.laas.fr/project/example-robot-data/.gitlab-ci.yml diff --git a/CMakeLists.txt b/CMakeLists.txt index 6a8dc46..20c089d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,15 +1,19 @@ CMAKE_MINIMUM_REQUIRED(VERSION 2.8) INCLUDE(cmake/base.cmake) +INCLUDE(cmake/test.cmake) +SET(PROJECT_NAMESPACE gepetto) SET(PROJECT_NAME example-robot-data) SET(PROJECT_DESCRIPTION "Set of robot URDFs for benchmarking and developed examples.") -SET(PROJECT_URL https://gepgitlab.laas.fr/gepetto/${PROJECT_NAME}) +SET(PROJECT_URL https://gepgitlab.laas.fr/${PROJECT_NAMESPACE}/${PROJECT_NAME}) SETUP_PROJECT() INSTALL(DIRECTORY hyq DESTINATION share/${PROJECT_NAME}) INSTALL(DIRECTORY talos DESTINATION share/${PROJECT_NAME}) +ADD_SUBDIRECTORY(unittest) + SETUP_PROJECT_FINALIZE() diff --git a/Dockerfile b/Dockerfile deleted file mode 100644 index 772a81b..0000000 --- a/Dockerfile +++ /dev/null @@ -1,6 +0,0 @@ -FROM gepgitlab.laas.fr:4567/gepetto/buildfarm/robotpkg-jrl:16.04 - -RUN apt-get update -qqy \ - && apt-get install -qqy \ - robotpkg-py27-pinocchio \ - && rm -rf /var/lib/apt/lists/* diff --git a/unittest/CMakeLists.txt b/unittest/CMakeLists.txt new file mode 100644 index 0000000..82b9b30 --- /dev/null +++ b/unittest/CMakeLists.txt @@ -0,0 +1,8 @@ +SET(${PROJECT_NAME}_PYTHON_TESTS + load + ) + +FOREACH(TEST ${${PROJECT_NAME}_PYTHON_TESTS}) + ADD_PYTHON_UNIT_TEST("py-${TEST}" "unittest/test_${TEST}.py") +ENDFOREACH(TEST ${${PROJECT_NAME}_PYTHON_TESTS}) + diff --git a/unittest/test_all.py b/unittest/test_all.py deleted file mode 100644 index 02564ce..0000000 --- a/unittest/test_all.py +++ /dev/null @@ -1,21 +0,0 @@ -import unittest -import sys - -testmodules = [ - 'test_load', -] - -suite = unittest.TestSuite() - -for t in testmodules: - try: - # If the module defines a suite() function, call it to get the suite. - mod = __import__(t, globals(), locals(), ['suite']) - suitefn = getattr(mod, 'suite') - suite.addTest(suitefn()) - except (ImportError, AttributeError): - # else, just load all the test cases from the module. - suite.addTest(unittest.defaultTestLoader.loadTestsFromName(t)) - -result = unittest.TextTestRunner().run(suite) -sys.exit(len(result.errors) + len(result.failures)) diff --git a/unittest/test_load.py b/unittest/test_load.py old mode 100644 new mode 100755 index 5e2a02d..af6ca01 --- a/unittest/test_load.py +++ b/unittest/test_load.py @@ -1,6 +1,9 @@ -from unittest_utils import loadTalosArm, loadTalos, loadHyQ +#!/usr/bin/env python2 + import unittest +from unittest_utils import loadHyQ, loadTalos, loadTalosArm + class RobotTestCase(unittest.TestCase): ROBOT = None @@ -16,29 +19,32 @@ class RobotTestCase(unittest.TestCase): self.assertEqual(model.nv, self.NV, "Wrong nv value.") def test_q0(self): - self.assertTrue(hasattr(self.ROBOT, "q0"), "It doesn't have q0") + self.assertTrue(hasattr(self.ROBOT, "q0"), "It doesn't have q0") + class TalosArmTest(RobotTestCase): RobotTestCase.ROBOT = loadTalosArm() RobotTestCase.NQ = 7 RobotTestCase.NV = 7 + class TalosArmFloatingTest(RobotTestCase): RobotTestCase.ROBOT = loadTalosArm() RobotTestCase.NQ = 14 RobotTestCase.NV = 13 + class TalosTest(RobotTestCase): RobotTestCase.ROBOT = loadTalos() RobotTestCase.NQ = 39 RobotTestCase.NV = 38 + class HyQTest(RobotTestCase): RobotTestCase.ROBOT = loadHyQ() RobotTestCase.NQ = 19 RobotTestCase.NV = 18 - if __name__ == '__main__': unittest.main() diff --git a/unittest/unittest_utils.py b/unittest/unittest_utils.py index d6ec1c6..d6205b0 100644 --- a/unittest/unittest_utils.py +++ b/unittest/unittest_utils.py @@ -1,50 +1,50 @@ +import numpy as np + import pinocchio -from pinocchio.utils import * from pinocchio.robot_wrapper import RobotWrapper - def readParamsFromSrdf(robot, SRDF_PATH, verbose): - rmodel = robot.model - - pinocchio.loadRotorParameters(rmodel, SRDF_PATH, verbose) - rmodel.armature = \ - np.multiply(rmodel.rotorInertia.flat, np.square(rmodel.rotorGearRatio.flat)) - try: - pinocchio.loadReferenceConfigurations(rmodel, SRDF_PATH, verbose) - robot.q0.flat[:] = rmodel.referenceConfigurations["half_sitting"].copy() - except: - print "loadReferenceConfigurations did not work. Please check your Pinocchio Version" + rmodel = robot.model + + pinocchio.loadRotorParameters(rmodel, SRDF_PATH, verbose) + rmodel.armature = np.multiply(rmodel.rotorInertia.flat, np.square(rmodel.rotorGearRatio.flat)) try: - pinocchio.getNeutralConfiguration(rmodel, SRDF_PATH, verbose) - robot.q0.flat[:] = rmodel.neutralConfiguration.copy() + pinocchio.loadReferenceConfigurations(rmodel, SRDF_PATH, verbose) + robot.q0.flat[:] = rmodel.referenceConfigurations["half_sitting"].copy() except: - robot.q0.flat[:] = pinocchio.neutral(rmodel) - return - + print("loadReferenceConfigurations did not work. Please check your Pinocchio Version") + try: + pinocchio.getNeutralConfiguration(rmodel, SRDF_PATH, verbose) + robot.q0.flat[:] = rmodel.neutralConfiguration.copy() + except: + robot.q0.flat[:] = pinocchio.neutral(rmodel) + return + + def loadTalosArm(modelPath='/opt/openrobots/share/example-robot-data'): URDF_FILENAME = "talos_left_arm.urdf" URDF_SUBPATH = "/talos/" + URDF_FILENAME SRDF_FILENAME = "talos.srdf" SRDF_SUBPATH = "/talos/" + SRDF_FILENAME # Load URDF file - robot = RobotWrapper.BuildFromURDF(modelPath+URDF_SUBPATH, [modelPath]) + robot = RobotWrapper(modelPath + URDF_SUBPATH, [modelPath]) # Load SRDF file - readParamsFromSrdf(robot, modelPath+SRDF_SUBPATH, False) + readParamsFromSrdf(robot, modelPath + SRDF_SUBPATH, False) return robot + def loadTalos(modelPath='/opt/openrobots/share/example-robot-data'): URDF_FILENAME = "talos_reduced.urdf" SRDF_FILENAME = "talos.srdf" SRDF_SUBPATH = "/talos/" + SRDF_FILENAME URDF_SUBPATH = "/talos/" + URDF_FILENAME # 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 @@ -53,8 +53,7 @@ def loadHyQ(modelPath='/opt/openrobots/share/example-robot-data'): import os URDF_FILENAME = "hyq_no_sensors.urdf" URDF_SUBPATH = "/hyq/" + URDF_FILENAME - robot = RobotWrapper.BuildFromURDF(modelPath+URDF_SUBPATH, [modelPath], - pinocchio.JointModelFreeFlyer()) + robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath], pinocchio.JointModelFreeFlyer()) # TODO define default position inside srdf robot.q0.flat[7:] = [-0.2, 0.75, -1.5, -0.2, -0.75, 1.5, -0.2, 0.75, -1.5, -0.2, -0.75, 1.5] robot.q0[2] = 0.57750958 -- GitLab