diff --git a/python/example_robot_data/robots_loader.py b/python/example_robot_data/robots_loader.py index 5678b8a186be4f42812ca10af4dd0e913e335fb6..91932c65eda82dfecb80d5a75371ea6aa8f2d73e 100644 --- a/python/example_robot_data/robots_loader.py +++ b/python/example_robot_data/robots_loader.py @@ -3,7 +3,6 @@ import warnings from os.path import dirname, exists, join import numpy as np - import pinocchio as pin from pinocchio.robot_wrapper import RobotWrapper @@ -222,7 +221,7 @@ def loadUR(robot=5, limited=False, gripper=False): def loadHector(): - return robot_loader('hector_description', "quadroto_base.urdf", free_flyer=True) + return robot_loader('hector_description', "quadrotor_base.urdf", free_flyer=True) def loadDoublePendulum(): diff --git a/unittest/test_load.py b/unittest/test_load.py index 3ac4760509e11d46a93467f482ea0435a275feec..0485b379602d99967c181ad2154c395a0af3d624 100755 --- a/unittest/test_load.py +++ b/unittest/test_load.py @@ -22,8 +22,8 @@ class RobotTestCase(unittest.TestCase): def test_double_pendulum(self): self.check('double_pendulum', 2, 2) - # def test_hector(self): - # self.check('hector', 0, 0) + def test_hector(self): + self.check('hector', 7, 6) def test_hyq(self): self.check('hyq', 19, 18)