Skip to content
Snippets Groups Projects
Commit e93a65ed authored by Guilhem Saurel's avatar Guilhem Saurel
Browse files

[Python] factorize loadTalosArm

parent 671d31f2
No related branches found
No related tags found
No related merge requests found
......@@ -88,12 +88,8 @@ def loadANYmal(withArm=None):
free_flyer=True)
def loadTalosArm():
return robot_loader('talos_data', "talos_left_arm.urdf", "talos.srdf")
def loadTalos(legs=False):
URDF_FILENAME = "talos_reduced.urdf"
def loadTalos(legs=False, arm=False):
URDF_FILENAME = "talos_left_arm.urdf" if arm else "talos_reduced.urdf"
SRDF_FILENAME = "talos.srdf"
robot = robot_loader('talos_data', URDF_FILENAME, SRDF_FILENAME, free_flyer=True)
......@@ -164,6 +160,11 @@ def loadTalosLegs():
return loadTalos(legs=True)
def loadTalosArm():
warnings.warn("`loadTalosArm()` is deprecated. Please use `loadTalos(arm=True)`", DeprecationWarning, 2)
return loadTalos(arm=True)
def loadHyQ():
return robot_loader('hyq_description', "hyq_no_sensors.urdf", "hyq.srdf", ref_posture="standing", free_flyer=True)
......
......@@ -48,13 +48,13 @@ class TalosTest(RobotTestCase):
class TalosArmTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadTalosArm()
RobotTestCase.ROBOT = example_robot_data.loadTalos(arm=True)
RobotTestCase.NQ = 7
RobotTestCase.NV = 7
class TalosArmFloatingTest(RobotTestCase):
RobotTestCase.ROBOT = example_robot_data.loadTalosArm()
RobotTestCase.ROBOT = example_robot_data.loadTalos(arm=True)
RobotTestCase.NQ = 14
RobotTestCase.NV = 13
......
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