Skip to content
Snippets Groups Projects
Unverified Commit a00409a3 authored by Guilhem Saurel's avatar Guilhem Saurel Committed by GitHub
Browse files

Merge pull request #43 from nim65s/devel

 [Python] add a load helper, and use it in main & tests
parents 43bfd22e 59e559ca
No related branches found
No related tags found
No related merge requests found
Pipeline #10436 passed
# flake8: noqa
from .robots_loader import (getModelPath, loadANYmal, loadDoublePendulum, loadHector, loadHyQ, loadICub, loadIris,
loadKinova, loadPanda, loadRomeo, loadSolo, loadTalos, loadTalosArm, loadTalosLegs,
loadTiago, loadTiagoNoHand, loadUR, readParamsFromSrdf)
from .robots_loader import (ROBOTS, getModelPath, load, loadANYmal, loadDoublePendulum, loadHector, loadHyQ, loadICub,
loadIris, loadKinova, loadPanda, loadRomeo, loadSolo, loadTalos, loadTalosArm,
loadTalosLegs, loadTiago, loadTiagoNoHand, loadUR, readParamsFromSrdf)
from argparse import ArgumentParser
import eigenpy
from .robots_loader import ROBOTS, load
from . import robots_loader
ROBOTS = sorted(ROBOTS.keys())
eigenpy.switchToNumpyMatrix()
ROBOTS = [
'anymal', 'anymal_kinova', 'hyq', 'solo', 'solo12', 'talos', 'talos_arm', 'talos_legs', 'kinova', 'tiago',
'tiago_no_hand', 'icub', 'ur5', 'romeo', 'hector', 'double_pendulum', 'iris', 'panda'
]
parser = ArgumentParser()
parser = ArgumentParser(description=load.__doc__)
parser.add_argument('robot', nargs='?', default=ROBOTS[0], choices=ROBOTS)
parser.add_argument('--no-display', action='store_false')
args = parser.parse_args()
if args.robot == 'anymal':
anymal = robots_loader.loadANYmal()
anymal.initViewer(loadModel=True)
anymal.display(anymal.q0)
elif args.robot == 'anymal_kinova':
anymal = robots_loader.loadANYmal(withArm='kinova')
anymal.initViewer(loadModel=True)
anymal.display(anymal.q0)
elif args.robot == 'hyq':
hyq = robots_loader.loadHyQ()
hyq.initViewer(loadModel=True)
hyq.display(hyq.q0)
elif args.robot == 'solo':
solo = robots_loader.loadSolo()
solo.initViewer(loadModel=True)
solo.display(solo.q0)
elif args.robot == 'solo12':
solo = robots_loader.loadSolo(False)
solo.initViewer(loadModel=True)
solo.display(solo.q0)
elif args.robot == 'talos':
talos = robots_loader.loadTalos()
talos.initViewer(loadModel=True)
talos.display(talos.q0)
elif args.robot == 'talos_arm':
talos_arm = robots_loader.loadTalosArm()
talos_arm.initViewer(loadModel=True)
talos_arm.display(talos_arm.q0)
elif args.robot == 'talos_legs':
talos_legs = robots_loader.loadTalosLegs()
talos_legs.initViewer(loadModel=True)
talos_legs.display(talos_legs.q0)
elif args.robot == 'kinova':
kinova = robots_loader.loadKinova()
kinova.initViewer(loadModel=True)
kinova.display(kinova.q0)
elif args.robot == 'tiago':
tiago = robots_loader.loadTiago()
tiago.initViewer(loadModel=True)
tiago.display(tiago.q0)
elif args.robot == 'tiago_no_hand':
tiago_no_hand = robots_loader.loadTiagoNoHand()
tiago_no_hand.initViewer(loadModel=True)
tiago_no_hand.display(tiago_no_hand.q0)
elif args.robot == 'icub':
icub = robots_loader.loadICub()
icub.initViewer(loadModel=True)
icub.display(icub.q0)
elif args.robot == 'ur5':
ur5 = robots_loader.loadUR()
ur5.initViewer(loadModel=True)
ur5.display(ur5.q0)
elif args.robot == 'romeo':
romeo = robots_loader.loadRomeo()
romeo.initViewer(loadModel=True)
romeo.display(romeo.q0)
if args.robot == 'hector':
hector = robots_loader.loadHector()
hector.initViewer(loadModel=True)
hector.display(hector.q0)
if args.robot == 'double_pendulum':
pendulum = robots_loader.loadDoublePendulum()
pendulum.initViewer(loadModel=True)
pendulum.display(pendulum.q0)
if args.robot == 'iris':
iris = robots_loader.loadIris()
iris.initViewer(loadModel=True)
iris.display(iris.q0)
if args.robot == 'panda':
panda = robots_loader.loadPanda()
panda.initViewer(loadModel=True)
panda.display(panda.q0)
load(args.robot, display=not args.no_display)
......@@ -227,3 +227,56 @@ def loadRomeo():
def loadIris():
return robot_loader('iris_description', "iris_simple.urdf", free_flyer=True)
ROBOTS = {
'anymal': (loadANYmal, {}),
'anymal_kinova': (loadANYmal, {
'withArm': 'kinova'
}),
'double_pendulum': (loadDoublePendulum, {}),
'hector': (loadHector, {}),
'hyq': (loadHyQ, {}),
'icub': (loadICub, {
'reduced': False
}),
'icub_reduced': (loadICub, {
'reduced': True
}),
'iris': (loadIris, {}),
'kinova': (loadKinova, {}),
'panda': (loadPanda, {}),
'romeo': (loadRomeo, {}),
'solo': (loadSolo, {}),
'solo12': (loadSolo, {
'solo': False
}),
'talos': (loadTalos, {}),
'talos_arm': (loadTalos, {
'arm': True
}),
'talos_legs': (loadTalos, {
'legs': True
}),
'tiago': (loadTiago, {}),
'tiago_no_hand': (loadTiago, {
'hand': False
}),
'ur5': (loadUR, {}),
'ur5_gripper': (loadUR, {
'gripper': True
}),
'ur5_limited': (loadUR, {
'limited': True
}),
}
def load(name, display=False):
"""Load a robot by its name, and optionnaly display it in a viewer."""
loader, kwargs = ROBOTS[name]
robot = loader(**kwargs)
if display:
robot.initViewer(loadModel=True)
robot.display(robot.q0)
return robot
#!/usr/bin/env python2
#!/usr/bin/env python
import sys
import unittest
import example_robot_data
from example_robot_data import load
class RobotTestCase(unittest.TestCase):
ROBOT = None
NQ = None
NV = None
def check(self, name, expected_nq, expected_nv):
"""Helper function for the real tests"""
robot = load(name, display=False)
self.assertEqual(robot.model.nq, expected_nq)
self.assertEqual(robot.model.nv, expected_nv)
self.assertTrue(hasattr(robot, "q0"))
def test_nq(self):
model = self.ROBOT.model
self.assertEqual(model.nq, self.NQ, "Wrong nq value.")
def test_anymal(self):
self.check('anymal', 19, 18)
def test_nv(self):
model = self.ROBOT.model
self.assertEqual(model.nv, self.NV, "Wrong nv value.")
def test_anymal_kinova(self):
self.check('anymal_kinova', 25, 24)
def test_q0(self):
self.assertTrue(hasattr(self.ROBOT, "q0"), "It doesn't have q0")
def test_double_pendulum(self):
self.check('double_pendulum', 2, 2)
# def test_hector(self):
# self.check('hector', 0, 0)
class ANYmalTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadANYmal()
RobotTestCase.NQ = 19
RobotTestCase.NV = 18
def test_hyq(self):
self.check('hyq', 19, 18)
def test_icub(self):
self.check('icub', 39, 38)
class ANYmalKinovaTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadANYmal(withArm="kinova")
RobotTestCase.NQ = 27
RobotTestCase.NV = 24
def test_icub_reduced(self):
self.check('icub_reduced', 36, 35)
def test_iris(self):
self.check('iris', 7, 6)
class HyQTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadHyQ()
RobotTestCase.NQ = 19
RobotTestCase.NV = 18
def test_kinova(self):
self.check('kinova', 9, 6)
def test_panda(self):
self.check('panda', 9, 9)
class TalosTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadTalos()
RobotTestCase.NQ = 39
RobotTestCase.NV = 38
def test_romeo(self):
self.check('romeo', 62, 61)
def test_solo(self):
self.check('solo', 15, 14)
class TalosArmTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadTalos(arm=True)
RobotTestCase.NQ = 7
RobotTestCase.NV = 7
def test_solo12(self):
self.check('solo12', 19, 18)
def test_talos(self):
self.check('talos', 39, 38)
class TalosArmFloatingTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadTalos(arm=True)
RobotTestCase.NQ = 14
RobotTestCase.NV = 13
def test_talos_arm(self):
self.check('talos_arm', 7, 7)
def test_talos_legs(self):
self.check('talos_legs', 19, 18)
class TalosLegsTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadTalos(legs=True)
RobotTestCase.NQ = 19
RobotTestCase.NV = 18
def test_tiago(self):
self.check('tiago', 50, 48)
def test_tiago_no_hand(self):
self.check('tiago_no_hand', 14, 12)
class ICubTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadICub(reduced=False)
RobotTestCase.NQ = 39
RobotTestCase.NV = 38
def test_ur5(self):
self.check('ur5', 6, 6)
def test_ur5_gripper(self):
self.check('ur5_gripper', 6, 6)
class SoloTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadSolo()
RobotTestCase.NQ = 15
RobotTestCase.NV = 14
class Solo12Test(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadSolo(False)
RobotTestCase.NQ = 19
RobotTestCase.NV = 18
class TiagoTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadTiago()
RobotTestCase.NQ = 50
RobotTestCase.NV = 48
class TiagoNoHandTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadTiago(hand=False)
RobotTestCase.NQ = 14
RobotTestCase.NV = 12
class UR5Test(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadUR()
RobotTestCase.NQ = 6
RobotTestCase.NV = 6
class UR5LimitedTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadUR(limited=True)
RobotTestCase.NQ = 6
RobotTestCase.NV = 6
class UR5GripperTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadUR(gripper=True)
RobotTestCase.NQ = 6
RobotTestCase.NV = 6
class KinovaTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadKinova()
RobotTestCase.NQ = 9
RobotTestCase.NV = 6
class RomeoTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadRomeo()
RobotTestCase.NQ = 62
RobotTestCase.NV = 61
class PandaTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadPanda()
RobotTestCase.NQ = 9
RobotTestCase.NV = 9
def test_ur5_limited(self):
self.check('ur5_limited', 6, 6)
if __name__ == '__main__':
test_classes_to_run = [
ANYmalTest, ANYmalKinovaTest, HyQTest, TalosTest, TalosArmTest, TalosArmFloatingTest, TalosLegsTest, ICubTest,
SoloTest, Solo12Test, TiagoTest, TiagoNoHandTest, UR5Test, UR5LimitedTest, UR5GripperTest, KinovaTest,
RomeoTest, PandaTest
]
loader = unittest.TestLoader()
suites_list = []
for test_class in test_classes_to_run:
suite = loader.loadTestsFromTestCase(test_class)
suites_list.append(suite)
big_suite = unittest.TestSuite(suites_list)
runner = unittest.TextTestRunner()
results = runner.run(big_suite)
sys.exit(not results.wasSuccessful())
unittest.main()
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment