From 30494a407fa15b834bdd23048dd6e589bf3bac08 Mon Sep 17 00:00:00 2001
From: Guilhem Saurel <guilhem.saurel@laas.fr>
Date: Fri, 1 Apr 2022 09:27:58 +0200
Subject: [PATCH] remove deprecated loaders

---
 python/example_robot_data/__init__.py      |   4 +-
 python/example_robot_data/robots_loader.py | 145 ---------------------
 2 files changed, 1 insertion(+), 148 deletions(-)

diff --git a/python/example_robot_data/__init__.py b/python/example_robot_data/__init__.py
index fdddeb0..c3bcbca 100644
--- a/python/example_robot_data/__init__.py
+++ b/python/example_robot_data/__init__.py
@@ -1,4 +1,2 @@
 # flake8: noqa
-from .robots_loader import (ROBOTS, getModelPath, load, load_full, loadANYmal, loadDoublePendulum, loadHector, loadHyQ,
-                            loadICub, loadIris, loadKinova, loadPanda, loadRomeo, loadSolo, loadTalos, loadTalosArm,
-                            loadTalosLegs, loadTiago, loadTiagoNoHand, loadUR, readParamsFromSrdf)
+from .robots_loader import ROBOTS, getModelPath, load, load_full, readParamsFromSrdf
diff --git a/python/example_robot_data/robots_loader.py b/python/example_robot_data/robots_loader.py
index 15eabd6..8180690 100644
--- a/python/example_robot_data/robots_loader.py
+++ b/python/example_robot_data/robots_loader.py
@@ -9,10 +9,6 @@ from pinocchio.robot_wrapper import RobotWrapper
 pin.switchToNumpyArray()
 
 
-def _depr_msg(deprecated, key):
-    return "`%s` is deprecated. Please use `load('%s')`" % (deprecated, key)
-
-
 def getModelPath(subpath, printmsg=False):
     source = dirname(dirname(dirname(__file__)))  # top level source directory
     paths = [
@@ -165,16 +161,6 @@ class BaxterLoader(RobotLoader):
     urdf_subpath = "urdf"
 
 
-def loadANYmal(withArm=None):
-    if withArm:
-        warnings.warn(_depr_msg('loadANYmal(kinova)', 'anymal_kinova'), FutureWarning, 2)
-        loader = ANYmalKinovaLoader
-    else:
-        warnings.warn(_depr_msg('loadANYmal()', 'anymal'), FutureWarning, 2)
-        loader = ANYmalLoader
-    return loader().robot
-
-
 class CassieLoader(RobotLoader):
     path = 'cassie_description'
     if tuple(int(i) for i in pin.__version__.split('.')) > (2, 9, 1):
@@ -277,40 +263,6 @@ class TalosLegsLoader(TalosLoader):
         self.addFreeFlyerJointLimits()
 
 
-def loadTalos(legs=False, arm=False, full=False, box=False):
-    if legs:
-        warnings.warn(_depr_msg('loadTalos(legs)', 'talos_legs'), FutureWarning, 2)
-        loader = TalosLegsLoader
-    elif arm:
-        warnings.warn(_depr_msg('loadTalos(arm)', 'talos_arm'), FutureWarning, 2)
-        loader = TalosArmLoader
-    elif full:
-        if box:
-            warnings.warn(_depr_msg('loadTalos(full, box)', 'talos_full_box'), FutureWarning, 2)
-            loader = TalosFullBoxLoader
-        else:
-            warnings.warn(_depr_msg('loadTalos(full)', 'talos_full'), FutureWarning, 2)
-            loader = TalosFullLoader
-    else:
-        if box:
-            warnings.warn(_depr_msg('loadTalos(box)', 'talos_box'), FutureWarning, 2)
-            loader = TalosBoxLoader
-        else:
-            warnings.warn(_depr_msg('loadTalos()', 'talos'), FutureWarning, 2)
-            loader = TalosLoader
-    return loader().robot
-
-
-def loadTalosLegs():
-    warnings.warn(_depr_msg('loadTalosLegs()', 'talos_legs'), FutureWarning, 2)
-    return loadTalos(legs=True)
-
-
-def loadTalosArm():
-    warnings.warn(_depr_msg('loadTalosArm()', 'talos_arm'), FutureWarning, 2)
-    return loadTalos(arm=True)
-
-
 class HyQLoader(RobotLoader):
     path = "hyq_description"
     urdf_filename = "hyq_no_sensors.urdf"
@@ -319,11 +271,6 @@ class HyQLoader(RobotLoader):
     free_flyer = True
 
 
-def loadHyQ():
-    warnings.warn(_depr_msg('loadHyQ()', 'hyq'), FutureWarning, 2)
-    return HyQLoader().robot
-
-
 class BoltLoader(RobotLoader):
     path = 'bolt_description'
     urdf_filename = "bolt.urdf"
@@ -351,12 +298,6 @@ class Solo12Loader(Solo8Loader):
     urdf_filename = "solo12.urdf"
 
 
-def loadSolo(solo=True):
-    warnings.warn(_depr_msg('loadSolo()', 'solo8'), FutureWarning, 2)
-    loader = Solo8Loader if solo else Solo12Loader
-    return loader().robot
-
-
 class FingerEduLoader(RobotLoader):
     path = 'finger_edu_description'
     urdf_filename = "finger_edu.urdf"
@@ -372,11 +313,6 @@ class KinovaLoader(RobotLoader):
     ref_posture = "arm_up"
 
 
-def loadKinova():
-    warnings.warn(_depr_msg('loadKinova()', 'kinova'), FutureWarning, 2)
-    return KinovaLoader().robot
-
-
 class TiagoLoader(RobotLoader):
     path = "tiago_description"
     urdf_filename = "tiago.urdf"
@@ -390,21 +326,6 @@ class TiagoNoHandLoader(TiagoLoader):
     urdf_filename = "tiago_no_hand.urdf"
 
 
-def loadTiago(hand=True):
-    if hand:
-        warnings.warn(_depr_msg('loadTiago()', 'tiago'), FutureWarning, 2)
-        loader = TiagoLoader
-    else:
-        warnings.warn(_depr_msg('loadTiago(hand=False)', 'tiago_no_hand'), FutureWarning, 2)
-        loader = TiagoNoHandLoader
-    return loader().robot
-
-
-def loadTiagoNoHand():
-    warnings.warn(_depr_msg('loadTiagoNoHand()', 'tiago_no_hand'), FutureWarning, 2)
-    return loadTiago(hand=False)
-
-
 class ICubLoader(RobotLoader):
     path = "icub_description"
     urdf_filename = "icub.urdf"
@@ -416,27 +337,12 @@ class ICubReducedLoader(ICubLoader):
     urdf_filename = "icub_reduced.urdf"
 
 
-def loadICub(reduced=True):
-    if reduced:
-        warnings.warn(_depr_msg('loadICub()', 'icub_reduced'), FutureWarning, 2)
-        loader = ICubReducedLoader
-    else:
-        warnings.warn(_depr_msg('loadICub(reduced=False)', 'icub'), FutureWarning, 2)
-        loader = ICubLoader
-    return loader().robot
-
-
 class PandaLoader(RobotLoader):
     path = "panda_description"
     urdf_filename = "panda.urdf"
     urdf_subpath = "urdf"
 
 
-def loadPanda():
-    warnings.warn(_depr_msg('loadPanda()', 'panda'), FutureWarning, 2)
-    return PandaLoader().robot
-
-
 class UR3Loader(RobotLoader):
     path = "ur_description"
     urdf_filename = "ur3_robot.urdf"
@@ -475,48 +381,12 @@ class UR10LimitedLoader(UR10Loader):
     urdf_filename = "ur10_joint_limited_robot.urdf"
 
 
-def loadUR(robot=5, limited=False, gripper=False):
-    if robot == 3:
-        if limited:
-            warnings.warn(_depr_msg('loadUr(3, limited)', 'ur3_limited'), FutureWarning, 2)
-            loader = UR3LimitedLoader
-        elif gripper:
-            warnings.warn(_depr_msg('loadUr(3, gripper)', 'ur3_gripper'), FutureWarning, 2)
-            loader = UR3GripperLoader
-        else:
-            warnings.warn(_depr_msg('loadUr(3)', 'ur3'), FutureWarning, 2)
-            loader = UR3Loader
-    elif robot == 5:
-        if limited:
-            warnings.warn(_depr_msg('loadUr(limited)', 'ur5_limited'), FutureWarning, 2)
-            loader = UR5LimitedLoader
-        elif gripper:
-            warnings.warn(_depr_msg('loadUr(gripper)', 'ur5_gripper'), FutureWarning, 2)
-            loader = UR5GripperLoader
-        else:
-            warnings.warn(_depr_msg('loadUr()', 'ur5'), FutureWarning, 2)
-            loader = UR5Loader
-    elif robot == 10:
-        if limited:
-            warnings.warn(_depr_msg('loadUr(10, limited)', 'ur10_limited'), FutureWarning, 2)
-            loader = UR10LimitedLoader
-        else:
-            warnings.warn(_depr_msg('loadUr(10)', 'ur10'), FutureWarning, 2)
-            loader = UR10Loader
-    return loader().robot
-
-
 class HectorLoader(RobotLoader):
     path = "hector_description"
     urdf_filename = "quadrotor_base.urdf"
     free_flyer = True
 
 
-def loadHector():
-    warnings.warn(_depr_msg('loadHector()', 'hector'), FutureWarning, 2)
-    return HectorLoader().robot
-
-
 class DoublePendulumLoader(RobotLoader):
     path = "double_pendulum_description"
     urdf_filename = "double_pendulum.urdf"
@@ -531,11 +401,6 @@ class DoublePendulumSimpleLoader(DoublePendulumLoader):
     urdf_filename = "double_pendulum_simple.urdf"
 
 
-def loadDoublePendulum():
-    warnings.warn(_depr_msg('loadDoublePendulum()', 'double_pendulum'), FutureWarning, 2)
-    return DoublePendulumLoader().robot
-
-
 class RomeoLoader(RobotLoader):
     path = "romeo_description"
     urdf_filename = "romeo.urdf"
@@ -543,11 +408,6 @@ class RomeoLoader(RobotLoader):
     free_flyer = True
 
 
-def loadRomeo():
-    warnings.warn(_depr_msg('loadRomeo()', 'romeo'), FutureWarning, 2)
-    return RomeoLoader().robot
-
-
 class SimpleHumanoidLoader(RobotLoader):
     path = 'simple_humanoid_description'
     urdf_subpath = 'urdf'
@@ -567,11 +427,6 @@ class IrisLoader(RobotLoader):
     free_flyer = True
 
 
-def loadIris():
-    warnings.warn(_depr_msg('loadIris()', 'iris'), FutureWarning, 2)
-    return IrisLoader().robot
-
-
 ROBOTS = {
     'a1': A1Loader,
     'anymal': ANYmalLoader,
-- 
GitLab